I2C/SPI require device type in constructor

This commit is contained in:
Daniel Agar 2020-04-01 12:24:22 -04:00 committed by GitHub
parent 04bf9afd1b
commit 02f4ad61ec
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
128 changed files with 181 additions and 351 deletions

View File

@ -44,7 +44,7 @@ constexpr px4_spi_bus_t px4_spi_buses[SPI_BUS_MAX_BUS_ITEMS] = {
}),
initSPIBus(SPI::Bus::SPI4, {
initSPIDevice(DRV_GYR_DEVTYPE_L3GD20, SPI::CS{GPIO::PortB, GPIO::Pin2}, SPI::DRDY{GPIO::PortE, GPIO::Pin4}),
initSPIDevice(DRV_ACC_DEVTYPE_LSM303D, SPI::CS{GPIO::PortD, GPIO::Pin11}),
initSPIDevice(DRV_IMU_DEVTYPE_LSM303D, SPI::CS{GPIO::PortD, GPIO::Pin11}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortE, GPIO::Pin3}, SPI::DRDY{GPIO::PortE, GPIO::Pin10}),
initSPIDevice(DRV_IMU_DEVTYPE_MPU6500, SPI::CS{GPIO::PortE, GPIO::Pin3}, SPI::DRDY{GPIO::PortE, GPIO::Pin10}),

View File

@ -36,7 +36,7 @@
using namespace time_literals;
AEROFC_ADC::AEROFC_ADC(I2CSPIBusOption bus_option, int bus_number, int bus_frequency) :
I2C("AEROFC_ADC", AEROFC_ADC_DEVICE_PATH, bus_number, SLAVE_ADDR, bus_frequency),
I2C(DRV_ADC_DEVTYPE_AEROFC, MODULE_NAME, bus_number, SLAVE_ADDR, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus_number),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": sample"))
{

View File

@ -50,7 +50,6 @@
#define ADC_ENABLE_REG 0x00
#define ADC_CHANNEL_REG 0x03
#define MAX_CHANNEL 5
#define AEROFC_ADC_DEVICE_PATH "/dev/aerofc_adc"
class AEROFC_ADC : public device::I2C, public I2CSPIDriver<AEROFC_ADC>
{

View File

@ -151,7 +151,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
initSPIDevice(DRV_GYR_DEVTYPE_L3GD20, SPI::CS{GPIO::PortC, GPIO::Pin13}, SPI::DRDY{GPIO::PortB, GPIO::Pin0}),
initSPIDevice(DRV_ACC_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5607, SPI::CS{GPIO::PortD, GPIO::Pin7}),
}, {GPIO::PortE, GPIO::Pin3}),
@ -180,7 +180,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortE, GPIO::Pin4}),
initSPIDevice(DRV_GYR_DEVTYPE_L3GD20, SPI::CS{GPIO::PortC, GPIO::Pin13}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}),
initSPIDevice(DRV_ACC_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
}),
}),

View File

@ -151,7 +151,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIDevice(DRV_IMU_DEVTYPE_MPU6000, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortC, GPIO::Pin2}, SPI::DRDY{GPIO::PortD, GPIO::Pin15}),
initSPIDevice(DRV_GYR_DEVTYPE_L3GD20, SPI::CS{GPIO::PortC, GPIO::Pin13}, SPI::DRDY{GPIO::PortB, GPIO::Pin0}),
initSPIDevice(DRV_ACC_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortD, GPIO::Pin7}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5607, SPI::CS{GPIO::PortD, GPIO::Pin7}),
}, {GPIO::PortE, GPIO::Pin3}),
@ -180,7 +180,7 @@ constexpr px4_spi_bus_all_hw_t px4_spi_buses_all_hw[BOARD_NUM_SPI_CFG_HW_VERSION
initSPIDevice(DRV_IMU_DEVTYPE_MPU9250, SPI::CS{GPIO::PortE, GPIO::Pin4}),
initSPIDevice(DRV_GYR_DEVTYPE_L3GD20, SPI::CS{GPIO::PortC, GPIO::Pin13}),
initSPIDevice(DRV_BARO_DEVTYPE_MS5611, SPI::CS{GPIO::PortC, GPIO::Pin14}),
initSPIDevice(DRV_ACC_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
initSPIDevice(DRV_IMU_DEVTYPE_LSM303D, SPI::CS{GPIO::PortC, GPIO::Pin15}),
}),
}),

View File

@ -42,7 +42,6 @@ BMP280::BMP280(I2CSPIBusOption bus_option, int bus, bmp280::IBMP280 *interface)
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
{
_px4_baro.set_device_type(DRV_BARO_DEVTYPE_BMP280);
}
BMP280::~BMP280()

View File

@ -71,7 +71,7 @@ bmp280::IBMP280 *bmp280_i2c_interface(uint8_t busnum, uint32_t device, int bus_f
}
BMP280_I2C::BMP280_I2C(uint8_t bus, uint32_t device, int bus_frequency) :
I2C("BMP280_I2C", nullptr, bus, device, bus_frequency)
I2C(DRV_BARO_DEVTYPE_BMP280, MODULE_NAME, bus, device, bus_frequency)
{
}

View File

@ -87,7 +87,7 @@ bmp280_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency, spi_mod
}
BMP280_SPI::BMP280_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("BMP280_SPI", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_BARO_DEVTYPE_BMP280, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
}

View File

@ -50,7 +50,6 @@ BMP388::BMP388(I2CSPIBusOption bus_option, int bus, IBMP388 *interface) :
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms errors"))
{
_px4_baro.set_device_type(DRV_BARO_DEVTYPE_BMP388);
}
BMP388::~BMP388()

View File

@ -68,7 +68,7 @@ IBMP388 *bmp388_i2c_interface(uint8_t busnum, uint32_t device, int bus_frequency
}
BMP388_I2C::BMP388_I2C(uint8_t bus, uint32_t device, int bus_frequency) :
I2C("BMP388_I2C", nullptr, bus, device, bus_frequency)
I2C(DRV_BARO_DEVTYPE_BMP388, MODULE_NAME, bus, device, bus_frequency)
{
}

View File

@ -84,7 +84,7 @@ IBMP388 *bmp388_spi_interface(uint8_t busnum, uint32_t device, int bus_frequency
}
BMP388_SPI::BMP388_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("BMP388_SPI", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_BARO_DEVTYPE_BMP388, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
}

View File

@ -54,7 +54,6 @@ DPS310::DPS310(I2CSPIBusOption bus_option, int bus, device::Device *interface) :
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comm errors"))
{
_px4_barometer.set_device_type(DRV_BARO_DEVTYPE_DPS310);
}
DPS310::~DPS310()

View File

