APM:Libraries
I2CDevice.cpp
Go to the documentation of this file.
1 /*
2  * This file is free software: you can redistribute it and/or modify it
3  * under the terms of the GNU General Public License as published by the
4  * Free Software Foundation, either version 3 of the License, or
5  * (at your option) any later version.
6  *
7  * This file is distributed in the hope that it will be useful, but
8  * WITHOUT ANY WARRANTY; without even the implied warranty of
9  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10  * See the GNU General Public License for more details.
11  *
12  * You should have received a copy of the GNU General Public License along
13  * with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #include "I2CDevice.h"
16 
17 #include <AP_HAL/AP_HAL.h>
18 
19 #include "Util.h"
20 #include "Scheduler.h"
21 
22 namespace PX4 {
23 
25 pthread_mutex_t PX4::PX4_I2C::instance_lock;
26 
28 
29 /*
30  constructor for I2C wrapper class
31  */
32 PX4_I2C::PX4_I2C(uint8_t bus) :
33  I2C(devname, devpath, map_bus_number(bus), 0, 100000UL)
34 {}
35 
36 /*
37  map ArduPilot bus numbers to PX4 bus numbers
38  */
39 uint8_t PX4_I2C::map_bus_number(uint8_t bus) const
40 {
41  switch (bus) {
42  case 0:
43  // map to internal bus
44 #ifdef PX4_I2C_BUS_ONBOARD
45  return PX4_I2C_BUS_ONBOARD;
46 #else
47  return 0;
48 #endif
49 
50  case 1:
51  // map to expansion bus
52 #ifdef PX4_I2C_BUS_EXPANSION
53  return PX4_I2C_BUS_EXPANSION;
54 #else
55  return 1;
56 #endif
57  case 2:
58  // map to expansion bus 2
59 #ifdef PX4_I2C_BUS_EXPANSION1
60  return PX4_I2C_BUS_EXPANSION1;
61 #else
62  return 2;
63 #endif
64  }
65  // default to bus 1
66  return 1;
67 }
68 
69 /*
70  implement wrapper for PX4 I2C driver
71  */
72 bool PX4_I2C::do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers)
73 {
74  set_address(address);
75  if (!init_done) {
76  if (pthread_mutex_lock(&instance_lock) != 0) {
77  return false;
78  }
79  init_done = true;
80  // we do late init() so we can setup the device paths
81 
82  snprintf(devname, sizeof(devname), "AP_I2C_%u", instance);
83  snprintf(devpath, sizeof(devpath), "/dev/api2c%u", instance);
84  init_ok = (init() == OK);
85  if (init_ok) {
86  instance++;
87  }
88  pthread_mutex_unlock(&instance_lock);
89  }
90  if (!init_ok) {
91  return false;
92  }
93 
94  if (split_transfers) {
95  /*
96  splitting the transfer() into two pieces avoids a stop condition
97  with SCL low which is not supported on some devices (such as
98  LidarLite blue label)
99  */
100  if (send && send_len) {
101  if (transfer(send, send_len, nullptr, 0) != OK) {
102  return false;
103  }
104  }
105  if (recv && recv_len) {
106  if (transfer(nullptr, 0, recv, recv_len) != OK) {
107  return false;
108  }
109  }
110  } else {
111  // combined transfer
112  if (transfer(send, send_len, recv, recv_len) != OK) {
113  return false;
114  }
115  }
116  return true;
117 }
118 
119 I2CDevice::I2CDevice(uint8_t bus, uint8_t address) :
120  _busnum(bus),
121  _px4dev(_busnum),
122  _address(address)
123 {
124  set_device_bus(bus);
125  set_device_address(address);
126  asprintf(&pname, "I2C:%u:%02x",
127  (unsigned)bus, (unsigned)address);
128  perf = perf_alloc(PC_ELAPSED, pname);
129 }
130 
132 {
133  printf("I2C device bus %u address 0x%02x closed\n",
134  (unsigned)_busnum, (unsigned)_address);
135  perf_free(perf);
136  free(pname);
137 }
138 
139 bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
140  uint8_t *recv, uint32_t recv_len)
141 {
142  perf_begin(perf);
143  bool ret = _px4dev.do_transfer(_address, send, send_len, recv, recv_len, _split_transfers);
144  perf_end(perf);
145  return ret;
146 }
147 
148 bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
149  uint32_t recv_len, uint8_t times)
150 {
151  return false;
152 }
153 
154 
155 /*
156  register a periodic callback
157 */
158 AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
159 {
160  if (_busnum >= num_buses) {
161  return nullptr;
162  }
163  struct DeviceBus &binfo = businfo[_busnum];
164  return binfo.register_periodic_callback(period_usec, cb, this);
165 }
166 
167 
168 /*
169  adjust a periodic callback
170 */
172 {
173  if (_busnum >= num_buses) {
174  return false;
175  }
176 
177  struct DeviceBus &binfo = businfo[_busnum];
178 
179  return binfo.adjust_timer(h, period_usec);
180 }
181 
183 I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
184  uint32_t bus_clock,
185  bool use_smbus,
186  uint32_t timeout_ms)
187 {
188  auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(bus, address));
189  return dev;
190 }
191 
192 }
int printf(const char *fmt,...)
Definition: stdio.c:113
uint8_t _busnum
Definition: I2CDevice.h:76
bool init_ok
Definition: I2CWrapper.h:36
perf_counter_t perf
Definition: I2CDevice.h:79
bool adjust_timer(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
Definition: Device.cpp:140
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(uint8_t bus, uint8_t address, uint32_t bus_clock=400000, bool use_smbus=false, uint32_t timeout_ms=4) override
Definition: I2CDevice.cpp:183
void set_device_bus(uint8_t bus)
Definition: Device.h:291
char devpath[15]
Definition: I2CWrapper.h:38
static uint8_t instance
Definition: I2CWrapper.h:33
char devname[11]
Definition: I2CWrapper.h:37
static pthread_mutex_t instance_lock
Definition: I2CWrapper.h:34
char * pname
Definition: I2CDevice.h:80
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times) override
Definition: I2CDevice.cpp:148
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb, AP_HAL::Device *hal_device)
Definition: Device.cpp:102
void * PeriodicHandle
Definition: Device.h:42
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: I2CDevice.cpp:158
uint8_t _address
Definition: I2CDevice.h:78
void free(void *ptr)
Definition: malloc.c:81
bool do_transfer(uint8_t address, const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len, bool split_transfers)
Definition: I2CDevice.cpp:72
static const uint8_t num_buses
Definition: I2CDevice.h:73
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.cpp:139
PX4_I2C(uint8_t bus)
Definition: I2CDevice.cpp:32
void init()
Generic board initialization function.
Definition: system.cpp:136
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
bool _split_transfers
Definition: I2CDevice.h:81
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.cpp:171
bool init_done
Definition: I2CWrapper.h:35
void set_device_address(uint8_t address)
Definition: Device.h:286
uint8_t map_bus_number(uint8_t bus) const
Definition: I2CDevice.cpp:39
PX4_I2C _px4dev
Definition: I2CDevice.h:77
static DeviceBus businfo[num_buses]
Definition: I2CDevice.h:74