2015-11-22 19:57:03 -04:00
|
|
|
/// -*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
|
|
|
|
/*
|
|
|
|
* Copyright (C) 2015-2016 Intel Corporation. All rights reserved.
|
|
|
|
*
|
|
|
|
* This file is free software: you can redistribute it and/or modify it
|
|
|
|
* under the terms of the GNU General Public License as published by the
|
|
|
|
* Free Software Foundation, either version 3 of the License, or
|
|
|
|
* (at your option) any later version.
|
|
|
|
*
|
|
|
|
* This file is distributed in the hope that it will be useful, but
|
|
|
|
* WITHOUT ANY WARRANTY; without even the implied warranty of
|
|
|
|
* MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
|
|
|
|
* See the GNU General Public License for more details.
|
|
|
|
*
|
|
|
|
* You should have received a copy of the GNU General Public License along
|
|
|
|
* with this program. If not, see <http://www.gnu.org/licenses/>.
|
|
|
|
*/
|
|
|
|
#include "I2CDevice.h"
|
|
|
|
|
|
|
|
#include <algorithm>
|
|
|
|
#include <assert.h>
|
|
|
|
#include <dirent.h>
|
|
|
|
#include <errno.h>
|
|
|
|
#include <fcntl.h>
|
|
|
|
#include <limits.h>
|
2015-11-12 17:43:10 -04:00
|
|
|
#include <linux/i2c-dev.h>
|
|
|
|
/*
|
|
|
|
* linux/i2c-dev.h is a kernel header, but some distros rename it to
|
|
|
|
* linux/i2c-dev.h.kernel when i2c-tools is installed. The header provided by
|
|
|
|
* i2c-tools is old/broken and contains some symbols defined in
|
|
|
|
* linux/i2c.h. The i2c.h will be only included if a well-known symbol is not
|
|
|
|
* defined. This is a workaround while distros propagate the real fix like
|
|
|
|
* http://lists.opensuse.org/archive/opensuse-commit/2015-10/msg00918.html (or
|
|
|
|
* do like Archlinux that installs only the kernel header).
|
|
|
|
*/
|
|
|
|
#ifndef I2C_SMBUS_BLOCK_MAX
|
|
|
|
#include <linux/i2c.h>
|
|
|
|
#endif
|
2016-05-11 16:07:14 -03:00
|
|
|
#include <stdio.h>
|
2015-11-22 19:57:03 -04:00
|
|
|
#include <stdlib.h>
|
2015-11-12 17:43:10 -04:00
|
|
|
#include <sys/ioctl.h>
|
2015-11-22 19:57:03 -04:00
|
|
|
#include <sys/stat.h>
|
|
|
|
#include <unistd.h>
|
|
|
|
#include <vector>
|
|
|
|
|
|
|
|
#include <AP_HAL/AP_HAL.h>
|
2016-01-19 01:32:24 -04:00
|
|
|
#include <AP_Math/AP_Math.h>
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-19 10:01:47 -03:00
|
|
|
#include "PollerThread.h"
|
|
|
|
#include "Scheduler.h"
|
|
|
|
#include "Semaphores.h"
|
|
|
|
#include "Thread.h"
|
2015-11-22 19:57:03 -04:00
|
|
|
#include "Util.h"
|
|
|
|
|
2016-01-19 01:32:24 -04:00
|
|
|
/* Workaround broken header from i2c-tools */
|
|
|
|
#ifndef I2C_RDRW_IOCTL_MAX_MSGS
|
|
|
|
#define I2C_RDRW_IOCTL_MAX_MSGS 42
|
|
|
|
#endif
|
|
|
|
|
2015-11-22 19:57:03 -04:00
|
|
|
namespace Linux {
|
|
|
|
|
|
|
|
static const AP_HAL::HAL &hal = AP_HAL::get_HAL();
|
|
|
|
|
2015-11-11 16:14:26 -04:00
|
|
|
/*
|
|
|
|
* TODO: move to Util or other upper class to be used by others
|
|
|
|
*
|
|
|
|
* Return pointer to the next char if @s starts with @prefix, otherwise
|
|
|
|
* returns nullptr.
|
|
|
|
*/
|
|
|
|
static inline char *startswith(const char *s, const char *prefix)
|
|
|
|
{
|
|
|
|
size_t len = strlen(prefix);
|
|
|
|
if (strncmp(s, prefix, len) == 0) {
|
|
|
|
return (char *) s + len;
|
|
|
|
}
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
2015-11-22 19:57:03 -04:00
|
|
|
/* Private struct to maintain for each bus */
|
2016-07-19 10:01:47 -03:00
|
|
|
class I2CBus : public TimerPollable::WrapperCb {
|
2015-11-22 19:57:03 -04:00
|
|
|
public:
|
2016-07-16 02:16:09 -03:00
|
|
|
~I2CBus();
|
2016-07-19 10:01:47 -03:00
|
|
|
|
|
|
|
/*
|
|
|
|
* TimerPollable::WrapperCb methods to take
|
|
|
|
* and release semaphore while calling the callback
|
|
|
|
*/
|
|
|
|
void start_cb() override;
|
|
|
|
void end_cb() override;
|
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
int open(uint8_t n);
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-19 10:01:47 -03:00
|
|
|
PollerThread thread;
|
2016-07-16 02:16:09 -03:00
|
|
|
Semaphore sem;
|
|
|
|
int fd = -1;
|
|
|
|
uint8_t bus;
|
|
|
|
uint8_t ref;
|
|
|
|
};
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
I2CBus::~I2CBus()
|
|
|
|
{
|
|
|
|
if (fd >= 0) {
|
|
|
|
::close(fd);
|
|
|
|
}
|
|
|
|
}
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-19 10:01:47 -03:00
|
|
|
void I2CBus::start_cb()
|
|
|
|
{
|
|
|
|
sem.take(HAL_SEMAPHORE_BLOCK_FOREVER);
|
|
|
|
}
|
|
|
|
|
|
|
|
void I2CBus::end_cb()
|
|
|
|
{
|
|
|
|
sem.give();
|
|
|
|
}
|
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
int I2CBus::open(uint8_t n)
|
|
|
|
{
|
|
|
|
char path[sizeof("/dev/i2c-XXX")];
|
|
|
|
int r;
|
2015-11-11 16:14:26 -04:00
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
if (fd >= 0) {
|
|
|
|
return -EBUSY;
|
|
|
|
}
|
2015-11-11 16:14:26 -04:00
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
r = snprintf(path, sizeof(path), "/dev/i2c-%u", n);
|
|
|
|
if (r < 0 || r >= (int)sizeof(path)) {
|
|
|
|
return -EINVAL;
|
|
|
|
}
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
fd = ::open(path, O_RDWR | O_CLOEXEC);
|
|
|
|
if (fd < 0) {
|
|
|
|
return -errno;
|
2015-11-22 19:57:03 -04:00
|
|
|
}
|
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
bus = n;
|
2015-11-22 19:57:03 -04:00
|
|
|
|
2016-07-16 02:16:09 -03:00
|
|
|
return fd;
|
|
|
|
}
|
2015-11-22 19:57:03 -04:00
|
|
|
|
|
|
|
I2CDevice::~I2CDevice()
|
|
|
|
{
|
|
|
|
// Unregister itself from the I2CDeviceManager
|
|
|
|
I2CDeviceManager::from(hal.i2c_mgr)->_unregister(_bus);
|
|
|
|
}
|
|
|
|
|
|
|
|
bool I2CDevice::transfer(const uint8_t *send, uint32_t send_len,
|
|
|
|
uint8_t *recv, uint32_t recv_len)
|
|
|
|
{
|
2015-11-12 17:43:10 -04:00
|
|
|
struct i2c_msg msgs[2] = { };
|
|
|
|
unsigned nmsgs = 0;
|
|
|
|
|
|
|
|
assert(_bus.fd >= 0);
|
|
|
|
|
|
|
|
if (send && send_len != 0) {
|
|
|
|
msgs[nmsgs].addr = _address;
|
|
|
|
msgs[nmsgs].flags = 0;
|
|
|
|
msgs[nmsgs].buf = const_cast<uint8_t*>(send);
|
|
|
|
msgs[nmsgs].len = send_len;
|
|
|
|
nmsgs++;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (recv && recv_len != 0) {
|
|
|
|
msgs[nmsgs].addr = _address;
|
|
|
|
msgs[nmsgs].flags = I2C_M_RD;
|
|
|
|
msgs[nmsgs].buf = recv;
|
|
|
|
msgs[nmsgs].len = recv_len;
|
|
|
|
nmsgs++;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!nmsgs) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
struct i2c_rdwr_ioctl_data i2c_data = { };
|
|
|
|
|
|
|
|
i2c_data.msgs = msgs;
|
|
|
|
i2c_data.nmsgs = nmsgs;
|
|
|
|
|
|
|
|
int r = -EINVAL;
|
|
|
|
unsigned retries = _retries;
|
|
|
|
do {
|
|
|
|
r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
|
|
|
|
} while (r < 0 && retries-- > 0);
|
|
|
|
|
|
|
|
return r >= 0;
|
2015-11-22 19:57:03 -04:00
|
|
|
}
|
|
|
|
|
2016-01-19 01:32:24 -04:00
|
|
|
bool I2CDevice::read_registers_multiple(uint8_t first_reg, uint8_t *recv,
|
|
|
|
uint32_t recv_len, uint8_t times)
|
|
|
|
{
|
|
|
|
const uint8_t max_times = I2C_RDRW_IOCTL_MAX_MSGS / 2;
|
|
|
|
|
2016-06-06 17:37:25 -03:00
|
|
|
first_reg |= _read_flag;
|
|
|
|
|
2016-01-19 01:32:24 -04:00
|
|
|
while (times > 0) {
|
|
|
|
uint8_t n = MIN(times, max_times);
|
|
|
|
struct i2c_msg msgs[2 * n];
|
|
|
|
struct i2c_rdwr_ioctl_data i2c_data = { };
|
|
|
|
|
|
|
|
memset(msgs, 0, 2 * n * sizeof(*msgs));
|
|
|
|
|
|
|
|
i2c_data.msgs = msgs;
|
|
|
|
i2c_data.nmsgs = 2 * n;
|
|
|
|
|
|
|
|
for (uint8_t i = 0; i < i2c_data.nmsgs; i += 2) {
|
|
|
|
msgs[i].addr = _address;
|
|
|
|
msgs[i].flags = 0;
|
|
|
|
msgs[i].buf = &first_reg;
|
|
|
|
msgs[i].len = 1;
|
|
|
|
msgs[i + 1].addr = _address;
|
|
|
|
msgs[i + 1].flags = I2C_M_RD;
|
|
|
|
msgs[i + 1].buf = recv;
|
|
|
|
msgs[i + 1].len = recv_len;
|
|
|
|
|
|
|
|
recv += recv_len;
|
|
|
|
};
|
|
|
|
|
|
|
|
int r = -EINVAL;
|
|
|
|
unsigned retries = _retries;
|
|
|
|
do {
|
|
|
|
r = ::ioctl(_bus.fd, I2C_RDWR, &i2c_data);
|
|
|
|
} while (r < 0 && retries-- > 0);
|
|
|
|
|
|
|
|
if (r < 0) {
|
|
|
|
return false;
|
|
|
|
}
|
|
|
|
|
|
|
|
times -= n;
|
|
|
|
}
|
|
|
|
|
|
|
|
return true;
|
|
|
|
}
|
|
|
|
|
2015-11-22 19:57:03 -04:00
|
|
|
AP_HAL::Semaphore *I2CDevice::get_semaphore()
|
|
|
|
{
|
|
|
|
return &_bus.sem;
|
|
|
|
}
|
|
|
|
|
|
|
|
int I2CDevice::get_fd()
|
|
|
|
{
|
|
|
|
return _bus.fd;
|
|
|
|
}
|
|
|
|
|
2016-07-19 09:44:52 -03:00
|
|
|
AP_HAL::Device::PeriodicHandle I2CDevice::register_periodic_callback(
|
2016-07-19 10:01:47 -03:00
|
|
|
uint32_t period_usec, AP_HAL::Device::PeriodicCb cb)
|
2016-07-19 09:44:52 -03:00
|
|
|
{
|
2016-07-19 10:01:47 -03:00
|
|
|
TimerPollable *p = _bus.thread.add_timer(cb, &_bus, period_usec);
|
|
|
|
if (!p) {
|
|
|
|
AP_HAL::panic("Could not create periodic callback");
|
|
|
|
}
|
|
|
|
|
|
|
|
if (!_bus.thread.is_started()) {
|
|
|
|
char name[16];
|
|
|
|
snprintf(name, sizeof(name), "ap-i2c-%u", _bus.bus);
|
|
|
|
|
|
|
|
_bus.thread.set_stack_size(AP_LINUX_SENSORS_STACK_SIZE);
|
|
|
|
_bus.thread.start(name, AP_LINUX_SENSORS_SCHED_POLICY,
|
|
|
|
AP_LINUX_SENSORS_SCHED_PRIO);
|
|
|
|
}
|
|
|
|
|
|
|
|
return static_cast<AP_HAL::Device::PeriodicHandle>(p);
|
2016-07-19 09:44:52 -03:00
|
|
|
}
|
|
|
|
|
|
|
|
bool I2CDevice::adjust_periodic_callback(
|
|
|
|
AP_HAL::Device::PeriodicHandle h, uint32_t period_usec)
|
|
|
|
{
|
2016-07-19 10:01:47 -03:00
|
|
|
return _bus.thread.adjust_timer(static_cast<TimerPollable*>(h), period_usec);
|
2016-07-19 09:44:52 -03:00
|
|
|
}
|
|
|
|
|
2015-11-22 19:57:03 -04:00
|
|
|
I2CDeviceManager::I2CDeviceManager()
|
|
|
|
{
|
|
|
|
/* Reserve space up-front for 4 buses */
|
|
|
|
_buses.reserve(4);
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
|
|
|
I2CDeviceManager::get_device(std::vector<const char *> devpaths, uint8_t address)
|
|
|
|
{
|
2016-03-08 10:11:04 -04:00
|
|
|
const char *dirname = "/sys/class/i2c-dev/";
|
2015-11-11 16:14:26 -04:00
|
|
|
struct dirent *de = nullptr;
|
|
|
|
DIR *d;
|
|
|
|
|
|
|
|
d = opendir(dirname);
|
|
|
|
if (!d) {
|
|
|
|
AP_HAL::panic("Could not get list of I2C buses");
|
|
|
|
}
|
|
|
|
|
|
|
|
for (de = readdir(d); de; de = readdir(d)) {
|
|
|
|
char *str_device, *abs_str_device;
|
|
|
|
const char *p;
|
|
|
|
|
|
|
|
if (strcmp(de->d_name, ".") == 0 || strcmp(de->d_name, "..") == 0) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (asprintf(&str_device, "%s/%s", dirname, de->d_name) < 0) {
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
abs_str_device = realpath(str_device, nullptr);
|
2016-03-08 10:11:04 -04:00
|
|
|
if (!abs_str_device || !(p = startswith(abs_str_device, "/sys/devices/"))) {
|
2015-11-11 16:14:26 -04:00
|
|
|
free(abs_str_device);
|
|
|
|
free(str_device);
|
|
|
|
continue;
|
|
|
|
}
|
|
|
|
|
|
|
|
auto t = std::find_if(std::begin(devpaths), std::end(devpaths),
|
|
|
|
[p](const char *prefix) {
|
|
|
|
return startswith(p, prefix) != nullptr;
|
|
|
|
});
|
|
|
|
|
|
|
|
free(abs_str_device);
|
|
|
|
free(str_device);
|
|
|
|
|
|
|
|
if (t != std::end(devpaths)) {
|
|
|
|
unsigned int n;
|
|
|
|
|
|
|
|
/* Found the bus, try to create the device now */
|
|
|
|
if (sscanf(de->d_name, "i2c-%u", &n) != 1) {
|
|
|
|
AP_HAL::panic("I2CDevice: can't parse %s", de->d_name);
|
|
|
|
}
|
|
|
|
if (n > UINT8_MAX) {
|
|
|
|
AP_HAL::panic("I2CDevice: bus with number n=%u higher than %u",
|
|
|
|
n, UINT8_MAX);
|
|
|
|
}
|
|
|
|
|
|
|
|
closedir(d);
|
|
|
|
return get_device(n, address);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* not found */
|
|
|
|
closedir(d);
|
2015-11-22 19:57:03 -04:00
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
|
|
|
I2CDeviceManager::get_device(uint8_t bus, uint8_t address)
|
|
|
|
{
|
|
|
|
for (uint8_t i = 0, n = _buses.size(); i < n; i++) {
|
|
|
|
if (_buses[i]->bus == bus) {
|
|
|
|
return _create_device(*_buses[i], address);
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Bus not found for this device, create a new one */
|
|
|
|
AP_HAL::OwnPtr<I2CBus> b{new I2CBus()};
|
|
|
|
if (!b) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
if (b->open(bus) < 0) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
auto dev = _create_device(*b, address);
|
|
|
|
if (!dev) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
|
|
|
|
_buses.push_back(b.leak());
|
|
|
|
|
|
|
|
return dev;
|
|
|
|
}
|
|
|
|
|
|
|
|
/* Create a new device increasing the bus reference */
|
|
|
|
AP_HAL::OwnPtr<AP_HAL::I2CDevice>
|
|
|
|
I2CDeviceManager::_create_device(I2CBus &b, uint8_t address) const
|
|
|
|
{
|
|
|
|
auto dev = AP_HAL::OwnPtr<AP_HAL::I2CDevice>(new I2CDevice(b, address));
|
|
|
|
if (!dev) {
|
|
|
|
return nullptr;
|
|
|
|
}
|
|
|
|
b.ref++;
|
|
|
|
return dev;
|
|
|
|
}
|
|
|
|
|
|
|
|
void I2CDeviceManager::_unregister(I2CBus &b)
|
|
|
|
{
|
|
|
|
assert(b.ref > 0);
|
|
|
|
|
|
|
|
if (--b.ref > 0) {
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
|
|
|
for (auto it = _buses.begin(); it != _buses.end(); it++) {
|
|
|
|
if ((*it)->bus == b.bus) {
|
|
|
|
_buses.erase(it);
|
|
|
|
delete &b;
|
|
|
|
break;
|
|
|
|
}
|
|
|
|
}
|
|
|
|
}
|
|
|
|
|
|
|
|
}
|