device: added a _device_id to all drivers

this device ID identifies a specific device via the tuple of (bus, bus
type, address, devtype). This allows device specific configuration
data to be stored along with a device ID, so the code can know when
the user has changed device configuration (such as removing an
external compass), and either invalidate the device configuration or
force the user to re-calibrate
This commit is contained in:
Andrew Tridgell
2014-07-08 21:09:12 +10:00
committed by Lorenz Meier
parent a2f528c5ba
commit 93d444d1aa
5 changed files with 57 additions and 1 deletions
+12
View File
@@ -42,6 +42,7 @@
#include <nuttx/arch.h>
#include <stdio.h>
#include <unistd.h>
#include <drivers/drv_device.h>
namespace device
{
@@ -93,6 +94,13 @@ Device::Device(const char *name,
_irq_attached(false)
{
sem_init(&_lock, 0, 1);
/* setup a default device ID. When bus_type is UNKNOWN the
other fields are invalid */
_device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
_device_id.devid_s.bus = 0;
_device_id.devid_s.address = 0;
_device_id.devid_s.devtype = 0;
}
Device::~Device()
@@ -238,6 +246,10 @@ Device::write(unsigned offset, void *data, unsigned count)
int
Device::ioctl(unsigned operation, unsigned &arg)
{
switch (operation) {
case DEVIOCGDEVICEID:
return (int)_device_id.devid;
}
return -ENODEV;
}
+25
View File
@@ -124,9 +124,34 @@ public:
*/
virtual int ioctl(unsigned operation, unsigned &arg);
/*
device bus types for DEVID
*/
enum DeviceBusType {
DeviceBusType_UNKNOWN = 0,
DeviceBusType_I2C = 1,
DeviceBusType_SPI = 2
};
/*
broken out
*/
struct DeviceStructure {
enum DeviceBusType bus_type;
uint8_t bus; // which instance of the bus type
uint8_t address; // address on the bus (eg. I2C address)
uint8_t devtype; // device class specific device type
};
union DeviceId {
struct DeviceStructure devid_s;
uint32_t devid;
};
protected:
const char *_name; /**< driver name */
bool _debug_enabled; /**< if true, debug messages are printed */
union DeviceId _device_id; /**< device identifier information */
/**
* Constructor
+7 -1
View File
@@ -62,6 +62,12 @@ I2C::I2C(const char *name,
_frequency(frequency),
_dev(nullptr)
{
// fill in _device_id fields for a I2C device
_device_id.devid_s.bus_type = DeviceBusType_I2C;
_device_id.devid_s.bus = bus;
_device_id.devid_s.address = address;
// devtype needs to be filled in by the driver
_device_id.devid_s.devtype = 0;
}
I2C::~I2C()
@@ -201,4 +207,4 @@ I2C::transfer(i2c_msg_s *msgv, unsigned msgs)
return ret;
}
} // namespace device
} // namespace device
+6
View File
@@ -75,6 +75,12 @@ SPI::SPI(const char *name,
_dev(nullptr),
_bus(bus)
{
// fill in _device_id fields for a SPI device
_device_id.devid_s.bus_type = DeviceBusType_SPI;
_device_id.devid_s.bus = bus;
_device_id.devid_s.address = (uint8_t)device;
// devtype needs to be filled in by the driver
_device_id.devid_s.devtype = 0;
}
SPI::~SPI()
+7
View File
@@ -59,4 +59,11 @@
/** check publication block status */
#define DEVIOCGPUBBLOCK _DEVICEIOC(1)
/**
* Return device ID, to enable matching of configuration parameters
* (such as compass offsets) to specific sensors
*/
#define DEVIOCGDEVICEID _DEVICEIOC(2)
#endif /* _DRV_DEVICE_H */