40 #ifndef _DEVICE_DEVICE_HPP 41 #define _DEVICE_DEVICE_HPP 46 #include <px4_platform_common/px4_config.h> 47 #include <px4_platform_common/posix.h> 51 #define DEVICE_LOG(FMT, ...) PX4_LOG_NAMED(_name, FMT, ##__VA_ARGS__) 52 #define DEVICE_DEBUG(FMT, ...) PX4_LOG_NAMED_COND(_name, _debug_enabled, FMT, ##__VA_ARGS__) 80 virtual ~
Device() =
default;
91 virtual int init() {
return PX4_OK; }
103 virtual int read(
unsigned address,
void *
data,
unsigned count) {
return -ENODEV; }
115 virtual int write(
unsigned address,
void *
data,
unsigned count) {
return -ENODEV; }
124 virtual int ioctl(
unsigned operation,
unsigned &arg)
127 case DEVIOCGDEVICEID:
136 DeviceBusType_UNKNOWN = 0,
137 DeviceBusType_I2C = 1,
138 DeviceBusType_SPI = 2,
139 DeviceBusType_UAVCAN = 3,
140 DeviceBusType_SIMULATION = 4,
174 case DeviceBusType_I2C:
177 case DeviceBusType_SPI:
180 case DeviceBusType_UAVCAN:
183 case DeviceBusType_SIMULATION:
186 case DeviceBusType_UNKNOWN:
229 int num_written = snprintf(buffer, length,
"Type: 0x%02X, %s:%d (0x%02X)", dev_id.devid_s.devtype,
230 get_device_bus_string(dev_id.devid_s.bus_type), dev_id.devid_s.bus, dev_id.devid_s.address);
232 buffer[length - 1] = 0;
242 const char *_name{
nullptr};
243 bool _debug_enabled{
false};
247 set_device_bus_type(DeviceBusType_UNKNOWN);
253 set_device_bus_type(bus_type);
255 set_device_address(address);
256 set_device_type(devtype);
261 set_device_bus_type(bus_type);
263 set_device_address(address);
264 set_device_type(devtype);
virtual int init()
Initialise the driver and make it ready for use.
void set_device_bus(uint8_t bus)
Namespace encapsulating all device framework classes, functions and data.
uint8_t get_device_bus() const
Return the bus ID the device is connected to.
DeviceBusType
Device bus types for DEVID.
void set_device_address(int address)
Device(const char *name, DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0)
uint32_t get_device_id() const
void set_device_bus_type(DeviceBusType bus_type)
Generic device / sensor interface.
device identifier information
virtual int write(unsigned address, void *data, unsigned count)
Write directly to the device.
virtual int ioctl(unsigned operation, unsigned &arg)
Perform a device-specific operation.
Device(DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0)
void set_device_type(uint8_t devtype)
virtual bool external() const
static int device_id_print_buffer(char *buffer, int length, uint32_t id)
Print decoded device id string to a buffer.
Fundamental base class for all physical drivers (I2C, SPI).
uint8_t get_device_type() const
Return the device type.
DeviceBusType get_device_bus_type() const
Return the bus type the device is connected to.
uint8_t get_device_address() const
Return the bus address of the device.
virtual int read(unsigned address, void *data, unsigned count)
Read directly from the device.
static const char * get_device_bus_string(DeviceBusType bus)