mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-04-14 10:07:39 +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:
parent
971b1e4b4d
commit
27f23ac290
@ -122,13 +122,8 @@ then
|
||||
param set BAT_N_CELLS 3
|
||||
|
||||
param set CAL_ACC0_ID 1311244
|
||||
param set CAL_ACC_PRIME 1311244
|
||||
|
||||
param set CAL_GYRO0_ID 1311244
|
||||
param set CAL_GYRO_PRIME 1311244
|
||||
|
||||
param set CAL_MAG0_ID 197388
|
||||
param set CAL_MAG_PRIME 197388
|
||||
|
||||
param set CBRK_AIRSPD_CHK 0
|
||||
param set CBRK_SUPPLY_CHK 894281
|
||||
|
||||
@ -186,17 +186,11 @@ then
|
||||
param set RTL_RETURN_ALT 25
|
||||
|
||||
# calibration
|
||||
param set CAL_ACC0_EN 1
|
||||
param set CAL_ACC1_EN 0
|
||||
#mpu6500
|
||||
param set CAL_ACC_PRIME 1442826
|
||||
param set CAL_ACC0_PRIO 255
|
||||
param set CAL_ACC1_PRIO 0
|
||||
|
||||
param set CAL_GYRO0_EN 1
|
||||
param set CAL_GYRO1_EN 0
|
||||
#mpu6500
|
||||
param set CAL_GYRO_PRIME 2360330
|
||||
|
||||
param set CAL_MAG_PRIME 265738
|
||||
param set CAL_GYRO0_PRIO 255
|
||||
param set CAL_GYRO1_PRIO 0
|
||||
fi
|
||||
|
||||
# Logger mode. Default(1) + estimator replay(2) + thermal calibration(4)
|
||||
|
||||
@ -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")),
|
||||
|
||||
@ -44,7 +44,7 @@
|
||||
|
||||
LIS2MDL::LIS2MDL(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),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors")),
|
||||
_conf_errors(perf_alloc(PC_COUNT, MODULE_NAME": conf_errors")),
|
||||
|
||||
@ -44,7 +44,7 @@
|
||||
|
||||
LIS3MDL::LIS3MDL(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),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors")),
|
||||
_conf_errors(perf_alloc(PC_COUNT, MODULE_NAME": conf_errors")),
|
||||
|
||||
@ -65,7 +65,7 @@ LSM303AGR::LSM303AGR(I2CSPIBusOption bus_option, int bus, int device, enum Rotat
|
||||
spi_mode_e spi_mode) :
|
||||
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),
|
||||
_px4_mag(get_device_id(), 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"))
|
||||
|
||||
@ -44,7 +44,7 @@ LSM9DS1_MAG::LSM9DS1_MAG(I2CSPIBusOption bus_option, int bus, uint32_t device, e
|
||||
int bus_frequency, spi_mode_e spi_mode) :
|
||||
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)
|
||||
_px4_mag(get_device_id(), rotation)
|
||||
{
|
||||
_px4_mag.set_external(external());
|
||||
}
|
||||
|
||||
@ -36,7 +36,7 @@
|
||||
QMC5883::QMC5883(device::Device *interface, enum Rotation rotation, I2CSPIBusOption bus_option, int bus,
|
||||
int i2c_address) :
|
||||
I2CSPIDriver(MODULE_NAME, px4::device_bus_to_wq(interface->get_device_id()), bus_option, bus, i2c_address),
|
||||
_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),
|
||||
_collect_phase(false),
|
||||
_sample_perf(perf_alloc(PC_ELAPSED, MODULE_NAME": read")),
|
||||
|
||||
@ -43,7 +43,7 @@
|
||||
|
||||
RM3100::RM3100(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),
|
||||
_comms_errors(perf_alloc(PC_COUNT, MODULE_NAME": comms_errors")),
|
||||
_conf_errors(perf_alloc(PC_COUNT, MODULE_NAME": conf_errors")),
|
||||
|
||||
@ -481,8 +481,7 @@ MK::task_main()
|
||||
actuator_outputs_s outputs;
|
||||
memset(&outputs, 0, sizeof(outputs));
|
||||
int dummy;
|
||||
_t_outputs = orb_advertise_multi(ORB_ID(actuator_outputs),
|
||||
&outputs, &dummy, ORB_PRIO_HIGH);
|
||||
_t_outputs = orb_advertise_multi(ORB_ID(actuator_outputs), &outputs, &dummy);
|
||||
|
||||
/*
|
||||
* advertise the blctrl status.
|
||||
|
||||
@ -2058,7 +2058,7 @@ PX4IO::io_reg_modify(uint8_t page, uint8_t offset, uint16_t clearbits, uint16_t
|
||||
int
|
||||
PX4IO::print_debug()
|
||||
{
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4_FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4_FMU_V3) || defined(CONFIG_ARCH_BOARD_HEX_CUBE_ORANGE)
|
||||
#if defined(CONFIG_ARCH_BOARD_PX4_FMU_V2) || defined(CONFIG_ARCH_BOARD_PX4_FMU_V3)
|
||||
int io_fd = -1;
|
||||
|
||||
if (io_fd <= 0) {
|
||||
|
||||
@ -117,7 +117,7 @@ int UavcanBarometerBridge::init_driver(uavcan_bridge::Channel *channel)
|
||||
device_id.devid_s.devtype = DRV_BARO_DEVTYPE_UAVCAN;
|
||||
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
|
||||
|
||||
channel->h_driver = new PX4Barometer(device_id.devid, ORB_PRIO_HIGH);
|
||||
channel->h_driver = new PX4Barometer(device_id.devid);
|
||||
|
||||
if (channel->h_driver == nullptr) {
|
||||
return PX4_ERROR;
|
||||
|
||||
@ -114,7 +114,7 @@ private:
|
||||
float _last_gnss_auxiliary_hdop{0.0f};
|
||||
float _last_gnss_auxiliary_vdop{0.0f};
|
||||
|
||||
uORB::PublicationMulti<vehicle_gps_position_s> _gps_pub{ORB_ID(vehicle_gps_position), ORB_PRIO_DEFAULT};
|
||||
uORB::PublicationMulti<vehicle_gps_position_s> _gps_pub{ORB_ID(vehicle_gps_position)};
|
||||
uORB::Subscription _orb_sub_gnss{ORB_ID(vehicle_gps_position)};
|
||||
|
||||
int _receiver_node_id{-1};
|
||||
|
||||
@ -148,7 +148,7 @@ int UavcanMagnetometerBridge::init_driver(uavcan_bridge::Channel *channel)
|
||||
device_id.devid_s.devtype = DRV_MAG_DEVTYPE_UAVCAN;
|
||||
device_id.devid_s.address = static_cast<uint8_t>(channel->node_id);
|
||||
|
||||
channel->h_driver = new PX4Magnetometer(device_id.devid, ORB_PRIO_HIGH, ROTATION_NONE);
|
||||
channel->h_driver = new PX4Magnetometer(device_id.devid, ROTATION_NONE);
|
||||
|
||||
if (channel->h_driver == nullptr) {
|
||||
return PX4_ERROR;
|
||||
|
||||
@ -130,7 +130,7 @@ UavcanCDevSensorBridgeBase::publish(const int node_id, const void *report)
|
||||
channel->class_instance = class_instance;
|
||||
DEVICE_LOG("channel %d class instance %d ok", channel->node_id, channel->class_instance);
|
||||
|
||||
channel->orb_advert = orb_advertise_multi(_orb_topic, report, &channel->orb_instance, ORB_PRIO_VERY_HIGH);
|
||||
channel->orb_advert = orb_advertise_multi(_orb_topic, report, &channel->orb_instance);
|
||||
|
||||
if (channel->orb_advert == nullptr) {
|
||||
DEVICE_LOG("uORB advertise failed. Out of instances?");
|
||||
|
||||
@ -41,7 +41,7 @@ using namespace time_literals;
|
||||
FakeMagnetometer::FakeMagnetometer() :
|
||||
ModuleParams(nullptr),
|
||||
ScheduledWorkItem(MODULE_NAME, px4::wq_configurations::hp_default),
|
||||
_px4_mag(0, ORB_PRIO_MIN, ROTATION_NONE)
|
||||
_px4_mag(0, ROTATION_NONE)
|
||||
{
|
||||
_px4_mag.set_device_type(DRV_MAG_DEVTYPE_MAGSIM);
|
||||
_px4_mag.set_external(false);
|
||||
|
||||
@ -46,6 +46,7 @@
|
||||
#include <px4_platform_common/module_params.h>
|
||||
#include <px4_platform_common/posix.h>
|
||||
#include <px4_platform_common/px4_work_queue/ScheduledWorkItem.hpp>
|
||||
#include <drivers/drv_sensor.h>
|
||||
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
|
||||
#include <uORB/Subscription.hpp>
|
||||
#include <uORB/topics/vehicle_attitude.h>
|
||||
|
||||
@ -186,7 +186,7 @@ Battery::updateBatteryStatus(hrt_abstime timestamp, float voltage_v, float curre
|
||||
void
|
||||
Battery::publish()
|
||||
{
|
||||
orb_publish_auto(ORB_ID(battery_status), &_orb_advert, &_battery_status, &_orb_instance, ORB_PRIO_DEFAULT);
|
||||
orb_publish_auto(ORB_ID(battery_status), &_orb_advert, &_battery_status, &_orb_instance);
|
||||
}
|
||||
|
||||
void
|
||||
|
||||
@ -63,10 +63,10 @@ static constexpr uint8_t clipping(const int16_t samples[16], int16_t clip_limit,
|
||||
return clip_count;
|
||||
}
|
||||
|
||||
PX4Accelerometer::PX4Accelerometer(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
|
||||
PX4Accelerometer::PX4Accelerometer(uint32_t device_id, enum Rotation rotation) :
|
||||
ModuleParams(nullptr),
|
||||
_sensor_pub{ORB_ID(sensor_accel), priority},
|
||||
_sensor_fifo_pub{ORB_ID(sensor_accel_fifo), priority},
|
||||
_sensor_pub{ORB_ID(sensor_accel)},
|
||||
_sensor_fifo_pub{ORB_ID(sensor_accel_fifo)},
|
||||
_device_id{device_id},
|
||||
_rotation{rotation}
|
||||
{
|
||||
|
||||
@ -44,7 +44,7 @@
|
||||
class PX4Accelerometer : public ModuleParams
|
||||
{
|
||||
public:
|
||||
PX4Accelerometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
|
||||
PX4Accelerometer(uint32_t device_id, enum Rotation rotation = ROTATION_NONE);
|
||||
~PX4Accelerometer() override;
|
||||
|
||||
uint32_t get_device_id() const { return _device_id; }
|
||||
|
||||
@ -36,9 +36,9 @@
|
||||
|
||||
#include <lib/drivers/device/Device.hpp>
|
||||
|
||||
PX4Barometer::PX4Barometer(uint32_t device_id, ORB_PRIO priority) :
|
||||
PX4Barometer::PX4Barometer(uint32_t device_id) :
|
||||
CDev(nullptr),
|
||||
_sensor_baro_pub{ORB_ID(sensor_baro), priority}
|
||||
_sensor_baro_pub{ORB_ID(sensor_baro)}
|
||||
{
|
||||
_class_device_instance = register_class_devname(BARO_BASE_DEVICE_PATH);
|
||||
_sensor_baro_pub.advertise();
|
||||
|
||||
@ -45,7 +45,7 @@ class PX4Barometer : public cdev::CDev
|
||||
{
|
||||
|
||||
public:
|
||||
PX4Barometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT);
|
||||
PX4Barometer(uint32_t device_id);
|
||||
~PX4Barometer() override;
|
||||
|
||||
const sensor_baro_s &get() { return _sensor_baro_pub.get(); }
|
||||
|
||||
@ -50,10 +50,10 @@ static constexpr int32_t sum(const int16_t samples[16], uint8_t len)
|
||||
return sum;
|
||||
}
|
||||
|
||||
PX4Gyroscope::PX4Gyroscope(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
|
||||
PX4Gyroscope::PX4Gyroscope(uint32_t device_id, enum Rotation rotation) :
|
||||
ModuleParams(nullptr),
|
||||
_sensor_pub{ORB_ID(sensor_gyro), priority},
|
||||
_sensor_fifo_pub{ORB_ID(sensor_gyro_fifo), priority},
|
||||
_sensor_pub{ORB_ID(sensor_gyro)},
|
||||
_sensor_fifo_pub{ORB_ID(sensor_gyro_fifo)},
|
||||
_device_id{device_id},
|
||||
_rotation{rotation}
|
||||
{
|
||||
|
||||
@ -43,7 +43,7 @@
|
||||
class PX4Gyroscope : public ModuleParams
|
||||
{
|
||||
public:
|
||||
PX4Gyroscope(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
|
||||
PX4Gyroscope(uint32_t device_id, enum Rotation rotation = ROTATION_NONE);
|
||||
~PX4Gyroscope() override;
|
||||
|
||||
uint32_t get_device_id() const { return _device_id; }
|
||||
|
||||
@ -36,9 +36,9 @@
|
||||
|
||||
#include <lib/drivers/device/Device.hpp>
|
||||
|
||||
PX4Magnetometer::PX4Magnetometer(uint32_t device_id, ORB_PRIO priority, enum Rotation rotation) :
|
||||
PX4Magnetometer::PX4Magnetometer(uint32_t device_id, enum Rotation rotation) :
|
||||
CDev(nullptr),
|
||||
_sensor_pub{ORB_ID(sensor_mag), priority},
|
||||
_sensor_pub{ORB_ID(sensor_mag)},
|
||||
_device_id{device_id},
|
||||
_rotation{rotation}
|
||||
{
|
||||
|
||||
@ -43,7 +43,7 @@
|
||||
class PX4Magnetometer : public cdev::CDev
|
||||
{
|
||||
public:
|
||||
PX4Magnetometer(uint32_t device_id, ORB_PRIO priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE);
|
||||
PX4Magnetometer(uint32_t device_id, enum Rotation rotation = ROTATION_NONE);
|
||||
~PX4Magnetometer() override;
|
||||
|
||||
bool external() { return _external; }
|
||||
|
||||
@ -35,8 +35,8 @@
|
||||
|
||||
#include <lib/drivers/device/Device.hpp>
|
||||
|
||||
PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const ORB_PRIO priority, const uint8_t device_orientation) :
|
||||
_distance_sensor_pub{ORB_ID(distance_sensor), priority}
|
||||
PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t device_orientation) :
|
||||
_distance_sensor_pub{ORB_ID(distance_sensor)}
|
||||
{
|
||||
_distance_sensor_pub.advertise();
|
||||
|
||||
|
||||
@ -44,7 +44,6 @@ class PX4Rangefinder
|
||||
|
||||
public:
|
||||
PX4Rangefinder(const uint32_t device_id,
|
||||
const ORB_PRIO priority = ORB_PRIO_DEFAULT,
|
||||
const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING);
|
||||
~PX4Rangefinder();
|
||||
|
||||
|
||||
@ -238,8 +238,8 @@ private:
|
||||
uORB::Subscription _armed_sub{ORB_ID(actuator_armed)};
|
||||
uORB::SubscriptionCallbackWorkItem _control_subs[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS];
|
||||
|
||||
uORB::PublicationMulti<actuator_outputs_s> _outputs_pub{ORB_ID(actuator_outputs), ORB_PRIO_DEFAULT};
|
||||
uORB::PublicationMulti<multirotor_motor_limits_s> _to_mixer_status{ORB_ID(multirotor_motor_limits), ORB_PRIO_DEFAULT}; ///< mixer status flags
|
||||
uORB::PublicationMulti<actuator_outputs_s> _outputs_pub{ORB_ID(actuator_outputs)};
|
||||
uORB::PublicationMulti<multirotor_motor_limits_s> _to_mixer_status{ORB_ID(multirotor_motor_limits)}; ///< mixer status flags
|
||||
|
||||
actuator_controls_s _controls[actuator_controls_s::NUM_ACTUATOR_CONTROL_GROUPS] {};
|
||||
actuator_armed_s _armed{};
|
||||
|
||||
@ -60,6 +60,44 @@ bool param_modify_on_import(bson_node_t node)
|
||||
}
|
||||
}
|
||||
|
||||
// 2020-06-29 (v1.11 beta): translate CAL_ACCx_EN/CAL_GYROx_EN/CAL_MAGx_EN -> CAL_ACCx_PRIO/CAL_GYROx_PRIO/CAL_MAGx_PRIO
|
||||
if (node->type == BSON_INT32) {
|
||||
|
||||
const char *cal_sensor_en_params[] = {
|
||||
"CAL_ACC0_EN",
|
||||
"CAL_ACC1_EN",
|
||||
"CAL_ACC2_EN",
|
||||
"CAL_GYRO0_EN",
|
||||
"CAL_GYRO1_EN",
|
||||
"CAL_GYRO2_EN",
|
||||
"CAL_MAG0_EN",
|
||||
"CAL_MAG1_EN",
|
||||
"CAL_MAG2_EN",
|
||||
"CAL_MAG3_EN",
|
||||
};
|
||||
|
||||
for (int i = 0; i < sizeof(cal_sensor_en_params) / sizeof(cal_sensor_en_params[0]); ++i) {
|
||||
if (strcmp(cal_sensor_en_params[i], node->name) == 0) {
|
||||
|
||||
char new_parameter_name[17] {};
|
||||
strcpy(new_parameter_name, cal_sensor_en_params[i]);
|
||||
|
||||
char *str_replace = strstr(new_parameter_name, "_EN");
|
||||
|
||||
if (str_replace != nullptr) {
|
||||
strcpy(str_replace, "_PRIO");
|
||||
PX4_INFO("%s -> %s", cal_sensor_en_params[i], new_parameter_name);
|
||||
strcpy(node->name, new_parameter_name);
|
||||
}
|
||||
|
||||
// if sensor wasn't disabled, reset to -1 so that it can be set to an appropriate default
|
||||
if (node->i != 0) {
|
||||
node->i = -1; // special value to process later
|
||||
}
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
||||
// translate (SPI) calibration ID parameters. This can be removed after the next release (current release=1.10)
|
||||
|
||||
@ -87,10 +125,7 @@ bool param_modify_on_import(bson_node_t node)
|
||||
"CAL_MAG2_ID",
|
||||
"TC_A2_ID",
|
||||
"TC_B2_ID",
|
||||
"TC_G2_ID",
|
||||
"CAL_ACC_PRIME",
|
||||
"CAL_GYRO_PRIME",
|
||||
"CAL_MAG_PRIME",
|
||||
"TC_G2_ID"
|
||||
};
|
||||
bool found = false;
|
||||
|
||||
|
||||
@ -118,9 +118,15 @@ void Accelerometer::ParametersUpdate()
|
||||
_rotation.setIdentity();
|
||||
}
|
||||
|
||||
// CAL_ACCx_EN
|
||||
int32_t enabled = GetCalibrationParam(SensorString(), "EN", _calibration_index);
|
||||
_enabled = (enabled == 1);
|
||||
// CAL_ACCx_PRIO
|
||||
_priority = GetCalibrationParam(SensorString(), "PRIO", _calibration_index);
|
||||
|
||||
if (_priority < 0 || _priority > 100) {
|
||||
// reset to default
|
||||
PX4_ERR("%s %d invalid priority %d, resetting to %d", SensorString(), _calibration_index, _priority, DEFAULT_PRIORITY);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, DEFAULT_PRIORITY);
|
||||
_priority = DEFAULT_PRIORITY;
|
||||
}
|
||||
|
||||
// CAL_ACCx_OFF{X,Y,Z}
|
||||
_offset = GetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index);
|
||||
@ -140,7 +146,7 @@ void Accelerometer::Reset()
|
||||
_scale = Vector3f{1.f, 1.f, 1.f};
|
||||
_thermal_offset.zero();
|
||||
|
||||
_enabled = true;
|
||||
_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
|
||||
|
||||
_calibration_index = -1;
|
||||
}
|
||||
@ -150,10 +156,17 @@ bool Accelerometer::ParametersSave()
|
||||
if (_calibration_index >= 0) {
|
||||
// save calibration
|
||||
SetCalibrationParam(SensorString(), "ID", _calibration_index, _device_id);
|
||||
SetCalibrationParam(SensorString(), "EN", _calibration_index, _enabled ? 1 : 0);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, _priority);
|
||||
SetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index, _offset);
|
||||
SetCalibrationParamsVector3f(SensorString(), "SCALE", _calibration_index, _scale);
|
||||
|
||||
// if (_external) {
|
||||
// SetCalibrationParam(SensorString(), "ROT", _calibration_index, (int32_t)_rotation_enum);
|
||||
|
||||
// } else {
|
||||
// SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1);
|
||||
// }
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
@ -47,6 +47,9 @@ class Accelerometer
|
||||
public:
|
||||
static constexpr int MAX_SENSOR_COUNT = 3;
|
||||
|
||||
static constexpr uint8_t DEFAULT_PRIORITY = 50;
|
||||
static constexpr uint8_t DEFAULT_EXTERNAL_PRIORITY = 75;
|
||||
|
||||
static constexpr const char *SensorString() { return "ACC"; }
|
||||
|
||||
Accelerometer();
|
||||
@ -63,8 +66,9 @@ public:
|
||||
void set_scale(const matrix::Vector3f &scale) { _scale = scale; }
|
||||
|
||||
uint32_t device_id() const { return _device_id; }
|
||||
bool enabled() const { return _enabled; }
|
||||
bool enabled() const { return (_priority > 0); }
|
||||
bool external() const { return _external; }
|
||||
const int32_t &priority() const { return _priority; }
|
||||
const matrix::Dcmf &rotation() const { return _rotation; }
|
||||
|
||||
// apply offsets and scale
|
||||
@ -91,8 +95,8 @@ private:
|
||||
|
||||
int8_t _calibration_index{-1};
|
||||
uint32_t _device_id{0};
|
||||
int32_t _priority{DEFAULT_PRIORITY};
|
||||
|
||||
bool _enabled{true};
|
||||
bool _external{false};
|
||||
};
|
||||
} // namespace calibration
|
||||
|
||||
@ -118,9 +118,15 @@ void Gyroscope::ParametersUpdate()
|
||||
_rotation.setIdentity();
|
||||
}
|
||||
|
||||
// CAL_GYROx_EN
|
||||
int32_t enabled = GetCalibrationParam(SensorString(), "EN", _calibration_index);
|
||||
_enabled = (enabled == 1);
|
||||
// CAL_GYROx_PRIO
|
||||
_priority = GetCalibrationParam(SensorString(), "PRIO", _calibration_index);
|
||||
|
||||
if (_priority < 0 || _priority > 100) {
|
||||
// reset to default
|
||||
PX4_ERR("%s %d invalid priority %d, resetting to %d", SensorString(), _calibration_index, _priority, DEFAULT_PRIORITY);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, DEFAULT_PRIORITY);
|
||||
_priority = DEFAULT_PRIORITY;
|
||||
}
|
||||
|
||||
// CAL_GYROx_OFF{X,Y,Z}
|
||||
_offset = GetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index);
|
||||
@ -136,7 +142,7 @@ void Gyroscope::Reset()
|
||||
_offset.zero();
|
||||
_thermal_offset.zero();
|
||||
|
||||
_enabled = true;
|
||||
_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
|
||||
|
||||
_calibration_index = -1;
|
||||
}
|
||||
@ -146,9 +152,16 @@ bool Gyroscope::ParametersSave()
|
||||
if (_calibration_index >= 0) {
|
||||
// save calibration
|
||||
SetCalibrationParam(SensorString(), "ID", _calibration_index, _device_id);
|
||||
SetCalibrationParam(SensorString(), "EN", _calibration_index, _enabled ? 1 : 0);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, _priority);
|
||||
SetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index, _offset);
|
||||
|
||||
// if (_external) {
|
||||
// SetCalibrationParam(SensorString(), "ROT", _calibration_index, (int32_t)_rotation_enum);
|
||||
|
||||
// } else {
|
||||
// SetCalibrationParam(SensorString(), "ROT", _calibration_index, -1);
|
||||
// }
|
||||
|
||||
return true;
|
||||
}
|
||||
|
||||
|
||||
@ -47,6 +47,9 @@ class Gyroscope
|
||||
public:
|
||||
static constexpr int MAX_SENSOR_COUNT = 3;
|
||||
|
||||
static constexpr uint8_t DEFAULT_PRIORITY = 50;
|
||||
static constexpr uint8_t DEFAULT_EXTERNAL_PRIORITY = 75;
|
||||
|
||||
static constexpr const char *SensorString() { return "GYRO"; }
|
||||
|
||||
Gyroscope();
|
||||
@ -62,8 +65,9 @@ public:
|
||||
void set_offset(const matrix::Vector3f &offset) { _offset = offset; }
|
||||
|
||||
uint32_t device_id() const { return _device_id; }
|
||||
bool enabled() const { return _enabled; }
|
||||
bool enabled() const { return (_priority > 0); }
|
||||
bool external() const { return _external; }
|
||||
const int32_t &priority() const { return _priority; }
|
||||
const matrix::Dcmf &rotation() const { return _rotation; }
|
||||
|
||||
// apply offsets and scale
|
||||
@ -89,8 +93,8 @@ private:
|
||||
|
||||
int8_t _calibration_index{-1};
|
||||
uint32_t _device_id{0};
|
||||
int32_t _priority{DEFAULT_PRIORITY};
|
||||
|
||||
bool _enabled{true};
|
||||
bool _external{false};
|
||||
};
|
||||
} // namespace calibration
|
||||
|
||||
@ -64,6 +64,21 @@ void Magnetometer::set_device_id(uint32_t device_id)
|
||||
|
||||
void Magnetometer::set_external(bool external)
|
||||
{
|
||||
// update priority default appropriately if not set
|
||||
if (_calibration_index < 0) {
|
||||
if ((_priority < 0) || (_priority > 100)) {
|
||||
_priority = external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
|
||||
|
||||
} else if (!_external && external && (_priority == DEFAULT_PRIORITY)) {
|
||||
// internal -> external
|
||||
_priority = DEFAULT_EXTERNAL_PRIORITY;
|
||||
|
||||
} else if (_external && !external && (_priority == DEFAULT_EXTERNAL_PRIORITY)) {
|
||||
// external -> internal
|
||||
_priority = DEFAULT_PRIORITY;
|
||||
}
|
||||
}
|
||||
|
||||
_external = external;
|
||||
}
|
||||
|
||||
@ -113,9 +128,16 @@ void Magnetometer::ParametersUpdate()
|
||||
_rotation = get_rot_matrix((enum Rotation)rotation);
|
||||
}
|
||||
|
||||
// CAL_MAGx_EN
|
||||
int32_t enabled = GetCalibrationParam(SensorString(), "EN", _calibration_index);
|
||||
_enabled = (enabled == 1);
|
||||
// CAL_MAGx_PRIO
|
||||
_priority = GetCalibrationParam(SensorString(), "PRIO", _calibration_index);
|
||||
|
||||
if ((_priority < 0) || (_priority > 100)) {
|
||||
// reset to default
|
||||
int32_t new_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
|
||||
PX4_ERR("%s %d invalid priority %d, resetting to %d", SensorString(), _calibration_index, _priority, new_priority);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, new_priority);
|
||||
_priority = new_priority;
|
||||
}
|
||||
|
||||
// CAL_MAGx_OFF{X,Y,Z}
|
||||
_offset = GetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index);
|
||||
@ -151,7 +173,7 @@ void Magnetometer::Reset()
|
||||
_power_compensation.zero();
|
||||
_power = 0.f;
|
||||
|
||||
_enabled = true;
|
||||
_priority = _external ? DEFAULT_EXTERNAL_PRIORITY : DEFAULT_PRIORITY;
|
||||
|
||||
_calibration_index = -1;
|
||||
}
|
||||
@ -161,7 +183,7 @@ bool Magnetometer::ParametersSave()
|
||||
if (_calibration_index >= 0) {
|
||||
// save calibration
|
||||
SetCalibrationParam(SensorString(), "ID", _calibration_index, _device_id);
|
||||
SetCalibrationParam(SensorString(), "EN", _calibration_index, _enabled ? 1 : 0);
|
||||
SetCalibrationParam(SensorString(), "PRIO", _calibration_index, _priority);
|
||||
SetCalibrationParamsVector3f(SensorString(), "OFF", _calibration_index, _offset);
|
||||
|
||||
Vector3f scale{_scale.diag()};
|
||||
|
||||
@ -48,6 +48,9 @@ class Magnetometer
|
||||
public:
|
||||
static constexpr int MAX_SENSOR_COUNT = 4;
|
||||
|
||||
static constexpr uint8_t DEFAULT_PRIORITY = 50;
|
||||
static constexpr uint8_t DEFAULT_EXTERNAL_PRIORITY = 75;
|
||||
|
||||
static constexpr const char *SensorString() { return "MAG"; }
|
||||
|
||||
Magnetometer();
|
||||
@ -66,9 +69,10 @@ public:
|
||||
void set_rotation(Rotation rotation);
|
||||
|
||||
uint32_t device_id() const { return _device_id; }
|
||||
bool enabled() const { return _enabled; }
|
||||
bool enabled() const { return (_priority > 0); }
|
||||
bool external() const { return _external; }
|
||||
const matrix::Vector3f &offset() const { return _offset; }
|
||||
const int32_t &priority() const { return _priority; }
|
||||
const matrix::Dcmf &rotation() const { return _rotation; }
|
||||
const Rotation &rotation_enum() const { return _rotation_enum; }
|
||||
const matrix::Matrix3f &scale() const { return _scale; }
|
||||
@ -98,8 +102,8 @@ private:
|
||||
|
||||
int8_t _calibration_index{-1};
|
||||
uint32_t _device_id{0};
|
||||
int32_t _priority{-1};
|
||||
|
||||
bool _enabled{true};
|
||||
bool _external{false};
|
||||
};
|
||||
} // namespace calibration
|
||||
|
||||
@ -263,8 +263,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name);
|
||||
|
||||
calibration::Accelerometer calibrations[MAX_ACCEL_SENS] {};
|
||||
ORB_PRIO device_prio_max = ORB_PRIO_UNINITIALIZED;
|
||||
int32_t device_id_primary = 0;
|
||||
unsigned active_sensors = 0;
|
||||
|
||||
for (uint8_t cur_accel = 0; cur_accel < MAX_ACCEL_SENS; cur_accel++) {
|
||||
@ -274,14 +272,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
calibrations[cur_accel].set_device_id(accel_sub.get().device_id);
|
||||
active_sensors++;
|
||||
|
||||
// Get priority
|
||||
const ORB_PRIO prio = accel_sub.get_priority();
|
||||
|
||||
if (prio > device_prio_max) {
|
||||
device_prio_max = prio;
|
||||
device_id_primary = accel_sub.get().device_id;
|
||||
}
|
||||
|
||||
} else {
|
||||
calibrations[cur_accel].Reset();
|
||||
}
|
||||
@ -365,7 +355,6 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub)
|
||||
calibrations[i].ParametersSave();
|
||||
}
|
||||
|
||||
param_set_no_notification(param_find("CAL_ACC_PRIME"), &device_id_primary);
|
||||
param_notify_changes();
|
||||
|
||||
/* if there is a any preflight-check system response, let the barrage of messages through */
|
||||
@ -384,7 +373,7 @@ int do_accel_calibration_quick(orb_advert_t *mavlink_log_pub)
|
||||
#if !defined(CONSTRAINED_FLASH)
|
||||
PX4_INFO("Accelerometer quick calibration");
|
||||
|
||||
int32_t device_id_primary = 0;
|
||||
bool success = false;
|
||||
|
||||
// sensor thermal corrections (optional)
|
||||
uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)};
|
||||
@ -492,20 +481,16 @@ int do_accel_calibration_quick(orb_advert_t *mavlink_log_pub)
|
||||
|
||||
} else {
|
||||
calibration.set_offset(offset);
|
||||
|
||||
success = true;
|
||||
}
|
||||
|
||||
calibration.ParametersSave();
|
||||
|
||||
if (device_id_primary == 0) {
|
||||
device_id_primary = arp.device_id;
|
||||
}
|
||||
|
||||
calibration.PrintStatus();
|
||||
}
|
||||
}
|
||||
|
||||
if (device_id_primary != 0) {
|
||||
param_set_no_notification(param_find("CAL_ACC_PRIME"), &device_id_primary);
|
||||
if (success) {
|
||||
param_notify_changes();
|
||||
return PX4_OK;
|
||||
}
|
||||
|
||||
@ -212,9 +212,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
gyro_worker_data_t worker_data{};
|
||||
worker_data.mavlink_log_pub = mavlink_log_pub;
|
||||
|
||||
ORB_PRIO device_prio_max = ORB_PRIO_UNINITIALIZED;
|
||||
int32_t device_id_primary = 0;
|
||||
|
||||
// We should not try to subscribe if the topic doesn't actually exist and can be counted.
|
||||
const unsigned orb_gyro_count = orb_group_count(ORB_ID(sensor_gyro));
|
||||
|
||||
@ -232,14 +229,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
|
||||
if (gyro_sub.advertised() && (gyro_sub.get().device_id != 0) && (gyro_sub.get().timestamp > 0)) {
|
||||
worker_data.calibrations[cur_gyro].set_device_id(gyro_sub.get().device_id);
|
||||
|
||||
// Get priority
|
||||
const ORB_PRIO prio = gyro_sub.get_priority();
|
||||
|
||||
if (prio > device_prio_max) {
|
||||
device_prio_max = prio;
|
||||
device_id_primary = gyro_sub.get().device_id;
|
||||
}
|
||||
}
|
||||
|
||||
// reset calibration index to match uORB numbering
|
||||
@ -317,8 +306,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub)
|
||||
calibration.ParametersSave();
|
||||
}
|
||||
|
||||
param_set_no_notification(param_find("CAL_GYRO_PRIME"), &device_id_primary);
|
||||
|
||||
if (failed) {
|
||||
calibration_log_critical(mavlink_log_pub, "ERROR: failed to set offset params");
|
||||
res = PX4_ERROR;
|
||||
|
||||
@ -262,12 +262,12 @@ private:
|
||||
uORB::Publication<vehicle_trajectory_waypoint_s> _trajectory_waypoint_pub{ORB_ID(vehicle_trajectory_waypoint)};
|
||||
|
||||
// ORB publications (multi)
|
||||
uORB::PublicationMulti<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<distance_sensor_s> _flow_distance_sensor_pub{ORB_ID(distance_sensor), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<input_rc_s> _rc_pub{ORB_ID(input_rc), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<ping_s> _ping_pub{ORB_ID(ping), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<radio_status_s> _radio_status_pub{ORB_ID(radio_status), ORB_PRIO_LOW};
|
||||
uORB::PublicationMulti<distance_sensor_s> _distance_sensor_pub{ORB_ID(distance_sensor)};
|
||||
uORB::PublicationMulti<distance_sensor_s> _flow_distance_sensor_pub{ORB_ID(distance_sensor)};
|
||||
uORB::PublicationMulti<input_rc_s> _rc_pub{ORB_ID(input_rc)};
|
||||
uORB::PublicationMulti<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint)};
|
||||
uORB::PublicationMulti<ping_s> _ping_pub{ORB_ID(ping)};
|
||||
uORB::PublicationMulti<radio_status_s> _radio_status_pub{ORB_ID(radio_status)};
|
||||
|
||||
// ORB publications (queue length > 1)
|
||||
uORB::PublicationQueued<gps_inject_data_s> _gps_inject_data_pub{ORB_ID(gps_inject_data)};
|
||||
|
||||
@ -107,7 +107,7 @@ private:
|
||||
uORB::SubscriptionCallbackWorkItem _vehicle_angular_velocity_sub{this, ORB_ID(vehicle_angular_velocity)};
|
||||
|
||||
uORB::Publication<actuator_controls_s> _actuators_0_pub;
|
||||
uORB::PublicationMulti<rate_ctrl_status_s> _controller_status_pub{ORB_ID(rate_ctrl_status), ORB_PRIO_DEFAULT}; /**< controller status publication */
|
||||
uORB::PublicationMulti<rate_ctrl_status_s> _controller_status_pub{ORB_ID(rate_ctrl_status)}; /**< controller status publication */
|
||||
uORB::Publication<landing_gear_s> _landing_gear_pub{ORB_ID(landing_gear)};
|
||||
uORB::Publication<vehicle_rates_setpoint_s> _v_rates_sp_pub{ORB_ID(vehicle_rates_setpoint)}; /**< rate setpoint publication */
|
||||
|
||||
|
||||
@ -157,7 +157,7 @@ private:
|
||||
uORB::Publication<rc_channels_s> _rc_pub{ORB_ID(rc_channels)}; /**< raw r/c control topic */
|
||||
uORB::Publication<actuator_controls_s> _actuator_group_3_pub{ORB_ID(actuator_controls_3)}; /**< manual control as actuator topic */
|
||||
|
||||
uORB::PublicationMulti<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint), ORB_PRIO_HIGH}; /**< manual control signal topic */
|
||||
uORB::PublicationMulti<manual_control_setpoint_s> _manual_control_setpoint_pub{ORB_ID(manual_control_setpoint)}; /**< manual control signal topic */
|
||||
|
||||
rc_channels_s _rc {}; /**< r/c channel data */
|
||||
|
||||
|
||||
@ -955,7 +955,7 @@ Replay::publishTopic(Subscription &sub, void *data)
|
||||
|
||||
if (advertised) {
|
||||
int instance;
|
||||
sub.orb_advert = orb_advertise_multi(sub.orb_meta, data, &instance, ORB_PRIO_DEFAULT);
|
||||
sub.orb_advert = orb_advertise_multi(sub.orb_meta, data, &instance);
|
||||
published = true;
|
||||
}
|
||||
}
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 0 enabled
|
||||
* Accelerometer 0 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_ACC0_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 1 enabled
|
||||
* Accelerometer 1 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_ACC1_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_ID, 0);
|
||||
|
||||
/**
|
||||
* Accelerometer 2 enabled
|
||||
* Accelerometer 2 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_ACC2_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Accelerometer X-axis offset
|
||||
|
||||
@ -1,40 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Primary accel ID
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_ACC_PRIME, 0);
|
||||
@ -1,40 +0,0 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
* are met:
|
||||
*
|
||||
* 1. Redistributions of source code must retain the above copyright
|
||||
* notice, this list of conditions and the following disclaimer.
|
||||
* 2. Redistributions in binary form must reproduce the above copyright
|
||||
* notice, this list of conditions and the following disclaimer in
|
||||
* the documentation and/or other materials provided with the
|
||||
* distribution.
|
||||
* 3. Neither the name PX4 nor the names of its contributors may be
|
||||
* used to endorse or promote products derived from this software
|
||||
* without specific prior written permission.
|
||||
*
|
||||
* THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
|
||||
* "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
|
||||
* LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
|
||||
* FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
|
||||
* COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
|
||||
* INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
|
||||
* BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS
|
||||
* OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED
|
||||
* AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
|
||||
* LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
|
||||
* ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
|
||||
* POSSIBILITY OF SUCH DAMAGE.
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Primary gyro ID
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO_PRIME, 0);
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 0 enabled
|
||||
* Gyro 0 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_GYRO0_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 1 enabled
|
||||
* Gyro 1 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_GYRO1_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2018 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -40,13 +40,19 @@
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_ID, 0);
|
||||
|
||||
/**
|
||||
* Gyro 2 enabled
|
||||
* Gyro 2 priority.
|
||||
*
|
||||
* @value 0 Disabled
|
||||
* @value 1 Min
|
||||
* @value 25 Low
|
||||
* @value 50 Medium (Default)
|
||||
* @value 75 High
|
||||
* @value 100 Max
|
||||
*
|
||||
* @boolean
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_EN, 1);
|
||||
PARAM_DEFINE_INT32(CAL_GYRO2_PRIO, 50);
|
||||
|
||||
/**
|
||||
* Gyro X-axis offset
|
||||
|
||||
@ -1,6 +1,6 @@
|
||||
/****************************************************************************
|
||||
*
|
||||
* Copyright (c) 2012-2017 PX4 Development Team. All rights reserved.
|
||||
* Copyright (c) 2012-2020 PX4 Development Team. All rights reserved.
|
||||
*
|
||||
* Redistribution and use in source and binary forms, with or without
|
||||
* modification, are permitted provided that the following conditions
|
||||
@ -31,14 +31,6 @@
|
||||
*
|
||||
****************************************************************************/
|
||||
|
||||
/**
|
||||
* Primary mag ID
|
||||
*
|
||||
* @category system
|
||||
* @group Sensor Calibration
|
||||
*/
|
||||
PARAM_DEFINE_INT32(CAL_MAG_PRIME, 0);
|
||||
|
||||
/**
|
||||
* Bitfield selecting mag sides for calibration
|
||||
*
|
||||
|
||||
Some files were not shown because too many files have changed in this diff Show More
Loading…
x
Reference in New Issue
Block a user