25 #include <linux/i2c-dev.h> 35 #ifndef I2C_SMBUS_BLOCK_MAX 36 #include <linux/i2c.h> 55 #ifndef I2C_RDRW_IOCTL_MAX_MSGS 56 #define I2C_RDRW_IOCTL_MAX_MSGS 42 69 static inline char *
startswith(
const char *s,
const char *prefix)
71 size_t len = strlen(prefix);
72 if (strncmp(s, prefix, len) == 0) {
73 return (
char *) s + len;
118 char path[
sizeof(
"/dev/i2c-XXX")];
125 r =
snprintf(path,
sizeof(path),
"/dev/i2c-%u", n);
126 if (r < 0 || r >= (
int)
sizeof(path)) {
130 fd =
::open(path, O_RDWR | O_CLOEXEC);
155 uint8_t *recv, uint32_t recv_len)
158 return transfer(send, send_len,
nullptr, 0) &&
159 transfer(
nullptr, 0, recv, recv_len);
162 struct i2c_msg msgs[2] = { };
167 if (send && send_len != 0) {
169 msgs[nmsgs].flags = 0;
170 msgs[nmsgs].buf =
const_cast<uint8_t*
>(send);
171 msgs[nmsgs].len = send_len;
175 if (recv && recv_len != 0) {
177 msgs[nmsgs].flags = I2C_M_RD;
178 msgs[nmsgs].buf = recv;
179 msgs[nmsgs].len = recv_len;
188 struct i2c_rdwr_ioctl_data i2c_data = { };
190 i2c_data.msgs = msgs;
191 i2c_data.nmsgs = nmsgs;
196 r = ::ioctl(
_bus.
fd, I2C_RDWR, &i2c_data);
197 }
while (r == -1 && retries-- > 0);
203 uint32_t recv_len, uint8_t times)
210 uint8_t n =
MIN(times, max_times);
211 struct i2c_msg msgs[2 * n];
212 struct i2c_rdwr_ioctl_data i2c_data = { };
214 memset(msgs, 0, 2 * n *
sizeof(*msgs));
216 i2c_data.msgs = msgs;
217 i2c_data.nmsgs = 2 * n;
219 for (uint8_t i = 0; i < i2c_data.nmsgs; i += 2) {
222 msgs[i].buf = &first_reg;
225 msgs[i + 1].flags = I2C_M_RD;
226 msgs[i + 1].buf = recv;
227 msgs[i + 1].len = recv_len;
235 r = ::ioctl(
_bus.
fd, I2C_RDWR, &i2c_data);
236 }
while (r == -1 && retries-- > 0);
254 uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
288 const char *
dirname =
"/sys/class/i2c-dev/";
289 struct dirent *de =
nullptr;
298 char *str_device, *abs_str_device;
301 if (strcmp(de->d_name,
".") == 0 || strcmp(de->d_name,
"..") == 0) {
305 if (
asprintf(&str_device,
"%s/%s", dirname, de->d_name) < 0) {
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);
316 auto t = std::find_if(std::begin(devpaths),
std::end(devpaths),
317 [p](
const char *prefix) {
321 free(abs_str_device);
328 if (
sscanf(de->d_name,
"i2c-%u", &n) != 1) {
332 AP_HAL::panic(
"I2CDevice: bus with number n=%u higher than %u",
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);
364 if (b->open(bus) < 0) {
368 auto dev = _create_device(*b, address);
373 _buses.push_back(b.leak());
398 for (
auto it = _buses.begin(); it != _buses.end(); it++) {
399 if ((*it)->bus == b.
bus) {
409 for (
auto it = _buses.begin(); it != _buses.end(); it++) {
411 (*it)->thread.stop();
414 for (
auto it = _buses.begin(); it != _buses.end(); it++) {
416 (*it)->thread.join();
dirent_t * readdir(DIR *dirp)
int dirname(char *str)
POSIX directory name of a filename. Return the index of the last '/' character.
void set_device_bus(uint8_t bus)
bool adjust_timer(TimerPollable *p, uint32_t timeout_usec)
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
AP_HAL::Semaphore * get_semaphore() override
#define HAL_SEMAPHORE_BLOCK_FOREVER
bool take(uint32_t timeout_ms)
bool adjust_periodic_callback(AP_HAL::Device::PeriodicHandle h, uint32_t period_usec) override
AP_HAL::OwnPtr< AP_HAL::I2CDevice > get_device(std::vector< const char *> devpaths, uint8_t address) override
static AP_HAL::OwnPtr< AP_HAL::Device > dev
int sscanf(const char *buf, const char *fmt,...)
static const AP_HAL::HAL & hal
#define I2C_RDRW_IOCTL_MAX_MSGS
int close(int fileno)
POSIX Close a file with fileno handel.
AP_HAL::OwnPtr< AP_HAL::I2CDevice > _create_device(I2CBus &b, uint8_t address) const
AP_HAL::Device::PeriodicHandle register_periodic_callback(uint32_t period_usec, AP_HAL::Device::PeriodicCb) override
AP_HAL::I2CDeviceManager * i2c_mgr
#define AP_LINUX_SENSORS_SCHED_PRIO
static char * startswith(const char *s, const char *prefix)
TimerPollable * add_timer(TimerPollable::PeriodicCb cb, TimerPollable::WrapperCb *wrapper, uint32_t timeout_usec)
int closedir(DIR *dirp)
POSIX closedir.
#define AP_LINUX_SENSORS_STACK_SIZE
bool set_stack_size(size_t stack_size)
static I2CDeviceManager * from(AP_HAL::I2CDeviceManager *i2c_mgr)
int errno
Note: fdevopen assigns stdin,stdout,stderr.
int snprintf(char *str, size_t size, const char *fmt,...)
bool read_registers_multiple(uint8_t first_reg, uint8_t *recv, uint32_t recv_len, uint8_t times) override
int asprintf(char **strp, const char *fmt,...)
bool start(const char *name, int policy, int prio)
DIR * opendir(const char *pathdir)
void panic(const char *errormsg,...) FMT_PRINTF(1
#define AP_LINUX_SENSORS_SCHED_POLICY
bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override
void _unregister(I2CBus &b)
void set_device_address(uint8_t address)