Skip to content

Commit

Permalink
Use accel of the same instance or primary baro for gyro instances tha…
Browse files Browse the repository at this point in the history
…t do not have valid temperature readings in temperature calibration data, use primary baro for magnetometers without valid temperature.
  • Loading branch information
mcsauder committed Jan 4, 2023
1 parent d37ec41 commit 860315d
Show file tree
Hide file tree
Showing 17 changed files with 820 additions and 706 deletions.
1,337 changes: 731 additions & 606 deletions Tools/process_sensor_caldata.py

Large diffs are not rendered by default.

2 changes: 2 additions & 0 deletions platforms/common/include/px4_platform_common/defines.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,8 @@
#ifdef __cplusplus
static inline constexpr bool PX4_ISFINITE(float x) { return __builtin_isfinite(x); }
static inline constexpr bool PX4_ISFINITE(double x) { return __builtin_isfinite(x); }
static inline constexpr bool PX4_ISNAN(float x) { return __builtin_isnan(x); }
static inline constexpr bool PX4_ISNAN(double x) { return __builtin_isnan(x); }
#else
#define PX4_ISFINITE(x) __builtin_isfinite(x)
#endif /* __cplusplus */
Expand Down
19 changes: 0 additions & 19 deletions src/drivers/magnetometer/isentek/ist8308/IST8308.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -220,13 +220,6 @@ void IST8308::RunImpl()
perf_count(_bad_register_perf);
Reset();
}

} else {
// periodically update temperature (~1 Hz)
if (hrt_elapsed_time(&_temperature_update_timestamp) >= 1_s) {
UpdateTemperature();
_temperature_update_timestamp = now;
}
}
}

Expand Down Expand Up @@ -298,15 +291,3 @@ void IST8308::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t cle
RegisterWrite(reg, val);
}
}

void IST8308::UpdateTemperature()
{
// Isentek magnetometers do not have a temperature sensor, so we will to use the baro's value.
sensor_baro_s sensor_baro;

if (_sensor_baro_sub[0].update(&sensor_baro)) {
if (PX4_ISFINITE(sensor_baro.temperature)) {
_px4_mag.set_temperature(sensor_baro.temperature);
}
}
}
7 changes: 0 additions & 7 deletions src/drivers/magnetometer/isentek/ist8308/IST8308.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -48,8 +48,6 @@
#include <lib/perf/perf_counter.h>
#include <lib/sensor_calibration/Barometer.hpp>
#include <px4_platform_common/i2c_spi_buses.h>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/sensor_baro.h>

using namespace iSentek_IST8308;

Expand Down Expand Up @@ -96,10 +94,6 @@ class IST8308 : public device::I2C, public I2CSPIDriver<IST8308>

void RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits);

void UpdateTemperature();

uORB::SubscriptionMultiArray<sensor_baro_s, calibration::Barometer::MAX_SENSOR_COUNT> _sensor_baro_sub{ORB_ID::sensor_baro};

PX4Magnetometer _px4_mag;

perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
Expand All @@ -108,7 +102,6 @@ class IST8308 : public device::I2C, public I2CSPIDriver<IST8308>

hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
hrt_abstime _temperature_update_timestamp{0};

int _failure_count{0};

Expand Down
20 changes: 0 additions & 20 deletions src/drivers/magnetometer/isentek/ist8310/IST8310.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -188,7 +188,6 @@ void IST8310::RunImpl()

_px4_mag.set_error_count(perf_event_count(_bad_register_perf) + perf_event_count(_bad_transfer_perf));
_px4_mag.update(now, x, y, z);
UpdateTemperature();

success = true;

Expand Down Expand Up @@ -223,13 +222,6 @@ void IST8310::RunImpl()
Reset();
return;
}

} else {
// periodically update temperature (~1 Hz)
if (hrt_elapsed_time(&_temperature_update_timestamp) >= 1_s) {
UpdateTemperature();
_temperature_update_timestamp = now;
}
}

