Firmware
Classes | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
device::Device Class Reference

Fundamental base class for all physical drivers (I2C, SPI). More...

#include <Device.hpp>

Inheritance diagram for device::Device:
device::CDev PX4IO_serial ADIS16448_gyro ADIS16448_mag ADIS16477_gyro ADIS16497_gyro BMI160_gyro FXOS8701CQ_mag HMC5883 ICM20948_accel ICM20948_gyro ICM20948_mag LIS3MDL LSM303D_mag MPU9250_accel MPU9250_gyro MPU9250_mag QMC5883 RGBLED_PWM RM3100 UavcanCDevSensorBridgeBase

Classes

union  DeviceId
 
struct  DeviceStructure
 

Public Types

enum  DeviceBusType { DeviceBusType_UNKNOWN = 0, DeviceBusType_I2C = 1, DeviceBusType_SPI = 2, DeviceBusType_UAVCAN = 3 }
 Device bus types for DEVID.
 

Public Member Functions

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...
 
uint8_t get_device_bus () const
 Return the bus ID the device is connected to. More...
 
uint32_t get_device_id () const
 
DeviceBusType get_device_bus_type () const
 Return the bus type the device is connected to. More...
 
uint8_t get_device_address () const
 Return the bus address of the device. More...
 
void set_device_address (int address)
 
void set_device_type (uint8_t devtype)
 Set the device type. More...
 
virtual bool external ()
 

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 (DeviceBusType bus_type, uint8_t bus, uint8_t address, uint8_t devtype=0)
 
 Device (const Device &)=delete
 
Deviceoperator= (const Device &)=delete
 
 Device (Device &&)=delete
 
Deviceoperator= (Device &&)=delete
 

Protected Attributes

union DeviceId _device_id
 device identifier information
 
const char * _name
 driver name
 
bool _debug_enabled {false}
 if true, debug messages are printed
 

Detailed Description

Fundamental base class for all physical drivers (I2C, SPI).

This class provides the basic driver template for I2C and SPI devices

Constructor & Destructor Documentation

§ ~Device()

virtual device::Device::~Device ( )
virtualdefault

Destructor.

Public so that anonymous devices can be destroyed.

Member Function Documentation

§ device_id_print_buffer()

static int device::Device::device_id_print_buffer ( char *  buffer,
int  length,
uint32_t  id 
)
inlinestatic

Print decoded device id string to a buffer.

Parameters
bufferbuffer to write to
lengthbuffer length
idThe device id.
returnnumber of bytes written

§ get_device_address()

uint8_t device::Device::get_device_address ( ) const
inline

Return the bus address of the device.

Returns
The bus address

§ get_device_bus()

uint8_t device::Device::get_device_bus ( ) const
inline

Return the bus ID the device is connected to.

Returns
The bus ID

§ get_device_bus_type()

DeviceBusType device::Device::get_device_bus_type ( ) const
inline

Return the bus type the device is connected to.

Returns
The bus type

§ init()

virtual int device::Device::init ( )
inlinevirtual

Initialise the driver and make it ready for use.

Returns
OK if the driver initialized OK, negative errno otherwise;

Reimplemented in PX4IO_serial, UavcanBarometerBridge, and UavcanMagnetometerBridge.

§ ioctl()

virtual int device::Device::ioctl ( unsigned  operation,
unsigned &  arg 
)
inlinevirtual

Perform a device-specific operation.

Parameters
operationThe operation to perform.
argAn argument to the operation.
Returns
Negative errno on error, OK or positive value on success.

§ read()

virtual int device::Device::read ( unsigned  address,
void *  data,
unsigned  count 
)
inlinevirtual

Read directly from the device.

The actual size of each unit quantity is device-specific.

Parameters
offsetThe device address at which to start reading
dataThe buffer into which the read values should be placed.
countThe number of items to read.
Returns
The number of items read on success, negative errno otherwise.

Reimplemented in PX4IO_serial.

§ set_device_type()

void device::Device::set_device_type ( uint8_t  devtype)
inline

Set the device type.

Returns
The device type

§ write()

virtual int device::Device::write ( unsigned  address,
void *  data,
unsigned  count 
)
inlinevirtual

Write directly to the device.

The actual size of each unit quantity is device-specific.

Parameters
addressThe device address at which to start writing.
dataThe buffer from which values should be read.
countThe number of items to write.
Returns
The number of items written on success, negative errno otherwise.

Reimplemented in PX4IO_serial.


The documentation for this class was generated from the following file: