APM:Libraries
I2CDevice.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "I2CDevice.h"
18 
19 #include <algorithm>
20 #include <assert.h>
21 #include <dirent.h>
22 #include <errno.h>
23 #include <fcntl.h>
24 #include <limits.h>
25 #include <linux/i2c-dev.h>
26 /*
27  * linux/i2c-dev.h is a kernel header, but some distros rename it to
28  * linux/i2c-dev.h.kernel when i2c-tools is installed. The header provided by
29  * i2c-tools is old/broken and contains some symbols defined in
30  * linux/i2c.h. The i2c.h will be only included if a well-known symbol is not
31  * defined. This is a workaround while distros propagate the real fix like
32  * http://lists.opensuse.org/archive/opensuse-commit/2015-10/msg00918.html (or
33  * do like Archlinux that installs only the kernel header).
34  */
35 #ifndef I2C_SMBUS_BLOCK_MAX
36 #include <linux/i2c.h>
37 #endif
38 #include <stdio.h>
39 #include <stdlib.h>
40 #include <sys/ioctl.h>
41 #include <sys/stat.h>
42 #include <unistd.h>
43 #include <vector>
44 
45 #include <AP_HAL/AP_HAL.h>
46 #include <AP_Math/AP_Math.h>
47 
48 #include "PollerThread.h"
49 #include "Scheduler.h"
50 #include "Semaphores.h"
51 #include "Thread.h"
52 #include "Util.h"
53 
54 /* Workaround broken header from i2c-tools */
55 #ifndef I2C_RDRW_IOCTL_MAX_MSGS
56 #define I2C_RDRW_IOCTL_MAX_MSGS 42
57 #endif
58 
59 namespace Linux {
60 
61 static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
62 
63 /*
64  * TODO: move to Util or other upper class to be used by others
65  *
66  * Return pointer to the next char if @s starts with @prefix, otherwise
67  * returns nullptr.
68  */
69 static inline char *startswith(const char *s, const char *prefix)
70 {
71  size_t len = strlen(prefix);
72  if (strncmp(s, prefix, len) == 0) {
73  return (char *) s + len;
74  }
75  return nullptr;
76 }
77 
78 /* Private struct to maintain for each bus */
80 public:
81  ~I2CBus();
82 
83  /*
84  * TimerPollable::WrapperCb methods to take
85  * and release semaphore while calling the callback
86  */
87  void start_cb() override;
88  void end_cb() override;
89 
90  int open(uint8_t n);
91 
94  int fd = -1;
95  uint8_t bus;
96  uint8_t ref;
97 };
98 
100 {
101  if (fd >= 0) {
102  ::close(fd);
103  }
104 }
105 
107 {
109 }
110 
112 {
113  sem.give();
114 }
115 
116 int I2CBus::open(uint8_t n)
117 {
118  char path[sizeof("/dev/i2c-XXX")];
119  int r;
120 
121  if (fd >= 0) {
122  return -EBUSY;
123  }
124 
125  r = snprintf(path, sizeof(path), "/dev/i2c-%u", n);
126  if (r < 0 || r >= (int)sizeof(path)) {
127  return -EINVAL;
128  }
129 
130  fd = ::open(path, O_RDWR | O_CLOEXEC);
131  if (fd < 0) {
132  return -errno;
133  }
134 
135  bus = n;
136 
137  return fd;
138 }
139 
140 I2CDevice::I2CDevice(I2CBus &bus, uint8_t address)
141  : _bus(bus)
142  , _address(address)
143 {
144  set_device_bus(bus.bus);
145  set_device_address(address);
146 }
147 
149 {
150  // Unregister itself from the I2CDeviceManager
152 }
153 
154 bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
155  uint8_t *recv, uint32_t recv_len)
156 {
157  if (_split_transfers && send_len > 0 && recv_len > 0) {
158  return transfer(send, send_len, nullptr, 0) &&
159  transfer(nullptr, 0, recv, recv_len);
160  }
161 
162  struct i2c_msg msgs[2] = { };
163  unsigned nmsgs = 0;
164 
165  assert(_bus.fd >= 0);
166 
167  if (send && send_len != 0) {
168  msgs[nmsgs].addr = _address;
169  msgs[nmsgs].flags = 0;
170  msgs[nmsgs].buf = const_cast<uint8_t*>(send);
171  msgs[nmsgs].len = send_len;
172  nmsgs++;
173  }
174 
175  if (recv && recv_len != 0) {
176  msgs[nmsgs].addr = _address;
177  msgs[nmsgs].flags = I2C_M_RD;
178  msgs[nmsgs].buf = recv;
179  msgs[nmsgs].len = recv_len;
180  nmsgs++;
181  }
182 
183  /* interpret it as an input error if nothing has to be done */
184  if (!nmsgs) {
185  return false;
186  }
187 
188  struct i2c_rdwr_ioctl_data i2c_data = { };
189 
190  i2c_data.msgs = msgs;
191  i2c_data.nmsgs = nmsgs;
192 
193  int r;
194  unsigned retries = _retries;
195  do {
196  r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
197  } while (r == -1 && retries-- > 0);
198 
199  return r != -1;
200 }
201 
202 bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
203  uint32_t recv_len, uint8_t times)
204 {
205  const uint8_t max_times = I2C_RDRW_IOCTL_MAX_MSGS / 2;
206 
207  first_reg |= _read_flag;
208 
209  while (times > 0) {
210  uint8_t n = MIN(times, max_times);
211  struct i2c_msg msgs[2 * n];
212  struct i2c_rdwr_ioctl_data i2c_data = { };
213 
214  memset(msgs, 0, 2 * n * sizeof(*msgs));
215 
216  i2c_data.msgs = msgs;
217  i2c_data.nmsgs = 2 * n;
218 
219  for (uint8_t i = 0; i < i2c_data.nmsgs; i += 2) {
220  msgs[i].addr = _address;
221  msgs[i].flags = 0;
222  msgs[i].buf = &first_reg;
223  msgs[i].len = 1;
224  msgs[i + 1].addr = _address;
225  msgs[i + 1].flags = I2C_M_RD;
226  msgs[i + 1].buf = recv;
227  msgs[i + 1].len = recv_len;
228 
229  recv += recv_len;
230  };
231 
232  int r;
233  unsigned retries = _retries;
234  do {
235  r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
236  } while (r == -1 && retries-- > 0);
237 
238  if (r == -1) {
239  return false;
240  }
241 
242  times -= n;
243  }
244 
245  return true;
246 }
247 
249 {
250  return &_bus.sem;
251 }
252 
254  uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
255 {
256  TimerPollable *p = _bus.thread.add_timer(cb, &_bus, period_usec);
257  if (!p) {
258  AP_HAL::panic("Could not create periodic callback");
259  }
260 
261  if (!_bus.thread.is_started()) {
262  char name[16];
263  snprintf(name, sizeof(name), "ap-i2c-%u", _bus.bus);
264 
268  }
269 
270  return static_cast<AP_HAL::Device::PeriodicHandle>(p);
271 }
272 
274  AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
275 {
276  return _bus.thread.adjust_timer(static_cast<TimerPollable*>(h), period_usec);
277 }
278 
280 {
281  /* Reserve space up-front for 4 buses */
282  _buses.reserve(4);
283 }
284 
286 I2CDeviceManager::get_device(std::vector<const char *> devpaths, uint8_t address)
287 {
288  const char *dirname = "/sys/class/i2c-dev/";
289  struct dirent *de = nullptr;
290  DIR *d;
291 
292  d = opendir(dirname);
293  if (!d) {
294  AP_HAL::panic("Could not get list of I2C buses");
295  }
296 
297  for (de = readdir(d); de; de = readdir(d)) {
298  char *str_device, *abs_str_device;
299  const char *p;
300 
301  if (strcmp(de->d_name, ".") == 0 || strcmp(de->d_name, "..") == 0) {
302  continue;
303  }
304 
305  if (asprintf(&str_device, "%s/%s", dirname, de->d_name) < 0) {
306  continue;
307  }
308 
309  abs_str_device = realpath(str_device, nullptr);
310  if (!abs_str_device || !(p = startswith(abs_str_device, "/sys/devices/"))) {
311  free(abs_str_device);
312  free(str_device);
313  continue;
314  }
315 
316  auto t = std::find_if(std::begin(devpaths), std::end(devpaths),
317  [p](const char *prefix) {
318  return startswith(p, prefix) != nullptr;
319  });
320 
321  free(abs_str_device);
322  free(str_device);
323 
324  if (t != std::end(devpaths)) {
325  unsigned int n;
326 
327  /* Found the bus, try to create the device now */
328  if (sscanf(de->d_name, "i2c-%u", &n) != 1) {
329  AP_HAL::panic("I2CDevice: can't parse %s", de->d_name);
330  }
331  if (n > UINT8_MAX) {
332  AP_HAL::panic("I2CDevice: bus with number n=%u higher than %u",
333  n, UINT8_MAX);
334  }
335 
336  closedir(d);
337  return get_device(n, address);
338  }
339  }
340 
341  /* not found */
342  closedir(d);
343  return nullptr;
344 }
345 
347 I2CDeviceManager::get_device(uint8_t bus, uint8_t address,
348  uint32_t bus_clock,
349  bool use_smbus,
350  uint32_t timeout_ms)
351 {
352  for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
353  if (_buses[i]->bus == bus) {
354  return _create_device(*_buses[i], address);
355  }
356  }
357 
358  /* Bus not found for this device, create a new one */
360  if (!b) {
361  return nullptr;
362  }
363 
364  if (b->open(bus) < 0) {
365  return nullptr;
366  }
367 
368  auto dev = _create_device(*b, address);
369  if (!dev) {
370  return nullptr;
371  }
372 
373  _buses.push_back(b.leak());
374 
375  return dev;
376 }
377 
378 /* Create a new device increasing the bus reference */
380 I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const
381 {
382  auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(b, address));
383  if (!dev) {
384  return nullptr;
385  }
386  b.ref++;
387  return dev;
388 }
389 
391 {
392  assert(b.ref > 0);
393 
394  if (--b.ref > 0) {
395  return;
396  }
397 
398  for (auto it = _buses.begin(); it != _buses.end(); it++) {
399  if ((*it)->bus == b.bus) {
400  _buses.erase(it);
401  delete &b;
402  break;
403  }
404  }
405 }
406 
408 {
409  for (auto it = _buses.begin(); it != _buses.end(); it++) {
410  /* Try to stop thread - it may not even be started yet */
411  (*it)->thread.stop();
412  }
413 
414  for (auto it = _buses.begin(); it != _buses.end(); it++) {
415  /* Try to join thread - failing is normal if thread was not started */
416  (*it)->thread.join();
417  }
418 }
419 
420 }
uint8_t ref
Definition: I2CDevice.cpp:96
dirent_t * readdir(DIR *dirp)
Definition: posix.c:1768
uint8_t _read_flag
Definition: Device.h:263
void end_cb() override
Definition: I2CDevice.cpp:111
bool _split_transfers
Definition: I2CDevice.h:83
int dirname(char *str)
POSIX directory name of a filename. Return the index of the last &#39;/&#39; character.
Definition: posix.c:1552
void set_device_bus(uint8_t bus)
Definition: Device.h:291
bool adjust_timer(TimerPollable *p, uint32_t timeout_usec)
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
AP_HAL::Semaphore * get_semaphore() override
Definition: I2CDevice.cpp:248
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
const char * name
Definition: BusTest.cpp:11
int open(uint8_t n)
Definition: I2CDevice.cpp:116
#define MIN(a, b)
Definition: usb_conf.h:215
bool take(uint32_t timeout_ms)
Definition: Semaphores.cpp:14
Definition: ff.h:201
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
Definition: I2CDevice.cpp:273
bool is_started() const
Definition: Thread.h:42
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(std::vector< const char *> devpaths, uint8_t address) override
Definition: I2CDevice.cpp:286
static AP_HAL::OwnPtr< AP_HAL::Device > dev
Definition: ICM20789.cpp:16
I2CBus & _bus
Definition: I2CDevice.h:80
int sscanf(const char *buf, const char *fmt,...)
Definition: stdio.c:136
static const AP_HAL::HAL & hal
Definition: I2CDevice.cpp:61
#define I2C_RDRW_IOCTL_MAX_MSGS
Definition: I2CDevice.cpp:56
void * PeriodicHandle
Definition: Device.h:42
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _create_device(I2CBus &b, uint8_t address) const
Definition: I2CDevice.cpp:380
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
Definition: I2CDevice.cpp:253
const HAL & get_HAL()
PollerThread thread
Definition: I2CDevice.cpp:92
AP_HAL::I2CDeviceManager * i2c_mgr
Definition: HAL.h:106
#define AP_LINUX_SENSORS_SCHED_PRIO
Definition: Scheduler.h:15
void free(void *ptr)
Definition: malloc.c:81
uint8_t bus
Definition: I2CDevice.cpp:95
static char * startswith(const char *s, const char *prefix)
Definition: I2CDevice.cpp:69
TimerPollable * add_timer(TimerPollable::PeriodicCb cb, TimerPollable::WrapperCb *wrapper, uint32_t timeout_usec)
Semaphore sem
Definition: I2CDevice.cpp:93
int closedir(DIR *dirp)
POSIX closedir.
Definition: posix.c:1730
#define AP_LINUX_SENSORS_STACK_SIZE
Definition: Scheduler.h:13
bool set_stack_size(size_t stack_size)
Definition: Thread.cpp:236
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
Definition: I2CDevice.h:90
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int snprintf(char *str, size_t size, const char *fmt,...)
Definition: stdio.c:64
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times) override
Definition: I2CDevice.cpp:202
void start_cb() override
Definition: I2CDevice.cpp:106
uint8_t _retries
Definition: I2CDevice.h:82
int asprintf(char **strp, const char *fmt,...)
Definition: stdio.c:91
bool start(const char *name, int policy, int prio)
Definition: Thread.cpp:155
DIR * opendir(const char *pathdir)
Definition: posix.c:1749
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
#define AP_LINUX_SENSORS_SCHED_POLICY
Definition: Scheduler.h:14
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
Definition: I2CDevice.cpp:154
void _unregister(I2CBus &b)
Definition: I2CDevice.cpp:390
void set_device_address(uint8_t address)
Definition: Device.h:286
uint8_t _address
Definition: I2CDevice.h:81