PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Fundamental base class for all physical drivers (I2C, SPI). More...
#include <Device.hpp>
Classes | |
union | _device_id |
device identifier information More... | |
union | DeviceId |
struct | DeviceStructure |
Public Types | |
enum | DeviceBusType { DeviceBusType_UNKNOWN = 0, DeviceBusType_I2C = 1, DeviceBusType_SPI = 2, DeviceBusType_UAVCAN = 3, DeviceBusType_SIMULATION = 4 } |
Device bus types for DEVID. More... | |
Public Member Functions | |
Device (const Device &)=delete | |
Device & | operator= (const Device &)=delete |
Device (Device &&)=delete | |
Device & | operator= (Device &&)=delete |
virtual | ~Device ()=default |
Destructor. More... | |
virtual int | init () |
Initialise the driver and make it ready for use. More... | |
virtual int | read (unsigned address, void *data, unsigned count) |
Read directly from the device. More... | |
virtual int | write (unsigned address, void *data, unsigned count) |
Write directly to the device. More... | |
virtual int | ioctl (unsigned operation, unsigned &arg) |
Perform a device-specific operation. More... | |
uint32_t | get_device_id () const |
DeviceBusType | get_device_bus_type () const |
Return the bus type the device is connected to. More... | |
void | set_device_bus_type (DeviceBusType bus_type) |
uint8_t | get_device_bus () const |
Return the bus ID the device is connected to. More... | |
void | set_device_bus (uint8_t bus) |
uint8_t | get_device_address () const |
Return the bus address of the device. More... | |
void | set_device_address (int address) |
uint8_t | get_device_type () const |
Return the device type. More... | |
void | set_device_type (uint8_t devtype) |
virtual bool | external () const |
Static Public Member Functions | |
static const char * | get_device_bus_string (DeviceBusType bus) |
static int | device_id_print_buffer (char *buffer, int length, uint32_t id) |
Print decoded device id string to a buffer. More... | |
Protected Member Functions | |
Device (const char *name) | |
Device (const char *name, DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0) | |
Device (DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0) | |
Protected Attributes | |
const char * | _name {nullptr} |
driver name More... | |
bool | _debug_enabled {false} |
if true, debug messages are printed More... | |
Fundamental base class for all physical drivers (I2C, SPI).
This class provides the basic driver template for I2C and SPI devices
Definition at line 65 of file Device.hpp.
Device bus types for DEVID.
Enumerator | |
---|---|
DeviceBusType_UNKNOWN | |
DeviceBusType_I2C | |
DeviceBusType_SPI | |
DeviceBusType_UAVCAN | |
DeviceBusType_SIMULATION |
Definition at line 135 of file Device.hpp.
|
delete |
|
delete |
|
virtualdefault |
Destructor.
Public so that anonymous devices can be destroyed.
|
inlineexplicitprotected |
Definition at line 245 of file Device.hpp.
|
inlineprotected |
Definition at line 250 of file Device.hpp.
|
inlineprotected |
Definition at line 259 of file Device.hpp.
|
inlinestatic |
Print decoded device id string to a buffer.
buffer | buffer to write to |
length | buffer length |
id | The device id. |
return | number of bytes written |
Definition at line 224 of file Device.hpp.
References device::Device::DeviceId::devid.
|
inlinevirtual |
Definition at line 237 of file Device.hpp.
Referenced by LPS22HB::collect(), MPL3115A2::init(), MS5611::init(), MPU9250::is_external(), and ICM20948::is_external().
|
inline |
Return the bus address of the device.
Definition at line 205 of file Device.hpp.
|
inline |
Return the bus ID the device is connected to.
Definition at line 197 of file Device.hpp.
|
inlinestatic |
Definition at line 171 of file Device.hpp.
|
inline |
Return the bus type the device is connected to.
Definition at line 168 of file Device.hpp.
Referenced by MPU9250::init(), ICM20948::init(), MPU6000::reset(), MPU9250::reset_mpu(), and ICM20948::reset_mpu().
|
inline |
Definition at line 161 of file Device.hpp.
Referenced by MPL3115A2::collect(), MS5611::collect(), LPS22HB::collect(), LPS25H::collect(), MPL3115A2::init(), and MS5611::init().
|
inline |
|
inlinevirtual |
Initialise the driver and make it ready for use.
Reimplemented in QMC5883, RM3100, HMC5883, LIS3MDL, device::CDev, UavcanMagnetometerBridge, UavcanBarometerBridge, UavcanBatteryBridge, and UavcanFlowBridge.
Definition at line 91 of file Device.hpp.
Referenced by device::CDev::init(), MPU9250::init(), and ICM20948::init().
|
inlinevirtual |
Perform a device-specific operation.
operation | The operation to perform. |
arg | An argument to the operation. |
Definition at line 124 of file Device.hpp.
Referenced by MPL3115A2::ioctl(), LPS22HB::ioctl(), LPS25H::ioctl(), MPL3115A2::measure(), MS5611::measure(), MPL3115A2::Run(), MS5611::Run(), and PX4IO::set_update_rate().
|
inlinevirtual |
Read directly from the device.
The actual size of each unit quantity is device-specific.
offset | The device address at which to start reading |
data | The buffer into which the read values should be placed. |
count | The number of items to read. |
Definition at line 103 of file Device.hpp.
Referenced by ICM20948_mag::ak09916_read_adjustments(), MPU9250_mag::ak8963_read_adjustments(), MPL3115A2::collect(), MS5611::collect(), LPS22HB::collect(), LPS25H::collect(), MPU6000::factory_self_test(), PX4IO::io_reg_get(), ICM20948_mag::measure(), MPU9250_mag::measure(), MPU6000::measure(), ICM20948_mag::read_block(), MPU9250_mag::read_block(), ICM20948_mag::read_reg(), MPU9250_mag::read_reg(), LPS22HB::read_reg(), LPS25H::read_reg(), MPU9250::read_reg(), MPU6000::read_reg(), ICM20948::read_reg(), MPU9250::read_reg16(), MPU6000::read_reg16(), ICM20948::read_reg16(), MPU9250::read_reg_range(), ICM20948::read_reg_range(), ICM20948::reset_mpu(), ICM20948::select_register_bank(), and MPU6000::test_error().
|
inline |
Definition at line 206 of file Device.hpp.
|
inline |
Definition at line 198 of file Device.hpp.
|
inline |
Definition at line 169 of file Device.hpp.
|
inline |
Definition at line 214 of file Device.hpp.
Referenced by MS5611::init(), LPS22HB::LPS22HB(), LPS25H::LPS25H(), and MPL3115A2::MPL3115A2().
|
inlinevirtual |
Write directly to the device.
The actual size of each unit quantity is device-specific.
address | The device address at which to start writing. |
data | The buffer from which values should be read. |
count | The number of items to write. |
Definition at line 115 of file Device.hpp.
Referenced by PX4IO::io_reg_set(), ICM20948::select_register_bank(), ICM20948_mag::write_reg(), MPU9250_mag::write_reg(), LPS22HB::write_reg(), LPS25H::write_reg(), MPU9250::write_reg(), MPU6000::write_reg(), and ICM20948::write_reg().
|
protected |
if true, debug messages are printed
Definition at line 243 of file Device.hpp.
|
protected |
driver name
Definition at line 242 of file Device.hpp.