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 namespace device
46 {
47 /*
48  * N.B. By defaulting the value of _bus_clocks to non Zero
49  * All calls to init() will NOT set the buss frequency
50  */
51 
52 unsigned int I2C::_bus_clocks[BOARD_NUMBER_I2C_BUSES] = BOARD_I2C_BUS_CLOCK_INIT;
53 
54 I2C::I2C(const char *name, const char *devname, const int bus, const uint16_t address, const uint32_t frequency) :
55  CDev(name, devname),
56  _frequency(frequency)
57 {
58  DEVICE_DEBUG("I2C::I2C name = %s devname = %s", name, devname);
59  // fill in _device_id fields for a I2C device
60  _device_id.devid_s.bus_type = DeviceBusType_I2C;
61  _device_id.devid_s.bus = bus;
62  _device_id.devid_s.address = address;
63  // devtype needs to be filled in by the driver
64  _device_id.devid_s.devtype = 0;
65 }
66 
68 {
69  if (_dev) {
70  px4_i2cbus_uninitialize(_dev);
71  _dev = nullptr;
72  }
73 }
74 
75 int
76 I2C::set_bus_clock(unsigned bus, unsigned clock_hz)
77 {
78  int index = bus - 1;
79 
80  if (index < 0 || index >= static_cast<int>(sizeof(_bus_clocks) / sizeof(_bus_clocks[0]))) {
81  return -EINVAL;
82  }
83 
84  if (_bus_clocks[index] > 0) {
85  // DEVICE_DEBUG("overriding clock of %u with %u Hz\n", _bus_clocks[index], clock_hz);
86  }
87 
88  _bus_clocks[index] = clock_hz;
89 
90  return OK;
91 }
92 
93 int
94 I2C::init()
95 {
96  int ret = PX4_ERROR;
97  unsigned bus_index;
98 
99  // attach to the i2c bus
100  _dev = px4_i2cbus_initialize(get_device_bus());
101 
102  if (_dev == nullptr) {
103  DEVICE_DEBUG("failed to init I2C");
104  ret = -ENOENT;
105  goto out;
106  }
107 
108  // the above call fails for a non-existing bus index,
109  // so the index math here is safe.
110  bus_index = get_device_bus() - 1;
111 
112  // abort if the max frequency we allow (the frequency we ask)
113  // is smaller than the bus frequency
114  if (_bus_clocks[bus_index] > _frequency) {
115  (void)px4_i2cbus_uninitialize(_dev);
116  _dev = nullptr;
117  DEVICE_LOG("FAIL: too slow for bus #%u: %u KHz, device max: %u KHz)",
118  get_device_bus(), _bus_clocks[bus_index] / 1000, _frequency / 1000);
119  ret = -EINVAL;
120  goto out;
121  }
122 
123  // set frequency for this instance once to the bus speed
124  // the bus speed is the maximum supported by all devices on the bus,
125  // as we have to prioritize performance over compatibility.
126  // If a new device requires a lower clock speed, this has to be
127  // manually set via "fmu i2c <bus> <clock>" before starting any
128  // drivers.
129  // This is necessary as automatically lowering the bus speed
130  // for maximum compatibility could induce timing issues on
131  // critical sensors the adopter might be unaware of.
132 
133  // set the bus frequency on the first access if it has
134  // not been set yet
135  if (_bus_clocks[bus_index] == 0) {
136  _bus_clocks[bus_index] = _frequency;
137  }
138 
139  // call the probe function to check whether the device is present
140  ret = probe();
141 
142  if (ret != OK) {
143  DEVICE_DEBUG("probe failed");
144  goto out;
145  }
146 
147  // do base class init, which will create device node, etc
148  ret = CDev::init();
149 
150  if (ret != OK) {
151  DEVICE_DEBUG("cdev init failed");
152  goto out;
153  }
154 
155  // tell the world where we are
156  DEVICE_LOG("on I2C bus %d at 0x%02x (bus: %u KHz, max: %u KHz)",
157  get_device_bus(), get_device_address(), _bus_clocks[bus_index] / 1000, _frequency / 1000);
158 
159 out:
160 
161  if ((ret != OK) && (_dev != nullptr)) {
162  px4_i2cbus_uninitialize(_dev);
163  _dev = nullptr;
164  }
165 
166  return ret;
167 }
168 
169 int
170 I2C::transfer(const uint8_t *send, const unsigned send_len, uint8_t *recv, const unsigned recv_len)
171 {
172  px4_i2c_msg_t msgv[2];
173  unsigned msgs;
174  int ret = PX4_ERROR;
175  unsigned retry_count = 0;
176 
177  if (_dev == nullptr) {
178  PX4_ERR("I2C device not opened");
179  return 1;
180  }
181 
182  do {
183  DEVICE_DEBUG("transfer out %p/%u in %p/%u", send, send_len, recv, recv_len);
184  msgs = 0;
185 
186  if (send_len > 0) {
187  msgv[msgs].frequency = _bus_clocks[get_device_bus() - 1];
188  msgv[msgs].addr = get_device_address();
189  msgv[msgs].flags = 0;
190  msgv[msgs].buffer = const_cast<uint8_t *>(send);
191  msgv[msgs].length = send_len;
192  msgs++;
193  }
194 
195  if (recv_len > 0) {
196  msgv[msgs].frequency = _bus_clocks[get_device_bus() - 1];
197  msgv[msgs].addr = get_device_address();
198  msgv[msgs].flags = I2C_M_READ;
199  msgv[msgs].buffer = recv;
200  msgv[msgs].length = recv_len;
201  msgs++;
202  }
203 
204  if (msgs == 0) {
205  return -EINVAL;
206  }
207 
208  ret = I2C_TRANSFER(_dev, &msgv[0], msgs);
209 
210  /* success */
211  if (ret == PX4_OK) {
212  break;
213  }
214 
215  /* if we have already retried once, or we are going to give up, then reset the bus */
216  if ((retry_count >= 1) || (retry_count >= _retries)) {
217  I2C_RESET(_dev);
218  }
219 
220  } while (retry_count++ < _retries);
221 
222  return ret;
223 }
224 
225 } // namespace device
px4_i2c_dev_t * _dev
Definition: I2C.hpp:116
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)
static unsigned int _bus_clocks[BOARD_NUMBER_I2C_BUSES]
Definition: I2C.hpp:72
uint32_t _frequency
Definition: I2C.hpp:115
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
virtual int probe()
Check for the presence of the device on the bus.
Definition: I2C.hpp:96
virtual ~I2C()
void init()
Activates/configures the hardware registers.
#define DEVICE_LOG(FMT,...)
Definition: Device.hpp:51
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 OK
Definition: uavcan_main.cpp:71
static int set_bus_clock(unsigned bus, unsigned clock_hz)
Definition: I2C.cpp:76
#define DEVICE_DEBUG(FMT,...)
Definition: Device.hpp:52