// initiate next measurement
Expand Down Expand Up @@ -304,15 +296,3 @@ void IST8310::RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t cle
RegisterWrite(reg, val);
}
}

void IST8310::UpdateTemperature()
{
// Isentek magnetometers do not have a temperature sensor, so we will to use the baro's value.
sensor_baro_s sensor_baro;

if (_sensor_baro_sub[0].update(&sensor_baro)) {
if (PX4_ISFINITE(sensor_baro.temperature)) {
_px4_mag.set_temperature(sensor_baro.temperature);
}
}
}
8 changes: 0 additions & 8 deletions src/drivers/magnetometer/isentek/ist8310/IST8310.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -46,10 +46,7 @@
#include <lib/drivers/device/i2c.h>
#include <lib/drivers/magnetometer/PX4Magnetometer.hpp>
#include <lib/perf/perf_counter.h>
#include <lib/sensor_calibration/Barometer.hpp>
#include <px4_platform_common/i2c_spi_buses.h>
#include <uORB/SubscriptionMultiArray.hpp>
#include <uORB/topics/sensor_baro.h>

using namespace iSentek_IST8310;

Expand Down Expand Up @@ -97,10 +94,6 @@ class IST8310 : public device::I2C, public I2CSPIDriver<IST8310>

void RegisterSetAndClearBits(Register reg, uint8_t setbits, uint8_t clearbits);

void UpdateTemperature();

uORB::SubscriptionMultiArray<sensor_baro_s, calibration::Barometer::MAX_SENSOR_COUNT> _sensor_baro_sub{ORB_ID::sensor_baro};

PX4Magnetometer _px4_mag;

perf_counter_t _bad_register_perf{perf_alloc(PC_COUNT, MODULE_NAME": bad register")};
Expand All @@ -109,7 +102,6 @@ class IST8310 : public device::I2C, public I2CSPIDriver<IST8310>

hrt_abstime _reset_timestamp{0};
hrt_abstime _last_config_check_timestamp{0};
hrt_abstime _temperature_update_timestamp{0};

int _failure_count{0};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -215,9 +215,11 @@ void VehicleAcceleration::Run()
// update corrections first to set _selected_sensor
bool selection_updated = SensorSelectionUpdate();

ParametersUpdate();

_calibration.SensorCorrectionsUpdate(selection_updated);

SensorBiasUpdate(selection_updated);
ParametersUpdate();

// require valid sensor sample rate to run
if (!PX4_ISFINITE(_filter_sample_rate)) {
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -790,6 +790,8 @@ void VehicleAngularVelocity::Run()

const hrt_abstime time_now_us = hrt_absolute_time();

ParametersUpdate();

// update corrections first to set _selected_sensor
const bool selection_updated = SensorSelectionUpdate(time_now_us);

Expand All @@ -801,9 +803,8 @@ void VehicleAngularVelocity::Run()
}
}

ParametersUpdate();

_calibration.SensorCorrectionsUpdate(selection_updated);

SensorBiasUpdate(selection_updated);

if (_reset_filters) {
Expand Down
16 changes: 10 additions & 6 deletions src/modules/sensors/vehicle_magnetometer/VehicleMagnetometer.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -360,8 +360,8 @@ void VehicleMagnetometer::UpdatePowerCompensation()
actuator_controls_s controls;

if (_actuator_controls_0_sub.update(&controls)) {
for (auto &cal : _calibration) {
cal.UpdatePower(controls.control[actuator_controls_s::INDEX_THROTTLE]);
for (int i = 0; i < MAX_SENSOR_COUNT; i++) {
_calibration[i].UpdatePower(controls.control[actuator_controls_s::INDEX_THROTTLE]);
}
}

Expand All @@ -373,14 +373,14 @@ void VehicleMagnetometer::UpdatePowerCompensation()
if (_battery_status_sub.update(&bat_stat)) {
float power = bat_stat.current_a * 0.001f; // current in [kA]

for (auto &cal : _calibration) {
cal.UpdatePower(power);
for (int i = 0; i < MAX_SENSOR_COUNT; i++) {
_calibration[i].UpdatePower(power);
}
}

} else {
for (auto &cal : _calibration) {
cal.UpdatePower(0.f);
for (int i = 0; i < MAX_SENSOR_COUNT; i++) {
_calibration[i].UpdatePower(0.f);
}
}
}
Expand All @@ -403,6 +403,10 @@ void VehicleMagnetometer::Run()
}
}

