40 #ifndef _DEVICE_DEVICE_HPP 41 #define _DEVICE_DEVICE_HPP 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__) 73 virtual ~
Device() =
default;
84 virtual int init() {
return PX4_OK; }
96 virtual int read(
unsigned address,
void *data,
unsigned count) {
return -ENODEV; }
108 virtual int write(
unsigned address,
void *data,
unsigned count) {
return -ENODEV; }
117 virtual int ioctl(
unsigned operation,
unsigned &arg)
120 case DEVIOCGDEVICEID:
121 return (
int)_device_id.devid;
129 DeviceBusType_UNKNOWN = 0,
130 DeviceBusType_I2C = 1,
131 DeviceBusType_SPI = 2,
132 DeviceBusType_UAVCAN = 3,
142 uint32_t get_device_id()
const {
return _device_id.devid; }
154 case DeviceBusType_I2C:
157 case DeviceBusType_SPI:
160 case DeviceBusType_UAVCAN:
163 case DeviceBusType_UNKNOWN:
176 void set_device_address(
int address) { _device_id.devid_s.address = address; }
185 virtual bool external() {
return false; }
218 int num_written = snprintf(buffer, length,
"Type: 0x%02X, %s:%d (0x%02X)", dev_id.devid_s.devtype,
219 get_device_bus_string(dev_id.devid_s.bus_type), dev_id.devid_s.bus, dev_id.devid_s.address);
221 buffer[length - 1] = 0;
230 bool _debug_enabled{
false};
232 Device(
const char *name) : _name(name)
236 _device_id.devid = 0;
237 _device_id.devid_s.bus_type = DeviceBusType_UNKNOWN;
238 _device_id.devid_s.bus = 0;
239 _device_id.devid_s.address = 0;
240 _device_id.devid_s.devtype = 0;
245 _device_id.devid = 0;
246 _device_id.devid_s.bus_type = bus_type;
247 _device_id.devid_s.bus = bus;
248 _device_id.devid_s.address = address;
249 _device_id.devid_s.devtype = devtype;
uint8_t get_device_address() const
Return the bus address of the device.
Definition: Device.hpp:174
virtual int ioctl(unsigned operation, unsigned &arg)
Perform a device-specific operation.
Definition: Device.hpp:117
virtual int read(unsigned address, void *data, unsigned count)
Read directly from the device.
Definition: Device.hpp:96
DeviceBusType get_device_bus_type() const
Return the bus type the device is connected to.
Definition: Device.hpp:149
Configuration flags used in code.
Includes POSIX-like functions for virtual character devices.
Namespace encapsulating all device framework classes, functions and data.
Definition: CDev.cpp:47
virtual int write(unsigned address, void *data, unsigned count)
Write directly to the device.
Definition: Device.hpp:108
Generic device / sensor interface.
Fundamental base class for all physical drivers (I2C, SPI).
Definition: Device.hpp:65
void set_device_type(uint8_t devtype)
Set the device type.
Definition: Device.hpp:183
virtual int init()
Initialise the driver and make it ready for use.
Definition: Device.hpp:84
uint8_t get_device_bus() const
Return the bus ID the device is connected to.
Definition: Device.hpp:140
Definition: video_device.h:50
Definition: Device.hpp:193
static int device_id_print_buffer(char *buffer, int length, uint32_t id)
Print decoded device id string to a buffer.
Definition: Device.hpp:213
DeviceBusType
Device bus types for DEVID.
Definition: Device.hpp:128
const char * _name
driver name
Definition: Device.hpp:229
Definition: Device.hpp:200