@ -62,7 +62,7 @@ DPS310_I2C_interface(uint8_t bus, uint32_t address, int bus_frequency)
}
DPS310_I2C::DPS310_I2C(uint8_t bus, uint32_t address, int bus_frequency) :
I2C("DPS310_I2C", nullptr, bus, address, bus_frequency)
I2C(DRV_BARO_DEVTYPE_DPS310, MODULE_NAME, bus, address, bus_frequency)
{
}

View File

@ -66,7 +66,7 @@ DPS310_SPI_interface(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e
}
DPS310_SPI::DPS310_SPI(uint8_t bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("DPS310_SPI", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_BARO_DEVTYPE_DPS310, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
}

View File

@ -46,11 +46,9 @@ LPS22HB::LPS22HB(I2CSPIBusOption bus_option, int bus, device::Device *interface)
CDev(nullptr),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus),
_interface(interface),
_sample_perf(perf_alloc(PC_ELAPSED, "lps22hb_read")),
_comms_errors(perf_alloc(PC_COUNT, "lps22hb_comms_errors"))
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors"))
{
// set the interface device type
_interface->set_device_type(DRV_BARO_DEVTYPE_LPS22HB);
}
LPS22HB::~LPS22HB()

View File

@ -64,7 +64,7 @@ LPS22HB_I2C_interface(int bus, int bus_frequency)
}
LPS22HB_I2C::LPS22HB_I2C(int bus, int bus_frequency) :
I2C("LPS22HB_I2C", nullptr, bus, LPS22HB_ADDRESS, bus_frequency)
I2C(DRV_BARO_DEVTYPE_LPS22HB, MODULE_NAME, bus, LPS22HB_ADDRESS, bus_frequency)
{
}

View File

@ -64,9 +64,8 @@ LPS22HB_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi
}
LPS22HB_SPI::LPS22HB_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode)
: SPI("LPS22HB_SPI", nullptr, bus, device, spi_mode, bus_frequency)
: SPI(DRV_BARO_DEVTYPE_LPS22HB, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_BARO_DEVTYPE_LPS22HB;
}
int

View File

@ -40,8 +40,6 @@ LPS25H::LPS25H(I2CSPIBusOption bus_option, int bus, device::Device *interface) :
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors"))
{
_interface->set_device_type(DRV_BARO_DEVTYPE_LPS25H);
_px4_barometer.set_device_type(DRV_BARO_DEVTYPE_LPS25H);
}
LPS25H::~LPS25H()

View File

@ -65,9 +65,8 @@ device::Device *LPS25H_I2C_interface(int bus, int bus_frequency)
}
LPS25H_I2C::LPS25H_I2C(int bus, int bus_frequency) :
I2C("LPS25H_I2C", nullptr, bus, LPS25H_ADDRESS, bus_frequency)
I2C(DRV_BARO_DEVTYPE_LPS25H, MODULE_NAME, bus, LPS25H_ADDRESS, bus_frequency)
{
set_device_type(DRV_BARO_DEVTYPE_LPS25H);
}
int LPS25H_I2C::probe()

View File

@ -65,9 +65,8 @@ device::Device *LPS25H_SPI_interface(int bus, uint32_t devid, int bus_frequency,
}
LPS25H_SPI::LPS25H_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("LPS25H_SPI", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_BARO_DEVTYPE_LPS25H, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
set_device_type(DRV_BARO_DEVTYPE_LPS25H);
}
int LPS25H_SPI::init()

View File

@ -55,15 +55,13 @@
#define MPL3115A2_CTRL_TRIGGER (CTRL_REG1_OST | CTRL_REG1_OS(MPL3115A2_OSR))
MPL3115A2::MPL3115A2(I2CSPIBusOption bus_option, const int bus, int bus_frequency) :
I2C("MPL3115A2", nullptr, bus, MPL3115A2_ADDRESS, bus_frequency),
I2C(DRV_BARO_DEVTYPE_MPL3115A2, MODULE_NAME, bus, MPL3115A2_ADDRESS, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_barometer(get_device_id()),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_measure_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": measure")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err"))
{
set_device_type(DRV_BARO_DEVTYPE_MPL3115A2);
_px4_barometer.set_device_type(DRV_BARO_DEVTYPE_MPL3115A2);
}
MPL3115A2::~MPL3115A2()

View File

@ -91,7 +91,7 @@ MS5611_i2c_interface(ms5611::prom_u &prom_buf, uint32_t devid, uint8_t busnum, i
}
MS5611_I2C::MS5611_I2C(uint8_t bus, ms5611::prom_u &prom, int bus_frequency) :
I2C("MS5611_I2C", nullptr, bus, 0, bus_frequency),
I2C(DRV_BARO_DEVTYPE_MS5611, MODULE_NAME, bus, 0, bus_frequency),
_prom(prom)
{
}

View File

@ -103,7 +103,7 @@ MS5611_spi_interface(ms5611::prom_u &prom_buf, uint32_t devid, uint8_t busnum, i
}
MS5611_SPI::MS5611_SPI(uint8_t bus, uint32_t device, ms5611::prom_u &prom_buf, int bus_frequency, spi_mode_e spi_mode) :
SPI("MS5611_SPI", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_BARO_DEVTYPE_MS5611, MODULE_NAME, bus, device, spi_mode, bus_frequency),
_prom(prom_buf)
{
}

View File

@ -42,11 +42,9 @@ LeddarOne::LeddarOne(const char *serial_port, uint8_t device_orientation):
{
_serial_port = strdup(serial_port);
_px4_rangefinder.set_device_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER);
_px4_rangefinder.set_max_distance(LEDDAR_ONE_MAX_DISTANCE);
_px4_rangefinder.set_min_distance(LEDDAR_ONE_MIN_DISTANCE);
_px4_rangefinder.set_fov(LEDDAR_ONE_FIELD_OF_VIEW);
_px4_rangefinder.set_orientation(device_orientation);
}
LeddarOne::~LeddarOne()

View File

@ -43,9 +43,9 @@
LidarLiteI2C::LidarLiteI2C(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency,
const int address) :
I2C("LL40LS", nullptr, bus, address, bus_frequency),
I2C(DRV_RNG_DEVTYPE_LL40LS, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation)
_px4_rangefinder(get_device_id(), ORB_PRIO_DEFAULT, rotation)
{
_px4_rangefinder.set_min_distance(LL40LS_MIN_DISTANCE);
_px4_rangefinder.set_max_distance(LL40LS_MAX_DISTANCE);

View File

@ -135,7 +135,6 @@
#define MAPPYDOT_MAX_DISTANCE (4.f) // meters
#define MAPPYDOT_BUS_CLOCK 400000 // 400kHz bus speed
#define MAPPYDOT_DEVICE_PATH "/dev/mappydot"
/* Configuration Constants */
#define MAPPYDOT_BASE_ADDR 0x08
@ -222,7 +221,7 @@ private:
MappyDot::MappyDot(I2CSPIBusOption bus_option, const int bus, int bus_frequency) :
I2C("MappyDot", MAPPYDOT_DEVICE_PATH, bus, MAPPYDOT_BASE_ADDR, bus_frequency),
I2C(DRV_DIST_DEVTYPE_MAPPYDOT, MODULE_NAME, bus, MAPPYDOT_BASE_ADDR, bus_frequency),
ModuleParams(nullptr),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
{}

View File

@ -74,7 +74,6 @@ using namespace time_literals;
#define MB12XX_BASE_ADDR 0x70 // 7-bit address is 0x70 = 112. 8-bit address is 0xE0 = 224.
#define MB12XX_MIN_ADDR 0x5A // 7-bit address is 0x5A = 90. 8-bit address is 0xB4 = 180.
#define MB12XX_BUS_SPEED 100000 // 100kHz bus speed.
#define MB12XX_DEVICE_PATH "/dev/mb12xx"
/* MB12xx Registers addresses */
#define MB12XX_TAKE_RANGE_REG 0x51 // Measure range Register.
@ -179,7 +178,7 @@ private:
};
MB12XX::MB12XX(I2CSPIBusOption bus_option, const int bus, int bus_frequency, int address) :
I2C("MB12xx", MB12XX_DEVICE_PATH, bus, address, bus_frequency),
I2C(DRV_DIST_DEVTYPE_MB12XX, MODULE_NAME, bus, address, bus_frequency),
ModuleParams(nullptr),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, address)
{

View File

@ -84,7 +84,7 @@ uint8_t PGA460::calc_checksum(uint8_t *data, const uint8_t size)
int PGA460::close_serial()
{
int ret = px4_close(_fd);
int ret = ::close(_fd);
if (ret != 0) {
PX4_WARN("Could not close serial port");
@ -292,7 +292,7 @@ float PGA460::get_temperature()
int PGA460::open_serial()
{
_fd = px4_open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
_fd = ::open(_port, O_RDWR | O_NOCTTY | O_NONBLOCK);
if (_fd < 0) {
PX4_WARN("Failed to open serial port");

View File

@ -382,7 +382,7 @@ private:
/** @orb_advert_t orb_advert_t uORB advertisement topic. */
orb_advert_t _distance_sensor_topic{nullptr};
/** @param _fd Returns the file descriptor from px4_open(). */
/** @param _fd Returns the file descriptor from open(). */
int _fd{-1};
/** @param _port Stores the port name. */

View File

@ -49,8 +49,6 @@ SF0X::SF0X(const char *port, uint8_t rotation) :
/* enforce null termination */
_port[sizeof(_port) - 1] = '\0';
_px4_rangefinder.set_device_type(distance_sensor_s::MAV_DISTANCE_SENSOR_LASER);
}
SF0X::~SF0X()

View File

@ -75,8 +75,6 @@
/* Configuration Constants */
#define SF1XX_BASEADDR 0x66
#define SF1XX_DEVICE_PATH "/dev/sf1xx"
class SF1XX : public device::I2C, public I2CSPIDriver<SF1XX>
{
@ -166,7 +164,7 @@ private:
extern "C" __EXPORT int sf1xx_main(int argc, char *argv[]);
SF1XX::SF1XX(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
I2C("SF1XX", SF1XX_DEVICE_PATH, bus, address, bus_frequency),
I2C(DRV_DIST_DEVTYPE_SF1XX, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_rotation(rotation)
{

View File

@ -34,9 +34,9 @@
#include "SRF02.hpp"
SRF02::SRF02(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
I2C("SRF02", nullptr, bus, address, bus_frequency),
I2C(DRV_DIST_DEVTYPE_SRF02, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation)
_px4_rangefinder(get_device_id(), ORB_PRIO_DEFAULT, rotation)
{
_px4_rangefinder.set_max_distance(SRF02_MAX_DISTANCE);
_px4_rangefinder.set_min_distance(SRF02_MIN_DISTANCE);

View File

@ -74,9 +74,9 @@ static uint8_t crc8(uint8_t *p, uint8_t len)
}
TERARANGER::TERARANGER(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency) :
I2C("TERARANGER", nullptr, bus, TERARANGER_ONE_BASEADDR, bus_frequency),
I2C(DRV_DIST_DEVTYPE_TERARANGER, MODULE_NAME, bus, TERARANGER_ONE_BASEADDR, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation)
_px4_rangefinder(get_device_id(), ORB_PRIO_DEFAULT, rotation)
{
// up the retries since the device misses the first measure attempts
I2C::_retries = 3;

View File

@ -60,7 +60,7 @@
#define VL53L0X_BUS_CLOCK 400000 // 400kHz bus clock speed
VL53L0X::VL53L0X(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
I2C("VL53L0X", nullptr, bus, address, bus_frequency),
I2C(DRV_DIST_DEVTYPE_VL53L0X, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation)
{

View File

@ -53,7 +53,7 @@
*/
#define DRV_MAG_DEVTYPE_HMC5883 0x01
#define DRV_MAG_DEVTYPE_LSM303D 0x02
#define DRV_MAG_DEVTYPE_LSM303D_LEGACY 0x02
#define DRV_MAG_DEVTYPE_MAGSIM 0x03
#define DRV_MAG_DEVTYPE_AK8963 0x04
#define DRV_MAG_DEVTYPE_LIS3MDL 0x05
@ -64,7 +64,7 @@
#define DRV_IMU_DEVTYPE_ICM20948 0x0A
#define DRV_MAG_DEVTYPE_IST8308 0x0B
#define DRV_ACC_DEVTYPE_LSM303D 0x11
#define DRV_IMU_DEVTYPE_LSM303D 0x11
#define DRV_ACC_DEVTYPE_BMA180 0x12
#define DRV_ACC_DEVTYPE_MPU6000_LEGACY 0x13
#define DRV_ACC_DEVTYPE_ACCELSIM 0x14

View File

@ -39,18 +39,13 @@
ADIS16448::ADIS16448(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("ADIS16448", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ADIS16448, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_MAX, rotation),
_px4_baro(get_device_id(), ORB_PRIO_MAX),
_px4_gyro(get_device_id(), ORB_PRIO_MAX, rotation),
_px4_mag(get_device_id(), ORB_PRIO_MAX, rotation)
{
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ADIS16448);
_px4_baro.set_device_type(DRV_IMU_DEVTYPE_ADIS16448);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ADIS16448);
_px4_mag.set_device_type(DRV_IMU_DEVTYPE_ADIS16448);
_px4_accel.set_scale(ADIS16448_ACCEL_SENSITIVITY);
_px4_gyro.set_scale(ADIS16448_GYRO_INITIAL_SENSITIVITY);
_px4_mag.set_scale(ADIS16448_MAG_SENSITIVITY);

View File

@ -55,12 +55,12 @@ using namespace time_literals;
ADIS16477::ADIS16477(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI("ADIS16477", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ADIS16477, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_MAX, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_MAX, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "adis16477: read")),
_bad_transfers(perf_alloc(PC_COUNT, "adis16477: bad transfers")),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
_drdy_gpio(drdy_gpio)
{
#ifdef GPIO_SPI1_RESET_ADIS16477
@ -68,10 +68,8 @@ ADIS16477::ADIS16477(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
px4_arch_configgpio(GPIO_SPI1_RESET_ADIS16477);
#endif // GPIO_SPI1_RESET_ADIS16477
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ADIS16477);
_px4_accel.set_scale(1.25f * CONSTANTS_ONE_G / 1000.0f); // accel 1.25 mg/LSB
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ADIS16477);
_px4_gyro.set_scale(math::radians(0.025f)); // gyro 0.025 °/sec/LSB
}

View File

@ -72,21 +72,18 @@ using namespace time_literals;
ADIS16497::ADIS16497(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI("ADIS16497", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ADIS16497, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_MAX, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_MAX, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "adis16497: read")),
_bad_transfers(perf_alloc(PC_COUNT, "adis16497: bad transfers")),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
_drdy_gpio(drdy_gpio)
{
#ifdef GPIO_SPI1_RESET_ADIS16497
// Configure hardware reset line
px4_arch_configgpio(GPIO_SPI1_RESET_ADIS16497);
#endif // GPIO_SPI1_RESET_ADIS16497
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ADIS16497);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ADIS16497);
}
ADIS16497::~ADIS16497()

View File

@ -220,7 +220,7 @@ private:
BMA180::BMA180(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("BMA180", ACCEL_DEVICE_PATH, bus, device, spi_mode, bus_frequency),
SPI(DRV_ACC_DEVTYPE_BMA180, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_call_interval(0),
_reports(nullptr),
@ -232,8 +232,6 @@ BMA180::BMA180(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
_current_range(0),
_sample_perf(perf_alloc(PC_ELAPSED, "bma180_read"))
{
_device_id.devid_s.devtype = DRV_ACC_DEVTYPE_BMA180;
// default scale factors
_accel_scale.x_offset = 0;
_accel_scale.x_scale = 1.0f;

View File

@ -53,7 +53,7 @@
class BMI055 : public device::SPI, public I2CSPIDriver<BMI055>
{
public:
BMI055(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
BMI055(uint8_t devtype, const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, uint32_t device,
enum spi_mode_e mode, uint32_t frequency, enum Rotation rotation);
virtual ~BMI055() = default;

View File

@ -46,8 +46,7 @@ const uint8_t BMI055_accel::_checked_registers[BMI055_ACCEL_NUM_CHECKED_REGISTER
BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path_accel, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_accel", path_accel, bus_option, bus, DRV_ACC_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
BMI055(DRV_ACC_DEVTYPE_BMI055, "bmi055_accel", path_accel, bus_option, bus, device, spi_mode, bus_frequency, rotation),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_accel_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_accel_bad_transfers")),
@ -55,7 +54,6 @@ BMI055_accel::BMI055_accel(I2CSPIBusOption bus_option, int bus, const char *path
_duplicates(perf_alloc(PC_COUNT, "bmi055_accel_duplicates")),
_got_duplicate(false)
{
_px4_accel.set_device_type(DRV_ACC_DEVTYPE_BMI055);
}
BMI055_accel::~BMI055_accel()

View File

@ -51,14 +51,12 @@ const uint8_t BMI055_gyro::_checked_registers[BMI055_GYRO_NUM_CHECKED_REGISTERS]
BMI055_gyro::BMI055_gyro(I2CSPIBusOption bus_option, int bus, const char *path_gyro, uint32_t device,
enum Rotation rotation, int bus_frequency, spi_mode_e spi_mode) :
BMI055("bmi055_gyro", path_gyro, bus_option, bus, DRV_GYR_DEVTYPE_BMI055, device, spi_mode, bus_frequency,
rotation),
BMI055(DRV_GYR_DEVTYPE_BMI055, "bmi055_gyro", path_gyro, bus_option, bus, device, spi_mode, bus_frequency, rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, "bmi055_gyro_read")),
_bad_transfers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi055_gyro_bad_registers"))
{
_px4_gyro.set_device_type(DRV_GYR_DEVTYPE_BMI055);
}
BMI055_gyro::~BMI055_gyro()

View File

@ -97,11 +97,10 @@ BMI055::custom_method(const BusCLIArguments &cli)
}
}
BMI055::BMI055(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
enum spi_mode_e mode,
uint32_t frequency, enum Rotation rotation):
SPI(name, devname, bus, device, mode, frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, type),
BMI055::BMI055(uint8_t devtype, const char *name, const char *devname, I2CSPIBusOption bus_option, int bus,
uint32_t device, enum spi_mode_e mode, uint32_t frequency, enum Rotation rotation):
SPI(devtype, name, bus, device, mode, frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, devtype),
_whoami(0),
_register_wait(0),
_reset_wait(0),

View File

@ -53,7 +53,7 @@
class BMI088 : public device::SPI, public I2CSPIDriver<BMI088>
{
public:
BMI088(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
BMI088(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, uint8_t type, uint32_t device,
enum spi_mode_e mode, uint32_t frequency, enum Rotation rotation);
virtual ~BMI088() = default;

View File

@ -63,7 +63,6 @@ BMI088_accel::BMI088_accel(I2CSPIBusOption bus_option, int bus, const char *path
_duplicates(perf_alloc(PC_COUNT, "bmi088_accel_duplicates")),
_got_duplicate(false)
{
_px4_accel.set_device_type(DRV_ACC_DEVTYPE_BMI088);
}
BMI088_accel::~BMI088_accel()

View File

@ -65,7 +65,6 @@ BMI088_gyro::BMI088_gyro(I2CSPIBusOption bus_option, int bus, const char *path_g
_bad_transfers(perf_alloc(PC_COUNT, "bmi088_gyro_bad_transfers")),
_bad_registers(perf_alloc(PC_COUNT, "bmi088_gyro_bad_registers"))
{
_px4_gyro.set_device_type(DRV_GYR_DEVTYPE_BMI088);
}
BMI088_gyro::~BMI088_gyro()

View File

@ -96,10 +96,11 @@ BMI088::custom_method(const BusCLIArguments &cli)
}
}
BMI088::BMI088(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, int type, uint32_t device,
BMI088::BMI088(const char *name, const char *devname, I2CSPIBusOption bus_option, int bus, uint8_t type,
uint32_t device,
enum spi_mode_e mode,
uint32_t frequency, enum Rotation rotation):
SPI(name, devname, bus, device, mode, frequency),
SPI(type, MODULE_NAME, bus, device, mode, frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, type),
_whoami(0),
_register_wait(0),

View File

@ -51,7 +51,7 @@ const uint8_t BMI160::_checked_registers[BMI160_NUM_CHECKED_REGISTERS] = { BM
BMI160::BMI160(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("BMI160", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_BMI160, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_MAX - 1 : ORB_PRIO_HIGH - 1), rotation),
@ -64,8 +64,6 @@ BMI160::BMI160(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
_reset_retries(perf_alloc(PC_COUNT, "bmi160_reset_retries")),
_duplicates(perf_alloc(PC_COUNT, "bmi160_duplicates"))
{
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_BMI160);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_BMI160);
}
BMI160::~BMI160()

View File

@ -188,7 +188,7 @@ using namespace time_literals;
FXAS21002C::FXAS21002C(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("FXAS21002C", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_GYR_DEVTYPE_FXAS2100C, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_gyro(get_device_id(), (external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
@ -196,7 +196,6 @@ FXAS21002C::FXAS21002C(I2CSPIBusOption bus_option, int bus, uint32_t device, enu
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad register")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": duplicate reading"))
{
_px4_gyro.set_device_type(DRV_GYR_DEVTYPE_FXAS2100C);
}
FXAS21002C::~FXAS21002C()

View File

@ -55,7 +55,7 @@ const uint8_t FXOS8701CQ::_checked_registers[FXOS8701C_NUM_CHECKED_REGISTERS] =
FXOS8701CQ::FXOS8701CQ(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("FXOS8701CQ", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_ACC_DEVTYPE_FXOS8701C, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_LOW, rotation),
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
@ -66,12 +66,7 @@ FXOS8701CQ::FXOS8701CQ(I2CSPIBusOption bus_option, int bus, uint32_t device, enu
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad reg")),
_accel_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": acc dupe"))
{
set_device_type(DRV_ACC_DEVTYPE_FXOS8701C);
_px4_accel.set_device_type(DRV_ACC_DEVTYPE_FXOS8701C);
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
_px4_mag.set_device_type(DRV_ACC_DEVTYPE_FXOS8701C);
_px4_mag.set_scale(0.001f);
#endif
}

View File

@ -56,11 +56,12 @@ ICM20948_mag::ICM20948_mag(ICM20948 *parent, device::Device *interface, enum Rot
_px4_mag(parent->_interface->get_device_id(), (parent->_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH),
rotation),
_parent(parent),
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag_overruns")),
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag_overflows")),
_mag_errors(perf_alloc(PC_COUNT, MODULE_NAME": mag_errors"))
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag overruns")),
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag overflows")),
_mag_errors(perf_alloc(PC_COUNT, MODULE_NAME": mag errors"))
{
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_AK09916);
_px4_mag.set_external(_parent->is_external());
_px4_mag.set_scale(ICM20948_MAG_RANGE_GA);
}

View File

@ -102,8 +102,6 @@ ICM20948::ICM20948(device::Device *interface, device::Device *mag_interface, enu
_good_transfers(perf_alloc(PC_COUNT, MODULE_NAME": good_trans")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": dupe"))
{
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20948);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20948);
}
ICM20948::~ICM20948()

View File

@ -68,9 +68,8 @@ ICM20948_I2C_interface(int bus, uint32_t address, int bus_frequency)
}
ICM20948_I2C::ICM20948_I2C(int bus, uint32_t address, int bus_frequency) :
I2C("ICM20948_I2C", nullptr, bus, address, bus_frequency)
I2C(DRV_IMU_DEVTYPE_ICM20948, MODULE_NAME, bus, address, bus_frequency)
{
_device_id.devid_s.devtype = DRV_IMU_DEVTYPE_ICM20948;
}
int

View File

@ -86,9 +86,8 @@ ICM20948_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e sp
}
ICM20948_SPI::ICM20948_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("ICM20948", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_IMU_DEVTYPE_ICM20948, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_IMU_DEVTYPE_ICM20948;
}
void

View File

@ -65,9 +65,8 @@ AK09916_I2C_interface(int bus, int bus_frequency)
}
AK09916_I2C::AK09916_I2C(int bus, int bus_frequency) :
I2C("AK09916_I2C", nullptr, bus, AK09916_I2C_ADDR, bus_frequency)
I2C(DRV_IMU_DEVTYPE_ICM20948, "AK09916_I2C", bus, AK09916_I2C_ADDR, bus_frequency)
{
_device_id.devid_s.devtype = DRV_IMU_DEVTYPE_ICM20948;
}
int

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
ICM20602::ICM20602(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ICM20602, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ICM20602);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20602);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20602);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
ICM20608G::ICM20608G(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ICM20608G, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
ICM20689::ICM20689(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ICM20689, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ICM20689);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20689);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20689);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
ICM40609D::ICM40609D(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ICM40609D, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ICM40609D);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM40609D);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM40609D);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
ICM42688P::ICM42688P(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ICM42688P, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ICM42688P);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM42688P);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM42688P);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
MPU6000::MPU6000(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_MPU6000, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_MPU6000);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_MPU6000);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_MPU6000);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -42,17 +42,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
MPU6500::MPU6500(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_MPU6500, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_MPU6500);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_MPU6500);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_MPU6500);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
}

View File

@ -44,17 +44,12 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
MPU9250::MPU9250(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio, bool enable_magnetometer) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_MPU9250, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_MPU9250);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_MPU9250);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_MPU9250);
ConfigureSampleRate(_px4_gyro.get_max_rate_hz());
if (enable_magnetometer) {

View File

@ -37,7 +37,7 @@ constexpr uint8_t L3GD20::_checked_registers[];
L3GD20::L3GD20(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("L3GD20", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_GYR_DEVTYPE_L3GD20, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_gyro(get_device_id(), ORB_PRIO_DEFAULT, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
@ -45,7 +45,6 @@ L3GD20::L3GD20(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotati
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad_reg")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": dupe"))
{
_px4_gyro.set_device_type(DRV_GYR_DEVTYPE_L3GD20);
}
L3GD20::~L3GD20()

View File

@ -55,7 +55,7 @@ static constexpr uint8_t _checked_registers[] = {
LSM303D::LSM303D(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("LSM303D", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_LSM303D, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_DEFAULT, rotation),
_px4_mag(get_device_id(), ORB_PRIO_LOW, rotation),
@ -65,8 +65,6 @@ LSM303D::LSM303D(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
_bad_values(perf_alloc(PC_COUNT, "lsm303d: bad_val")),
_accel_duplicates(perf_alloc(PC_COUNT, "lsm303d: acc_dupe"))
{
_px4_accel.set_device_type(DRV_ACC_DEVTYPE_LSM303D);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_LSM303D);
_px4_mag.set_external(external());
}

View File

@ -93,7 +93,7 @@ extern "C" int lsm303d_main(int argc, char *argv[])
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_ACC_DEVTYPE_LSM303D);
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_LSM303D);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);

View File

@ -55,21 +55,25 @@ MPU6000::MPU6000(device::Device *interface, enum Rotation rotation, int device_t
switch (_device_type) {
default:
case MPU_DEVICE_TYPE_MPU6000:
_interface->set_device_type(DRV_IMU_DEVTYPE_MPU6000);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_MPU6000);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_MPU6000);
break;
case MPU_DEVICE_TYPE_ICM20602:
_interface->set_device_type(DRV_IMU_DEVTYPE_ICM20602);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20602);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20602);
break;
case MPU_DEVICE_TYPE_ICM20608:
_interface->set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20608G);
break;
case MPU_DEVICE_TYPE_ICM20689:
_interface->set_device_type(DRV_IMU_DEVTYPE_ICM20689);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ICM20689);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ICM20689);
break;

View File

@ -70,7 +70,7 @@ MPU6000_I2C_interface(int bus, uint32_t devid, int device_type, bool external_bu
}
MPU6000_I2C::MPU6000_I2C(int bus, int device_type, int bus_frequency) :
I2C("MPU6000_I2C", nullptr, bus, PX4_I2C_MPU6050_ADDR, bus_frequency),
I2C(DRV_IMU_DEVTYPE_MPU6000, MODULE_NAME, bus, PX4_I2C_MPU6050_ADDR, bus_frequency)
_device_type(device_type)
{
}

View File

@ -105,7 +105,7 @@ MPU6000_SPI_interface(int bus, uint32_t devid, int device_type, bool external_bu
}
MPU6000_SPI::MPU6000_SPI(int bus, uint32_t device, int device_type, int bus_frequency, spi_mode_e spi_mode) :
SPI("MPU6000", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_MPU6000, MODULE_NAME, bus, device, spi_mode, bus_frequency),
_device_type(device_type)
{
}

View File

@ -68,9 +68,9 @@ AK8963_I2C_interface(int bus, int bus_frequency)
return new AK8963_I2C(bus, bus_frequency);
}
AK8963_I2C::AK8963_I2C(int bus, int bus_frequency) : I2C("AK8963_I2C", nullptr, bus, AK8963_I2C_ADDR, bus_frequency)
AK8963_I2C::AK8963_I2C(int bus, int bus_frequency) :
I2C(DRV_MAG_DEVTYPE_AK8963, "AK8963_I2C", bus, AK8963_I2C_ADDR, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_AK8963;
}
int

