PX4 Firmware
PX4 Autopilot Software http://px4.io
I2C.cpp
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * Copyright (c) 2012-2015 PX4 Development Team. All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions
7  * are met:
8  *
9  * 1. Redistributions of source code must retain the above copyright
10  * notice, this list of conditions and the following disclaimer.
11  * 2. Redistributions in binary form must reproduce the above copyright
12  * notice, this list of conditions and the following disclaimer in
13  * the documentation and/or other materials provided with the
14  * distribution.
15  * 3. Neither the name PX4 nor the names of its contributors may be
16  * used to endorse or promote products derived from this software
17  * without specific prior written permission.
18  *
19  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
20  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
21  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
22  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
23  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
24  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
25  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
26  * OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
27  * AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
28  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
29  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
30  * POSSIBILITY OF SUCH DAMAGE.
31  *
32  ****************************************************************************/
33 
34 /**
35  * @file i2c.cpp
36  *
37  * Base class for devices attached via the I2C bus.
38  *
39  * @todo Bus frequency changes; currently we do nothing with the value
40  * that is supplied. Should we just depend on the bus knowing?
41  */
42 
43 #include "I2C.hpp"
44 
45 #ifdef __PX4_LINUX
46 
47 #include <linux/i2c.h>
48 #include <linux/i2c-dev.h>
49 
50 namespace device
51 {
52 
53 I2C::I2C(const char *name, const char *devname, const int bus, const uint16_t address, const uint32_t frequency) :
54  CDev(name, devname)
55 {
56  DEVICE_DEBUG("I2C::I2C name = %s devname = %s", name, devname);
57  // fill in _device_id fields for a I2C device
58  _device_id.devid_s.bus_type = DeviceBusType_I2C;
59  _device_id.devid_s.bus = bus;
60  _device_id.devid_s.address = address;
61  // devtype needs to be filled in by the driver
62  _device_id.devid_s.devtype = 0;
63 }
64 
65 I2C::~I2C()
66 {
67  if (_fd >= 0) {
68  ::close(_fd);
69  _fd = -1;
70  }
71 }
72 
73 int
74 I2C::init()
75 {
76  // Assume the driver set the desired bus frequency. There is no standard
77  // way to set it from user space.
78 
79  // do base class init, which will create device node, etc
80  int ret = CDev::init();
81 
82  if (ret != PX4_OK) {
83  DEVICE_DEBUG("CDev::init failed");
84  return ret;
85  }
86 
87  // Open the actual I2C device
88  char dev_path[16];
89  snprintf(dev_path, sizeof(dev_path), "/dev/i2c-%i", get_device_bus());
90  _fd = ::open(dev_path, O_RDWR);
91 
92  if (_fd < 0) {
93  PX4_ERR("could not open %s", dev_path);
94  px4_errno = errno;
95  return PX4_ERROR;
96  }
97 
98  return ret;
99 }
100 
101 int
102 I2C::transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
103 {
104  struct i2c_msg msgv[2];
105  unsigned msgs;
106  int ret = PX4_ERROR;
107  unsigned retry_count = 0;
108 
109  if (_fd < 0) {
110  PX4_ERR("I2C device not opened");
111  return 1;
112  }
113 
114  do {
115  DEVICE_DEBUG("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
116  msgs = 0;
117 
118  if (send_len > 0) {
119  msgv[msgs].addr = get_device_address();
120  msgv[msgs].flags = 0;
121  msgv[msgs].buf = const_cast<uint8_t *>(send);
122  msgv[msgs].len = send_len;
123  msgs++;
124  }
125 
126  if (recv_len > 0) {
127  msgv[msgs].addr = get_device_address();
128  msgv[msgs].flags = I2C_M_READ;
129  msgv[msgs].buf = recv;
130  msgv[msgs].len = recv_len;
131  msgs++;
132  }
133 
134  if (msgs == 0) {
135  return -EINVAL;
136  }
137 
138  struct i2c_rdwr_ioctl_data packets;
139 
140  packets.msgs = msgv;
141 
142  packets.nmsgs = msgs;
143 
144  ret = ::ioctl(_fd, I2C_RDWR, (unsigned long)&packets);
145 
146  if (ret == -1) {
147  DEVICE_DEBUG("I2C transfer failed");
148  ret = PX4_ERROR;
149 
150  } else {
151  ret = PX4_OK;
152  }
153 
154  /* success */
155  if (ret == PX4_OK) {
156  break;
157  }
158 
159  } while (retry_count++ < _retries);
160 
161  return ret;
162 }
163 
164 } // namespace device
165 
166 #endif // __PX4_LINUX
int transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
Perform an I2C transaction to the device.
void * send(void *data)
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
virtual ~I2C()
void init()
Activates/configures the hardware registers.
int px4_errno
const char * name
Definition: tests_main.c:58
virtual int init() override
uint8_t _retries
The number of times a read or write operation will be retried on error.
Definition: I2C.hpp:79
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52