AP_HAL_Linux: add constructor to find I2C bus reliably

The device number in /dev may not be reliable from one boot to another
due to the initialization order of each bus.

For example, in Minnow Board Max, the exposed I2C buses may be i2c-7 and
i2c-8 or i2c-8 and i2c-9 depending if the platform driver in the kernel
is initialized before or after the PCI.

It also may change with different version and configuration of the DT or
UEFI used making another kernel driver to bind to the device. This means that
for Minnow Board Max we need to use something like below to pass to the
constructor:

	static const char * const i2c_devpaths[] = {
	    /* UEFI with lpss set to ACPI */
	    "/devices/platform/80860F41:05",
	    /* UEFI with lpss set to PCI */
	    "/devices/pci0000:00/0000:00:18.6",
	     NULL
	};

The devpath here is the one returned by udev with the following command:

	udevadm info -q path /dev/<i2c-device>

In contrary to the device number in /dev/i2c-N, this path in sysfs is
stable across reboots and can only change if there's a change in the
UEFI firmware or the board's device tree.

This patch assumes the currently supported boards don't have this
problem so it's not touching them.
This commit is contained in:
Lucas De Marchi 2015-06-24 19:01:13 -03:00 committed by Andrew Tridgell
parent ec5d0b6c08
commit a4c1b0d75f
2 changed files with 64 additions and 3 deletions

View File

@ -4,26 +4,85 @@
#if CONFIG_HAL_BOARD == HAL_BOARD_LINUX
#include "I2CDriver.h"
#include <errno.h>
#include <sys/types.h>
#include <sys/stat.h>
#include <dirent.h>
#include <fcntl.h>
#include <unistd.h>
#include <stdio.h>
#include <stdlib.h>
#include <limits.h>
#include <sys/ioctl.h>
#include <linux/i2c-dev.h>
#ifndef I2C_SMBUS_BLOCK_MAX
#include <linux/i2c.h>
#endif
extern const AP_HAL::HAL& hal;
using namespace Linux;
/*
constructor
*/
LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char *device) :
_semaphore(semaphore),
_device(device)
_semaphore(semaphore)
{
_device = strdup(device);
}
/* Match a given device by the prefix its devpath, i.e. the path returned by
* udevadm info -q path /dev/<i2c-device>'. This constructor can be used when
* the number of the I2C bus is not stable across reboots. It matches the
* first device with a prefix in @devpaths */
LinuxI2CDriver::LinuxI2CDriver(AP_HAL::Semaphore* semaphore,
const char * const devpaths[]) :
_semaphore(semaphore)
{
const char *dirname = "/sys/class/i2c-dev";
struct dirent *de;
DIR *d;
d = opendir(dirname);
if (!d)
hal.scheduler->panic("Could not get list of I2C buses");
for (de = readdir(d); de; de = readdir(d)) {
const char *p, * const *t;
char buf[PATH_MAX], buf2[PATH_MAX];
if (strcmp(de->d_name, ".") == 0 || strcmp(de->d_name, "..") == 0)
continue;
if (snprintf(buf, sizeof(buf), "%s/%s", dirname, de->d_name) >= PATH_MAX)
continue;
p = realpath(buf, buf2);
if (!p || strncmp(p, "/sys", sizeof("/sys") - 1))
continue;
p += sizeof("/sys") - 1;
for (t = devpaths; t && *t; t++) {
if (strncmp(p, *t, strlen(*t)) == 0)
break;
}
if (!*t)
continue;
/* Found the device name, use the new path */
asprintf(&_device, "/dev/%s", de->d_name);
break;
}
closedir(d);
}
LinuxI2CDriver::~LinuxI2CDriver()
{
free(_device);
}
/*

View File

@ -7,6 +7,8 @@
class Linux::LinuxI2CDriver : public AP_HAL::I2CDriver {
public:
LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char *device);
LinuxI2CDriver(AP_HAL::Semaphore* semaphore, const char * const devpaths[]);
~LinuxI2CDriver();
void begin();
void end();
@ -44,7 +46,7 @@ private:
bool set_address(uint8_t addr);
AP_HAL::Semaphore* _semaphore;
const char *_device = NULL;
char *_device = NULL;
int _fd = -1;
uint8_t _addr;
};