View File

@ -56,11 +56,12 @@ MPU9250_mag::MPU9250_mag(MPU9250 *parent, device::Device *interface, enum Rotati
_px4_mag(parent->_interface->get_device_id(), (parent->_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH),
rotation),
_parent(parent),
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag_overruns")),
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag_overflows")),
_mag_errors(perf_alloc(PC_COUNT, MODULE_NAME": mag_errors"))
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag overruns")),
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag overflows")),
_mag_errors(perf_alloc(PC_COUNT, MODULE_NAME": mag errors"))
{
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_AK8963);
_px4_mag.set_external(_parent->is_external());
_px4_mag.set_scale(MPU9250_MAG_RANGE_GA);
}
@ -138,7 +139,6 @@ bool MPU9250_mag::_measure(const hrt_abstime &timestamp_sample, const ak8963_reg
return false;
}
_px4_mag.set_external(_parent->is_external());
_px4_mag.set_temperature(_parent->_last_temperature);
/*

View File

@ -82,8 +82,6 @@ MPU9250::MPU9250(device::Device *interface, device::Device *mag_interface, enum
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad_reg")),
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": dupe"))
{
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_MPU9250);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_MPU9250);
}
MPU9250::~MPU9250()

View File

@ -68,9 +68,8 @@ MPU9250_I2C_interface(int bus, uint32_t address, int bus_frequency)
}
MPU9250_I2C::MPU9250_I2C(int bus, uint32_t address, int bus_frequency) :
I2C("MPU9250_I2C", nullptr, bus, address, bus_frequency)
I2C(DRV_IMU_DEVTYPE_MPU9250, MODULE_NAME, bus, address, bus_frequency)
{
set_device_type(DRV_IMU_DEVTYPE_MPU9250);
}
int

View File

@ -86,9 +86,8 @@ MPU9250_SPI_interface(int bus, uint32_t cs, int bus_frequency, spi_mode_e spi_mo
}
MPU9250_SPI::MPU9250_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("MPU9250", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_IMU_DEVTYPE_MPU9250, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
set_device_type(DRV_IMU_DEVTYPE_MPU9250);
}
void

View File

@ -41,16 +41,12 @@ static constexpr uint32_t FIFO_INTERVAL{1000}; // 1000 us / 1000 Hz interval
ISM330DLC::ISM330DLC(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ST_ISM330DLC, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_drdy_gpio(drdy_gpio),
_px4_accel(get_device_id(), ORB_PRIO_DEFAULT, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_DEFAULT, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ST_ISM330DLC);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ST_ISM330DLC);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ST_ISM330DLC);
_px4_accel.set_update_rate(1000000 / FIFO_INTERVAL);
_px4_gyro.set_update_rate(1000000 / FIFO_INTERVAL);
}

View File

@ -40,15 +40,11 @@ static constexpr int16_t combine(uint8_t lsb, uint8_t msb) { return (msb << 8u)
LSM9DS1::LSM9DS1(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_IMU_DEVTYPE_ST_LSM9DS1_AG, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_accel(get_device_id(), ORB_PRIO_DEFAULT, rotation),
_px4_gyro(get_device_id(), ORB_PRIO_DEFAULT, rotation)
{
set_device_type(DRV_IMU_DEVTYPE_ST_LSM9DS1_AG);
_px4_accel.set_device_type(DRV_IMU_DEVTYPE_ST_LSM9DS1_AG);
_px4_gyro.set_device_type(DRV_IMU_DEVTYPE_ST_LSM9DS1_AG);
_px4_accel.set_update_rate(1000000 / _fifo_interval);
_px4_gyro.set_update_rate(1000000 / _fifo_interval);
}

View File

@ -88,8 +88,7 @@ extern "C" __EXPORT int lsm9ds1_main(int argc, char *argv[])
return -1;
}
BusInstanceIterator iterator(MODULE_NAME, cli,
DRV_IMU_DEVTYPE_ST_LSM9DS1_AG);
BusInstanceIterator iterator(MODULE_NAME, cli, DRV_IMU_DEVTYPE_ST_LSM9DS1_AG);
if (!strcmp(verb, "start")) {
return ThisDriver::module_start(cli, iterator);

View File

@ -75,9 +75,6 @@
#define IRLOCK_TAN_ANG_PER_PIXEL_X (2*IRLOCK_TAN_HALF_FOV_X/IRLOCK_RES_X)
#define IRLOCK_TAN_ANG_PER_PIXEL_Y (2*IRLOCK_TAN_HALF_FOV_Y/IRLOCK_RES_Y)
#define IRLOCK_BASE_DEVICE_PATH "/dev/irlock"
#define IRLOCK0_DEVICE_PATH "/dev/irlock0"
#define IRLOCK_OBJECTS_MAX 5 /** up to 5 objects can be detected/reported **/
struct irlock_target_s {
@ -139,7 +136,7 @@ private:
extern "C" __EXPORT int irlock_main(int argc, char *argv[]);
IRLOCK::IRLOCK(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
I2C("irlock", IRLOCK0_DEVICE_PATH, bus, address, bus_frequency),
I2C(DRV_SENS_DEVTYPE_IRLOCK, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus, address),
_reports(nullptr),
_sensor_ok(false),

View File

@ -118,7 +118,7 @@ class BlinkM : public device::I2C, public I2CSPIDriver<BlinkM>
{
public:
BlinkM(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address);
virtual ~BlinkM() = default;
~BlinkM() override;
static I2CSPIDriverBase *instantiate(const BusCLIArguments &cli, const BusInstanceIterator &iterator,
int runtime_instance);
@ -254,7 +254,7 @@ const char *const BlinkM::script_names[] = {
extern "C" __EXPORT int blinkm_main(int argc, char *argv[]);
BlinkM::BlinkM(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
I2C("blinkm", BLINKM0_DEVICE_PATH, bus, address, bus_frequency),
I2C(DRV_LED_DEVTYPE_BLINKM, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
led_color_1(LED_OFF),
led_color_2(LED_OFF),
@ -276,6 +276,13 @@ BlinkM::BlinkM(I2CSPIBusOption bus_option, const int bus, int bus_frequency, con
led_thread_ready(true),
num_of_used_sats(0)
{
// now register the driver
register_driver(BLINKM0_DEVICE_PATH, &fops, 0666, (void *)this);
}
BlinkM::~BlinkM()
{
unregister_driver(BLINKM0_DEVICE_PATH);
}
int

View File

@ -100,7 +100,7 @@ private:
};
RGBLED::RGBLED(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
I2C("rgbled", nullptr, bus, address, bus_frequency),
I2C(DRV_LED_DEVTYPE_RGBLED, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
{
}

View File

@ -100,7 +100,7 @@ private:
};
RGBLED_NPC5623C::RGBLED_NPC5623C(I2CSPIBusOption bus_option, const int bus, int bus_frequency, const int address) :
I2C("rgbled1", nullptr, bus, address, bus_frequency),
I2C(DRV_LED_DEVTYPE_RGBLED_NCP5623C, MODULE_NAME, bus, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus)
{
}

View File

@ -48,7 +48,7 @@
extern "C" __EXPORT int ak09916_main(int argc, char *argv[]);
AK09916::AK09916(I2CSPIBusOption bus_option, const int bus, int bus_frequency, enum Rotation rotation) :
I2C("AK09916", nullptr, bus, AK09916_I2C_ADDR, bus_frequency),
I2C(DRV_MAG_DEVTYPE_AK09916, MODULE_NAME, bus, AK09916_I2C_ADDR, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation),
_mag_reads(perf_alloc(PC_COUNT, MODULE_NAME": mag_reads")),
@ -56,10 +56,7 @@ AK09916::AK09916(I2CSPIBusOption bus_option, const int bus, int bus_frequency, e
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag_overruns")),
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag_overflows"))
{
set_device_type(DRV_MAG_DEVTYPE_AK09916);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_AK09916);
_px4_mag.set_external(external());
_px4_mag.set_scale(AK09916_MAG_RANGE_GA);
}

View File

@ -41,7 +41,7 @@
#include <px4_platform_common/module.h>
BMM150::BMM150(I2CSPIBusOption bus_option, const int bus, int bus_frequency, enum Rotation rotation) :
I2C("BMM150", nullptr, bus, BMM150_SLAVE_ADDRESS, bus_frequency),
I2C(DRV_MAG_DEVTYPE_BMM150, MODULE_NAME, bus, BMM150_SLAVE_ADDRESS, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation),
_call_interval(0),
@ -67,9 +67,6 @@ BMM150::BMM150(I2CSPIBusOption bus_option, const int bus, int bus_frequency, enu
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": duplicates")),
_got_duplicate(false)
{
set_device_type(DRV_MAG_DEVTYPE_BMM150);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_BMM150);
_px4_mag.set_external(external());
// default range scale from from uT to gauss

View File

@ -48,8 +48,6 @@ HMC5883::HMC5883(device::Device *interface, enum Rotation rotation, I2CSPIBusOpt
_temperature_counter(0),
_temperature_error_count(0)
{
_interface->set_device_type(DRV_MAG_DEVTYPE_HMC5883);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_HMC5883);
_px4_mag.set_external(_interface->external());
}

View File

@ -68,9 +68,8 @@ HMC5883_I2C_interface(int bus, int bus_frequency)
}
HMC5883_I2C::HMC5883_I2C(int bus, int bus_frequency) :
I2C("HMC5883_I2C", nullptr, bus, HMC5883L_ADDRESS, bus_frequency)
I2C(DRV_MAG_DEVTYPE_HMC5883, MODULE_NAME, bus, HMC5883L_ADDRESS, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
}
int HMC5883_I2C::probe()

View File

@ -72,9 +72,8 @@ HMC5883_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi
}
HMC5883_SPI::HMC5883_SPI(int bus, uint32_t device, int bus_frequency, spi_mode_e spi_mode) :
SPI("HMC5883_SPI", nullptr, bus, device, spi_mode, bus_frequency)
SPI(DRV_MAG_DEVTYPE_HMC5883, MODULE_NAME, bus, device, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_HMC5883;
}
int HMC5883_SPI::init()

View File

@ -41,13 +41,10 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
}
IST8308::IST8308(I2CSPIBusOption bus_option, int bus, enum Rotation rotation, int bus_frequency) :
I2C(MODULE_NAME, nullptr, bus, I2C_ADDRESS_DEFAULT, bus_frequency),
I2C(DRV_MAG_DEVTYPE_IST8308, MODULE_NAME, bus, I2C_ADDRESS_DEFAULT, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation)
{
set_device_type(DRV_MAG_DEVTYPE_IST8308);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_IST8308);
_px4_mag.set_external(external());
}

View File

@ -269,7 +269,7 @@ private:
};
IST8310::IST8310(I2CSPIBusOption bus_option, int bus_number, int address, enum Rotation rotation, int bus_frequency) :
I2C("IST8310", nullptr, bus_number, address, bus_frequency),
I2C(DRV_MAG_DEVTYPE_IST8310, MODULE_NAME, bus_number, address, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus_number, address),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
@ -277,9 +277,6 @@ IST8310::IST8310(I2CSPIBusOption bus_option, int bus_number, int address, enum R
_range_errors(perf_alloc(PC_COUNT, MODULE_NAME": rng_err")),
_conf_errors(perf_alloc(PC_COUNT, MODULE_NAME": conf_err"))
{
set_device_type(DRV_MAG_DEVTYPE_IST8310);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_IST8310);
_px4_mag.set_external(external());
// default range scale from counts to gauss

View File

@ -65,9 +65,6 @@ LIS3MDL::LIS3MDL(device::Device *interface, enum Rotation rotation, I2CSPIBusOpt
_temperature_counter(0),
_temperature_error_count(0)
{
_interface->set_device_type(DRV_MAG_DEVTYPE_IST8310);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_IST8310);
_px4_mag.set_external(_interface->external());
}

View File

@ -81,9 +81,8 @@ LIS3MDL_I2C_interface(int bus, int bus_frequency)
}
LIS3MDL_I2C::LIS3MDL_I2C(int bus, int bus_frequency) :
I2C("LIS3MDL_I2C", nullptr, bus, LIS3MDLL_ADDRESS, bus_frequency)
I2C(DRV_MAG_DEVTYPE_LIS3MDL, MODULE_NAME, bus, LIS3MDLL_ADDRESS, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LIS3MDL;
}
int LIS3MDL_I2C::probe()

View File

@ -81,9 +81,8 @@ LIS3MDL_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi
}
LIS3MDL_SPI::LIS3MDL_SPI(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode) :
SPI("LIS3MDL_SPI", nullptr, bus, devid, spi_mode, bus_frequency)
SPI(DRV_MAG_DEVTYPE_LIS3MDL, MODULE_NAME, bus, devid, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_LIS3MDL;
}
int

