PX4 Firmware
PX4 Autopilot Software http://px4.io
|
Definitions for the generic base classes in the device framework. More...
#include <px4_platform_common/px4_config.h>
#include <px4_platform_common/posix.h>
#include <drivers/drv_device.h>
Go to the source code of this file.
Classes | |
class | device::Device |
Fundamental base class for all physical drivers (I2C, SPI). More... | |
struct | device::Device::DeviceStructure |
union | device::Device::DeviceId |
union | device::Device::_device_id |
device identifier information More... | |
Namespaces | |
device | |
Namespace encapsulating all device framework classes, functions and data. | |
Macros | |
#define | DEVICE_LOG(FMT, ...) PX4_LOG_NAMED(_name, FMT, ##__VA_ARGS__) |
#define | DEVICE_DEBUG(FMT, ...) PX4_LOG_NAMED_COND(_name, _debug_enabled, FMT, ##__VA_ARGS__) |
Definitions for the generic base classes in the device framework.
Definition in file Device.hpp.
#define DEVICE_DEBUG | ( | FMT, | |
... | |||
) | PX4_LOG_NAMED_COND(_name, _debug_enabled, FMT, ##__VA_ARGS__) |
Definition at line 52 of file Device.hpp.
Referenced by LidarLiteI2C::collect(), PX4FLOW::collect(), LSM303AGR::collect(), RM3100::collect(), LIS3MDL::collect(), QMC5883::collect(), HMC5883::collect(), IST8310::collect(), L3GD20::disable_i2c(), __EXPORT::I2C::I2C(), device::CDev::init(), __EXPORT::SPI::init(), ADIS16448::init(), LIS3MDL::init(), HMC5883::init(), RM3100::init(), BMI088_gyro::init(), MK::init(), BMI055_gyro::init(), QMC5883::init(), BMI055_accel::init(), BMI088_accel::init(), IST8310::init(), BMM150::init(), BMI160::init(), device::CDev::ioctl(), LIS3MDL::ioctl(), HMC5883::ioctl(), RM3100::ioctl(), QMC5883::ioctl(), PX4FLOW::measure(), LPS22HB_I2C::probe(), LPS25H_I2C::probe(), HMC5883_I2C::probe(), QMC5883_I2C::probe(), ADIS16448::probe(), BlinkM::probe(), BMI088_gyro::probe(), BMI055_gyro::probe(), BMI055_accel::probe(), BMI088_accel::probe(), IST8310::probe(), BMI160::probe(), MK::pwm_ioctl(), MS5525::Run(), ETSAirspeed::Run(), SDP3X::Run(), MEASAirspeed::Run(), PX4FLOW::Run(), PCA9685::Run(), LSM303AGR::Run(), RM3100::Run(), QMC5883::Run(), LIS3MDL::Run(), HMC5883::Run(), IST8310::Run(), ADIS16477::self_test_memory(), __EXPORT::I2C::set_bus_clock(), and __EXPORT::I2C::transfer().
#define DEVICE_LOG | ( | FMT, | |
... | |||
) | PX4_LOG_NAMED(_name, FMT, ##__VA_ARGS__) |
Definition at line 51 of file Device.hpp.
Referenced by VL53LXX::collect(), UavcanFlowBridge::init(), UavcanBarometerBridge::init(), __EXPORT::SPI::init(), PX4FLOW::init(), MK::init(), VL53LXX::measure(), UavcanCDevSensorBridgeBase::publish(), PCA9685::read8(), IRLOCK::read_device(), PMW3901::readMotionCount(), OSDatxxxx::readRegister(), PMW3901::readRegister(), __EXPORT::I2C::set_bus_clock(), PCA9685::setPWM(), RGBLED::status(), MK::task_main(), PCA9685::write8(), OSDatxxxx::writeRegister(), PMW3901::writeRegister(), and VL53LXX::writeRegisterMulti().