mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-05-25 00:31:36 +08:00
move initial sensor priority to parameters and purge ORB_PRIORITY
- CAL_ACCx_EN -> CAL_ACCx_PRIO - CAL_GYROx_EN -> CAL_GYROx_PRIO - CAL_MAGx_EN -> CAL_MAGx_PRIO
This commit is contained in:
@@ -87,7 +87,7 @@ static constexpr unsigned char crc_lsb_vector[] = {
|
||||
|
||||
CM8JL65::CM8JL65(const char *port, uint8_t rotation) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
|
||||
_px4_rangefinder(0 /* TODO: device ids */, ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(0 /* TODO: device ids */, rotation)
|
||||
{
|
||||
// Store the port name.
|
||||
strncpy(_port, port, sizeof(_port) - 1);
|
||||
|
||||
@@ -39,7 +39,7 @@
|
||||
|
||||
LeddarOne::LeddarOne(const char *serial_port, uint8_t device_orientation):
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(serial_port)),
|
||||
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, device_orientation)
|
||||
_px4_rangefinder(0 /* device id not yet used */, device_orientation)
|
||||
{
|
||||
_serial_port = strdup(serial_port);
|
||||
|
||||
|
||||
@@ -45,7 +45,7 @@ LidarLiteI2C::LidarLiteI2C(I2CSPIBusOption bus_option, const int bus, const uint
|
||||
const int address) :
|
||||
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(get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(get_device_id(), rotation)
|
||||
{
|
||||
_px4_rangefinder.set_min_distance(LL40LS_MIN_DISTANCE);
|
||||
_px4_rangefinder.set_max_distance(LL40LS_MAX_DISTANCE);
|
||||
|
||||
@@ -50,7 +50,7 @@
|
||||
|
||||
LidarLitePWM::LidarLitePWM(const uint8_t rotation) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
|
||||
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(0 /* device id not yet used */, rotation)
|
||||
{
|
||||
_px4_rangefinder.set_min_distance(LL40LS_MIN_DISTANCE);
|
||||
_px4_rangefinder.set_max_distance(LL40LS_MAX_DISTANCE);
|
||||
|
||||
@@ -275,8 +275,7 @@ MappyDot::collect()
|
||||
report.variance = 0;
|
||||
|
||||
int instance_id;
|
||||
orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id, ORB_PRIO_DEFAULT);
|
||||
|
||||
orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id);
|
||||
}
|
||||
|
||||
perf_end(_sample_perf);
|
||||
|
||||
@@ -233,7 +233,7 @@ MB12XX::collect()
|
||||
report.variance = 0.0f;
|
||||
|
||||
int instance_id;
|
||||
orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id, ORB_PRIO_DEFAULT);
|
||||
orb_publish_auto(ORB_ID(distance_sensor), &_distance_sensor_topic, &report, &instance_id);
|
||||
|
||||
// Begin the next measurement.
|
||||
if (measure() != PX4_OK) {
|
||||
|
||||
@@ -41,7 +41,7 @@
|
||||
|
||||
SF0X::SF0X(const char *port, uint8_t rotation) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
|
||||
_px4_rangefinder(0 /* device id not yet used */, ORB_PRIO_DEFAULT, rotation),
|
||||
_px4_rangefinder(0 /* device id not yet used */, rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err"))
|
||||
{
|
||||
|
||||
@@ -117,7 +117,7 @@ private:
|
||||
SF1XX::SF1XX(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
|
||||
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),
|
||||
_px4_rangefinder(DRV_DIST_DEVTYPE_SF1XX, ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(DRV_DIST_DEVTYPE_SF1XX, rotation)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -36,7 +36,7 @@
|
||||
SRF02::SRF02(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
|
||||
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(get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(get_device_id(), rotation)
|
||||
{
|
||||
_px4_rangefinder.set_max_distance(SRF02_MAX_DISTANCE);
|
||||
_px4_rangefinder.set_min_distance(SRF02_MIN_DISTANCE);
|
||||
|
||||
@@ -76,7 +76,7 @@ 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(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(get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(get_device_id(), rotation)
|
||||
{
|
||||
// up the retries since the device misses the first measure attempts
|
||||
I2C::_retries = 3;
|
||||
|
||||
@@ -37,7 +37,7 @@
|
||||
|
||||
TFMINI::TFMINI(const char *port, uint8_t rotation) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
|
||||
_px4_rangefinder(0 /* TODO: device id */, ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(0 /* TODO: device id */, rotation)
|
||||
{
|
||||
// store port name
|
||||
strncpy(_port, port, sizeof(_port) - 1);
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
|
||||
AerotennaULanding::AerotennaULanding(const char *port, uint8_t rotation) :
|
||||
ScheduledWorkItem(MODULE_NAME, px4::serial_port_to_wq(port)),
|
||||
_px4_rangefinder(0 /* TODO: device ids */, ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_rangefinder(0 /* TODO: device ids */, rotation)
|
||||
{
|
||||
/* store port name */
|
||||
strncpy(_port, port, sizeof(_port) - 1);
|
||||
|
||||
@@ -62,7 +62,7 @@
|
||||
VL53L0X::VL53L0X(I2CSPIBusOption bus_option, const int bus, const uint8_t rotation, int bus_frequency, int address) :
|
||||
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)
|
||||
_px4_rangefinder(0 /* device id not yet used */, rotation)
|
||||
{
|
||||
// VL53L0X typical range 0-2 meters with 25 degree field of view
|
||||
_px4_rangefinder.set_min_distance(0.f);
|
||||
|
||||
@@ -41,10 +41,10 @@ ADIS16448::ADIS16448(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
|
||||
spi_mode_e spi_mode) :
|
||||
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(get_device_id(), rotation),
|
||||
_px4_baro(get_device_id()),
|
||||
_px4_gyro(get_device_id(), rotation),
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_accel.set_scale(ADIS16448_ACCEL_SENSITIVITY);
|
||||
_px4_gyro.set_scale(ADIS16448_GYRO_INITIAL_SENSITIVITY);
|
||||
|
||||
@@ -57,8 +57,8 @@ ADIS16477::ADIS16477(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
|
||||
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
|
||||
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),
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
|
||||
_drdy_gpio(drdy_gpio)
|
||||
|
||||
@@ -74,8 +74,8 @@ ADIS16497::ADIS16497(I2CSPIBusOption bus_option, int bus, int32_t device, enum R
|
||||
spi_mode_e spi_mode, spi_drdy_gpio_t drdy_gpio) :
|
||||
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),
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
|
||||
_drdy_gpio(drdy_gpio)
|
||||
|
||||
@@ -179,7 +179,7 @@ BMA180::BMA180(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
|
||||
spi_mode_e spi_mode) :
|
||||
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),
|
||||
_px4_accel(get_device_id(), ORB_PRIO_MAX, rotation),
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read"))
|
||||
{
|
||||
}
|
||||
|
||||
@@ -53,15 +53,15 @@ BMI160::BMI160(I2CSPIBusOption bus_option, int bus, int32_t device, enum Rotatio
|
||||
spi_mode_e spi_mode) :
|
||||
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(), ORB_PRIO_DEFAULT, rotation),
|
||||
_px4_gyro(get_device_id(), ORB_PRIO_DEFAULT, rotation),
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation),
|
||||
_accel_reads(perf_alloc(PC_COUNT, MODULE_NAME": accel read")),
|
||||
_gyro_reads(perf_alloc(PC_COUNT, MODULE_NAME":gyro read")),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME":read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME":bad transfers")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME":bad registers")),
|
||||
_good_transfers(perf_alloc(PC_COUNT, MODULE_NAME":good transfers")),
|
||||
_reset_retries(perf_alloc(PC_COUNT, MODULE_NAME":reset retries")),
|
||||
_gyro_reads(perf_alloc(PC_COUNT, MODULE_NAME": gyro read")),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad registers")),
|
||||
_good_transfers(perf_alloc(PC_COUNT, MODULE_NAME": good transfers")),
|
||||
_reset_retries(perf_alloc(PC_COUNT, MODULE_NAME": reset retries")),
|
||||
_duplicates(perf_alloc(PC_COUNT, MODULE_NAME": duplicates"))
|
||||
{
|
||||
}
|
||||
|
||||
@@ -43,7 +43,7 @@ namespace Bosch::BMI055::Accelerometer
|
||||
BMI055_Accelerometer::BMI055_Accelerometer(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) :
|
||||
BMI055(DRV_ACC_DEVTYPE_BMI055, "BMI055_Accelerometer", bus_option, bus, device, spi_mode, bus_frequency, drdy_gpio),
|
||||
_px4_accel(get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_accel(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_interval_perf = perf_alloc(PC_INTERVAL, MODULE_NAME"_accel: DRDY interval");
|
||||
|
||||
@@ -43,7 +43,7 @@ namespace Bosch::BMI055::Gyroscope
|
||||
BMI055_Gyroscope::BMI055_Gyroscope(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) :
|
||||
BMI055(DRV_GYR_DEVTYPE_BMI055, "BMI055_Gyroscope", bus_option, bus, device, spi_mode, bus_frequency, drdy_gpio),
|
||||
_px4_gyro(get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_interval_perf = perf_alloc(PC_INTERVAL, MODULE_NAME"_gyro: DRDY interval");
|
||||
|
||||
@@ -43,7 +43,7 @@ namespace Bosch::BMI088::Accelerometer
|
||||
BMI088_Accelerometer::BMI088_Accelerometer(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) :
|
||||
BMI088(DRV_ACC_DEVTYPE_BMI088, "BMI088_Accelerometer", bus_option, bus, device, spi_mode, bus_frequency, drdy_gpio),
|
||||
_px4_accel(get_device_id(), ORB_PRIO_HIGH, rotation)
|
||||
_px4_accel(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_interval_perf = perf_alloc(PC_INTERVAL, MODULE_NAME"_accel: DRDY interval");
|
||||
|
||||
@@ -43,7 +43,7 @@ namespace Bosch::BMI088::Gyroscope
|
||||
BMI088_Gyroscope::BMI088_Gyroscope(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) :
|
||||
BMI088(DRV_GYR_DEVTYPE_BMI088, "BMI088_Gyroscope", bus_option, bus, device, spi_mode, bus_frequency, drdy_gpio),
|
||||
_px4_gyro(get_device_id(), ORB_PRIO_HIGH, rotation)
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_interval_perf = perf_alloc(PC_INTERVAL, MODULE_NAME"_gyro: DRDY interval");
|
||||
|
||||
@@ -69,7 +69,7 @@ FXAS21002C::FXAS21002C(device::Device *interface, I2CSPIBusOption bus_option, in
|
||||
int i2c_address) :
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus, i2c_address),
|
||||
_interface(interface),
|
||||
_px4_gyro(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT), rotation),
|
||||
_px4_gyro(_interface->get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_errors(perf_alloc(PC_COUNT, MODULE_NAME": err")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad register")),
|
||||
|
||||
@@ -57,9 +57,9 @@ FXOS8701CQ::FXOS8701CQ(device::Device *interface, I2CSPIBusOption bus_option, in
|
||||
int i2c_address) :
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus, i2c_address),
|
||||
_interface(interface),
|
||||
_px4_accel(interface->get_device_id(), ORB_PRIO_LOW, rotation),
|
||||
_px4_accel(interface->get_device_id(), rotation),
|
||||
#if !defined(BOARD_HAS_NOISY_FXOS8700_MAG)
|
||||
_px4_mag(interface->get_device_id(), ORB_PRIO_LOW, rotation),
|
||||
_px4_mag(interface->get_device_id(), rotation),
|
||||
_mag_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": mag read")),
|
||||
#endif
|
||||
_accel_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": acc read")),
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM20602::ICM20602(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Ro
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM20608G::ICM20608G(I2CSPIBusOption bus_option, int bus, uint32_t device, enum
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM20649::ICM20649(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Ro
|
||||
SPI(DRV_IMU_DEVTYPE_ICM20649, 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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM20689::ICM20689(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Ro
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -47,8 +47,8 @@ ICM20948::ICM20948(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Ro
|
||||
SPI(DRV_IMU_DEVTYPE_ICM20948, 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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -48,7 +48,7 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
ICM20948_AK09916::ICM20948_AK09916(ICM20948 &icm20948, enum Rotation rotation) :
|
||||
ScheduledWorkItem("icm20948_ak09916", px4::device_bus_to_wq(icm20948.get_device_id())),
|
||||
_icm20948(icm20948),
|
||||
_px4_mag(icm20948.get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_mag(icm20948.get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_AK09916);
|
||||
_px4_mag.set_external(icm20948.external());
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM40609D::ICM40609D(I2CSPIBusOption bus_option, int bus, uint32_t device, enum
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ ICM42688P::ICM42688P(I2CSPIBusOption bus_option, int bus, uint32_t device, enum
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ MPU6000::MPU6000(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -45,8 +45,8 @@ MPU6500::MPU6500(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -47,8 +47,8 @@ MPU9250::MPU9250(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
if (drdy_gpio != 0) {
|
||||
_drdy_missed_perf = perf_alloc(PC_COUNT, MODULE_NAME": DRDY missed");
|
||||
|
||||
@@ -48,7 +48,7 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
MPU9250_AK8963::MPU9250_AK8963(MPU9250 &mpu9250, enum Rotation rotation) :
|
||||
ScheduledWorkItem("mpu9250_ak8963", px4::device_bus_to_wq(mpu9250.get_device_id())),
|
||||
_mpu9250(mpu9250),
|
||||
_px4_mag(mpu9250.get_device_id(), ORB_PRIO_DEFAULT, rotation)
|
||||
_px4_mag(mpu9250.get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_AK8963);
|
||||
_px4_mag.set_external(mpu9250.external());
|
||||
|
||||
@@ -39,7 +39,7 @@ L3GD20::L3GD20(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rotati
|
||||
spi_mode_e spi_mode) :
|
||||
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),
|
||||
_px4_gyro(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_errors(perf_alloc(PC_COUNT, MODULE_NAME": err")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, MODULE_NAME": bad_reg")),
|
||||
|
||||
@@ -57,8 +57,8 @@ LSM303D::LSM303D(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
|
||||
spi_mode_e spi_mode) :
|
||||
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),
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_mag(get_device_id(), rotation),
|
||||
_accel_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d: acc_read")),
|
||||
_mag_sample_perf(perf_alloc(PC_ELAPSED, "lsm303d: mag_read")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, "lsm303d: bad_reg")),
|
||||
|
||||
@@ -44,8 +44,8 @@ MPU6000::MPU6000(device::Device *interface, enum Rotation rotation, int device_t
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus, 0, device_type),
|
||||
_interface(interface),
|
||||
_device_type(device_type),
|
||||
_px4_accel(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
|
||||
_px4_gyro(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
|
||||
_px4_accel(_interface->get_device_id(), rotation),
|
||||
_px4_gyro(_interface->get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, "mpu6k_read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, "mpu6k_bad_trans")),
|
||||
_bad_registers(perf_alloc(PC_COUNT, "mpu6k_bad_reg")),
|
||||
|
||||
@@ -53,8 +53,7 @@
|
||||
// Otherwise, it will passthrough the parent MPU9250
|
||||
MPU9250_mag::MPU9250_mag(MPU9250 *parent, device::Device *interface, enum Rotation rotation) :
|
||||
_interface(interface),
|
||||
_px4_mag(parent->_interface->get_device_id(), (parent->_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH),
|
||||
rotation),
|
||||
_px4_mag(parent->_interface->get_device_id(), rotation),
|
||||
_parent(parent),
|
||||
_mag_overruns(perf_alloc(PC_COUNT, MODULE_NAME": mag overruns")),
|
||||
_mag_overflows(perf_alloc(PC_COUNT, MODULE_NAME": mag overflows")),
|
||||
|
||||
@@ -74,8 +74,8 @@ MPU9250::MPU9250(device::Device *interface, device::Device *mag_interface, enum
|
||||
I2CSPIBusOption bus_option, int bus) :
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus),
|
||||
_interface(interface),
|
||||
_px4_accel(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
|
||||
_px4_gyro(_interface->get_device_id(), (_interface->external() ? ORB_PRIO_MAX : ORB_PRIO_HIGH), rotation),
|
||||
_px4_accel(_interface->get_device_id(), rotation),
|
||||
_px4_gyro(_interface->get_device_id(), rotation),
|
||||
_mag(this, mag_interface, rotation),
|
||||
_dlpf_freq(MPU9250_DEFAULT_ONCHIP_FILTER_FREQ),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
|
||||
@@ -44,8 +44,8 @@ ISM330DLC::ISM330DLC(I2CSPIBusOption bus_option, int bus, uint32_t device, enum
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -42,8 +42,8 @@ LSM9DS1::LSM9DS1(I2CSPIBusOption bus_option, int bus, uint32_t device, enum Rota
|
||||
spi_mode_e spi_mode) :
|
||||
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)
|
||||
_px4_accel(get_device_id(), rotation),
|
||||
_px4_gyro(get_device_id(), rotation)
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
@@ -43,7 +43,7 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
AK09916::AK09916(I2CSPIBusOption bus_option, int bus, int bus_frequency, enum Rotation rotation) :
|
||||
I2C(DRV_MAG_DEVTYPE_AK09916, 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)
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_external(external());
|
||||
}
|
||||
|
||||
@@ -43,7 +43,7 @@ static constexpr int16_t combine(uint8_t msb, uint8_t lsb)
|
||||
AK8963::AK8963(I2CSPIBusOption bus_option, int bus, int bus_frequency, enum Rotation rotation) :
|
||||
I2C(DRV_MAG_DEVTYPE_AK8963, 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)
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_external(external());
|
||||
}
|
||||
|
||||
@@ -43,7 +43,7 @@
|
||||
BMM150::BMM150(I2CSPIBusOption bus_option, const int bus, int bus_frequency, enum Rotation rotation) :
|
||||
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),
|
||||
_px4_mag(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_bad_transfers(perf_alloc(PC_COUNT, MODULE_NAME": bad transfers")),
|
||||
_good_transfers(perf_alloc(PC_COUNT, MODULE_NAME": good transfers")),
|
||||
|
||||
@@ -39,7 +39,6 @@
|
||||
#include <systemlib/conversions.h>
|
||||
#include <drivers/drv_hrt.h>
|
||||
#include <drivers/device/i2c.h>
|
||||
#include <drivers/drv_mag.h>
|
||||
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
|
||||
|
||||
#define BMM150_SLAVE_ADDRESS 0x10
|
||||
|
||||
@@ -35,7 +35,7 @@
|
||||
|
||||
HMC5883::HMC5883(device::Device *interface, enum Rotation rotation, I2CSPIBusOption bus_option, int bus) :
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus),
|
||||
_px4_mag(interface->get_device_id(), interface->external() ? ORB_PRIO_VERY_HIGH : ORB_PRIO_DEFAULT, rotation),
|
||||
_px4_mag(interface->get_device_id(), rotation),
|
||||
_interface(interface),
|
||||
_range_ga(1.9f),
|
||||
_collect_phase(false),
|
||||
|
||||
@@ -43,7 +43,7 @@ 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(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)
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_external(external());
|
||||
}
|
||||
|
||||
@@ -270,7 +270,7 @@ private:
|
||||
IST8310::IST8310(I2CSPIBusOption bus_option, int bus_number, int address, enum Rotation rotation, int 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),
|
||||
_px4_mag(get_device_id(), rotation),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": com_err")),
|
||||
_range_errors(perf_alloc(PC_COUNT, MODULE_NAME": rng_err")),
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Reference in New Issue
Block a user