View File

@ -63,16 +63,13 @@ static constexpr uint8_t LSM303AGR_WHO_AM_I_M = 0x40;
LSM303AGR::LSM303AGR(I2CSPIBusOption bus_option, int bus, int device, enum Rotation rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("LSM303AGR", nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_MAG_DEVTYPE_LSM303AGR, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation),
_mag_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": mag_read")),
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad_reg")),
_bad_values(perf_alloc(PC_COUNT, MODULE_NAME": bad_val"))
{
set_device_type(DRV_MAG_DEVTYPE_LSM303AGR);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_LSM303AGR);
_px4_mag.set_external(external());
_px4_mag.set_scale(1.5f / 1000.f); // 1.5 milligauss/LSB

View File

@ -42,13 +42,10 @@ static constexpr int16_t combine(uint8_t lsb, uint8_t msb) { return (msb << 8u)
LSM9DS1_MAG::LSM9DS1_MAG(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotation rotation,
int bus_frequency, spi_mode_e spi_mode) :
SPI(MODULE_NAME, nullptr, bus, device, spi_mode, bus_frequency),
SPI(DRV_MAG_DEVTYPE_ST_LSM9DS1_M, MODULE_NAME, bus, device, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_px4_mag(get_device_id(), external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation)
{
set_device_type(DRV_MAG_DEVTYPE_ST_LSM9DS1_M);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_ST_LSM9DS1_M);
_px4_mag.set_external(external());
}

View File

@ -47,9 +47,6 @@ QMC5883::QMC5883(device::Device *interface, enum Rotation rotation, I2CSPIBusOpt
_temperature_counter(0),
_temperature_error_count(0)
{
_interface->set_device_type(DRV_MAG_DEVTYPE_QMC5883);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_QMC5883);
_px4_mag.set_external(_interface->external());
}

View File

@ -66,9 +66,8 @@ QMC5883_I2C_interface(int bus, int bus_frequency, int i2c_address)
}
QMC5883_I2C::QMC5883_I2C(int bus, int bus_frequency, int i2c_address) :
I2C("QMC5883_I2C", nullptr, bus, i2c_address, bus_frequency)
I2C(DRV_MAG_DEVTYPE_QMC5883, MODULE_NAME, bus, i2c_address, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_QMC5883;
}
int QMC5883_I2C::probe()

