aboutsummaryrefslogtreecommitdiff
diff options
context:
space:
mode:
authorAndrew Tridgell <tridge@samba.org>2014-07-08 21:09:12 +1000
committerLorenz Meier <lm@inf.ethz.ch>2014-07-12 16:25:43 +0200
commit93d444d1aade59b5e88f41b71c842a00ab950c64 (patch)
treebac1fefd6a71196c7584804d38bf765612d11434
parenta2f528c5ba20ade8c3be200ed07fb6e925030c0d (diff)
downloadpx4-firmware-93d444d1aade59b5e88f41b71c842a00ab950c64.tar.gz
px4-firmware-93d444d1aade59b5e88f41b71c842a00ab950c64.tar.bz2
px4-firmware-93d444d1aade59b5e88f41b71c842a00ab950c64.zip
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
-rw-r--r--src/drivers/device/device.cpp12
-rw-r--r--src/drivers/device/device.h25
-rw-r--r--src/drivers/device/i2c.cpp8
-rw-r--r--src/drivers/device/spi.cpp6
-rw-r--r--src/drivers/drv_device.h7
5 files changed, 57 insertions, 1 deletions
diff --git a/src/drivers/device/device.cpp b/src/drivers/device/device.cpp
index 683455149..f1f777dce 100644
--- a/src/drivers/device/device.cpp
+++ b/src/drivers/device/device.cpp
@@ -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;
}
diff --git a/src/drivers/device/device.h b/src/drivers/device/device.h
index d99f22922..c98386eb0 100644
--- a/src/drivers/device/device.h
+++ b/src/drivers/device/device.h
@@ -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
diff --git a/src/drivers/device/i2c.cpp b/src/drivers/device/i2c.cpp
index a416801eb..286778c01 100644
--- a/src/drivers/device/i2c.cpp
+++ b/src/drivers/device/i2c.cpp
@@ -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 \ No newline at end of file
+} // namespace device
diff --git a/src/drivers/device/spi.cpp b/src/drivers/device/spi.cpp
index 1ab1dc699..200acac05 100644
--- a/src/drivers/device/spi.cpp
+++ b/src/drivers/device/spi.cpp
@@ -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()
diff --git a/src/drivers/drv_device.h b/src/drivers/drv_device.h
index b310beb74..19d55cef3 100644
--- a/src/drivers/drv_device.h
+++ b/src/drivers/drv_device.h
@@ -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 */