for (int i = 0; i < MAX_SENSOR_COUNT; i++) {
_calibration[i].SensorCorrectionsUpdate();
}

UpdatePowerCompensation();

UpdateMagBiasEstimate();
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -146,6 +146,7 @@ class VehicleMagnetometer : public ModuleParams, public px4::ScheduledWorkItem
Current_inst0,
Current_inst1
};

MagCompensationType _mag_comp_type{MagCompensationType::Disabled};

perf_counter_t _cycle_perf{perf_alloc(PC_ELAPSED, MODULE_NAME": cycle")};
Expand All @@ -158,6 +159,7 @@ class VehicleMagnetometer : public ModuleParams, public px4::ScheduledWorkItem

uint64_t _timestamp_sample_sum[MAX_SENSOR_COUNT] {};
matrix::Vector3f _data_sum[MAX_SENSOR_COUNT] {};

int _data_sum_count[MAX_SENSOR_COUNT] {};
hrt_abstime _last_publication_timestamp[MAX_SENSOR_COUNT] {};

Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -144,16 +144,16 @@ void TemperatureCompensationModule::accelPoll()

// For each accel instance
for (uint8_t uorb_index = 0; uorb_index < ACCEL_COUNT_MAX; uorb_index++) {
sensor_accel_s report;
sensor_accel_s sensor_accel;

// Grab temperature from report
if (_accel_subs[uorb_index].update(&report)) {
if (PX4_ISFINITE(report.temperature)) {
// Grab temperature from accel
if (_accel_subs[uorb_index].update(&sensor_accel)) {
if (PX4_ISFINITE(sensor_accel.temperature)) {
// Update the offsets and mark for publication if they've changed
if (_temperature_compensation.update_offsets_accel(uorb_index, report.temperature, offsets[uorb_index]) == 2) {
if (_temperature_compensation.update_offsets_accel(uorb_index, sensor_accel.temperature, offsets[uorb_index]) == 2) {

_corrections.accel_device_ids[uorb_index] = report.device_id;
_corrections.accel_temperature[uorb_index] = report.temperature;
_corrections.accel_device_ids[uorb_index] = sensor_accel.device_id;
_corrections.accel_temperature[uorb_index] = sensor_accel.temperature;
_corrections_changed = true;
}
}
Expand All @@ -167,16 +167,28 @@ void TemperatureCompensationModule::gyroPoll()

// For each gyro instance
for (uint8_t uorb_index = 0; uorb_index < GYRO_COUNT_MAX; uorb_index++) {
sensor_gyro_s report;
sensor_gyro_s sensor_gyro;

// Grab temperature from report
if (_gyro_subs[uorb_index].update(&report)) {
if (PX4_ISFINITE(report.temperature)) {
// Grab temperature from gyro
if (_gyro_subs[uorb_index].update(&sensor_gyro)) {
if (PX4_ISFINITE(sensor_gyro.temperature)) {
// Update the offsets and mark for publication if they've changed
if (_temperature_compensation.update_offsets_gyro(uorb_index, report.temperature, offsets[uorb_index]) == 2) {
if (_temperature_compensation.update_offsets_gyro(uorb_index, sensor_gyro.temperature, offsets[uorb_index]) == 2) {

_corrections.gyro_device_ids[uorb_index] = sensor_gyro.device_id;
_corrections.gyro_temperature[uorb_index] = sensor_gyro.temperature;
_corrections_changed = true;
}

} else if (PX4_ISNAN(sensor_gyro.temperature)) {

_corrections.gyro_device_ids[uorb_index] = sensor_gyro.device_id;

_corrections.gyro_device_ids[uorb_index] = report.device_id;
_corrections.gyro_temperature[uorb_index] = report.temperature;
// Use accelerometer of the same instance if gyro temperature was NAN.
sensor_accel_s sensor_accel;

if (_accel_subs[uorb_index].update(&sensor_accel)) {
_corrections.gyro_temperature[uorb_index] = sensor_accel.temperature;
_corrections_changed = true;
}
}
Expand All @@ -190,16 +202,28 @@ void TemperatureCompensationModule::magPoll()

// For each mag instance
for (uint8_t uorb_index = 0; uorb_index < MAG_COUNT_MAX; uorb_index++) {
sensor_mag_s report;
sensor_mag_s sensor_mag;

// Grab temperature from report
if (_mag_subs[uorb_index].update(&report)) {
if (PX4_ISFINITE(report.temperature)) {
if (_mag_subs[uorb_index].update(&sensor_mag)) {
if (PX4_ISFINITE(sensor_mag.temperature)) {
// Update the offsets and mark for publication if they've changed
if (_temperature_compensation.update_offsets_mag(uorb_index, report.temperature, offsets[uorb_index]) == 2) {
if (_temperature_compensation.update_offsets_mag(uorb_index, sensor_mag.temperature, offsets[uorb_index]) == 2) {

_corrections.mag_device_ids[uorb_index] = sensor_mag.device_id;
_corrections.mag_temperature[uorb_index] = sensor_mag.temperature;
_corrections_changed = true;
}

} else if (PX4_ISNAN(sensor_mag.temperature)) {

_corrections.mag_device_ids[uorb_index] = report.device_id;
_corrections.mag_temperature[uorb_index] = report.temperature;
_corrections.mag_device_ids[uorb_index] = sensor_mag.device_id;

// Use primary baro instance if mag temperature was NAN.
sensor_baro_s sensor_baro;

if (_accel_subs[0].update(&sensor_baro)) {
_corrections.mag_temperature[uorb_index] = sensor_baro.temperature;
_corrections_changed = true;
}
}
Expand All @@ -213,16 +237,28 @@ void TemperatureCompensationModule::baroPoll()

// For each baro instance
for (uint8_t uorb_index = 0; uorb_index < BARO_COUNT_MAX; uorb_index++) {
sensor_baro_s report;
sensor_baro_s sensor_baro;

// Grab temperature from report
if (_baro_subs[uorb_index].update(&report)) {
if (PX4_ISFINITE(report.temperature)) {
if (_baro_subs[uorb_index].update(&sensor_baro)) {
if (PX4_ISFINITE(sensor_baro.temperature)) {
// Update the offsets and mark for publication if they've changed
if (_temperature_compensation.update_offsets_baro(uorb_index, report.temperature, offsets[uorb_index]) == 2) {
if (_temperature_compensation.update_offsets_baro(uorb_index, sensor_baro.temperature, offsets[uorb_index]) == 2) {

_corrections.baro_device_ids[uorb_index] = sensor_baro.device_id;
_corrections.baro_temperature[uorb_index] = sensor_baro.temperature;
_corrections_changed = true;
}

} else if (PX4_ISNAN(sensor_baro.temperature)) {

_corrections.baro_device_ids[uorb_index] = sensor_baro.device_id;

// Use primary accelerometer instance if baro temperature was NAN.
sensor_accel_s sensor_accel;

_corrections.baro_device_ids[uorb_index] = report.device_id;
_corrections.baro_temperature[uorb_index] = report.temperature;
if (_accel_subs[0].update(&sensor_accel)) {
_corrections.baro_temperature[uorb_index] = sensor_accel.temperature;
_corrections_changed = true;
}
}
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2022 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2017-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2017-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2017-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
Expand Down
Original file line number Diff line number Diff line change
@@ -1,6 +1,6 @@
/****************************************************************************
*
* Copyright (c) 2017-2020 PX4 Development Team. All rights reserved.
* Copyright (c) 2022-2023 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
Expand Down
Loading

0 comments on commit 860315d

Please sign in to comment.