View File

@ -54,9 +54,6 @@ RM3100::RM3100(device::Device *interface, enum Rotation rotation, I2CSPIBusOptio
_measure_interval(0),
_check_state_cnt(0)
{
_interface->set_device_type(DRV_MAG_DEVTYPE_RM3100);
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_RM3100);
_px4_mag.set_external(_interface->external());
_px4_mag.set_scale(1.f / (RM3100_SENSITIVITY * UTESLA_TO_GAUSS));

View File

@ -80,9 +80,8 @@ RM3100_I2C_interface(int bus, int bus_frequency)
}
RM3100_I2C::RM3100_I2C(int bus, int bus_frequency) :
I2C("RM300_I2C", nullptr, bus, RM3100_ADDRESS, bus_frequency)
I2C(DRV_MAG_DEVTYPE_RM3100, MODULE_NAME, bus, RM3100_ADDRESS, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_RM3100;
}
int RM3100_I2C::probe()

View File

@ -80,9 +80,8 @@ RM3100_SPI_interface(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_
}
RM3100_SPI::RM3100_SPI(int bus, uint32_t devid, int bus_frequency, spi_mode_e spi_mode) :
SPI("RM3100_SPI", nullptr, bus, devid, spi_mode, bus_frequency)
SPI(DRV_MAG_DEVTYPE_RM3100, MODULE_NAME, bus, devid, spi_mode, bus_frequency)
{
_device_id.devid_s.devtype = DRV_MAG_DEVTYPE_RM3100;
}
int RM3100_SPI::init()

View File

@ -218,7 +218,7 @@ MK *g_mk;
} // namespace
MK::MK(int bus, const char *_device_path) :
I2C("mkblctrl", "/dev/mkblctrl0", bus, 0, I2C_BUS_SPEED),
I2C(0, "mkblctrl", bus, 0, I2C_BUS_SPEED),
_update_rate(UPDATE_RATE),
_task(-1),
_t_actuators(-1),

View File

@ -35,11 +35,11 @@
PAW3902::PAW3902(I2CSPIBusOption bus_option, int bus, int devid, enum Rotation yaw_rotation, int bus_frequency,
spi_mode_e spi_mode) :
SPI("PAW3902", nullptr, bus, devid, spi_mode, bus_frequency),
SPI(DRV_FLOW_DEVTYPE_PAW3902, MODULE_NAME, bus, devid, spi_mode, bus_frequency),
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(get_device_id()), bus_option, bus),
_sample_perf(perf_alloc(PC_ELAPSED, "paw3902: read")),
_comms_errors(perf_alloc(PC_COUNT, "paw3902: com_err")),
_dupe_count_perf(perf_alloc(PC_COUNT, "paw3902: duplicate reading")),
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err")),
_dupe_count_perf(perf_alloc(PC_COUNT, MODULE_NAME": duplicate reading")),
_yaw_rotation(yaw_rotation)
{
}

Some files were not shown because too many files have changed in this diff Show More