From a7e1b82a4a5ff5ffde384fe8fbdd7e439a1c2434 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Mon, 2 Mar 2020 18:40:15 -0500 Subject: [PATCH] accel and gyro calibration cleanup - kill IOCTLs for accel and gyro calibration - move accel/calibration entirely to sensors module --- .ci/Jenkinsfile-hardware | 4 + boards/atlflight/eagle/default.cmake | 1 - boards/atlflight/excelsior/default.cmake | 1 - boards/px4/fmu-v2/default.cmake | 1 - boards/px4/fmu-v2/fixedwing.cmake | 1 - boards/px4/fmu-v2/lpe.cmake | 1 - boards/px4/fmu-v2/multicopter.cmake | 1 - boards/px4/fmu-v2/rover.cmake | 1 - boards/px4/fmu-v2/test.cmake | 1 - boards/px4/sitl/default.cmake | 1 - boards/px4/sitl/rtps.cmake | 1 - boards/px4/sitl/test.cmake | 1 - .../px4_platform_common/module_params.h | 14 +- .../distance_sensor/cm8jl65/CM8JL65.cpp | 2 + .../distance_sensor/leddar_one/LeddarOne.cpp | 1 + src/drivers/distance_sensor/sf0x/SF0X.cpp | 1 + src/drivers/distance_sensor/tfmini/TFMINI.cpp | 2 + src/drivers/drv_accel.h | 75 --- src/drivers/drv_gyro.h | 70 --- src/drivers/drv_mixer.h | 2 +- .../matlab_csv_serial/matlab_csv_serial.c | 2 - .../accelerometer/PX4Accelerometer.cpp | 76 +-- .../accelerometer/PX4Accelerometer.hpp | 15 +- src/lib/drivers/barometer/PX4Barometer.cpp | 11 +- src/lib/drivers/barometer/PX4Barometer.hpp | 2 +- src/lib/drivers/gyroscope/PX4Gyroscope.cpp | 74 +-- src/lib/drivers/gyroscope/PX4Gyroscope.hpp | 16 +- .../drivers/magnetometer/PX4Magnetometer.cpp | 2 +- .../drivers/magnetometer/PX4Magnetometer.hpp | 2 +- .../drivers/rangefinder/PX4Rangefinder.cpp | 27 +- .../drivers/rangefinder/PX4Rangefinder.hpp | 10 +- src/modules/commander/Commander.cpp | 2 +- .../commander/accelerometer_calibration.cpp | 533 ++++++------------ .../commander/calibration_routines.cpp | 2 +- src/modules/commander/calibration_routines.h | 3 - src/modules/commander/gyro_calibration.cpp | 330 ++++------- src/modules/commander/mag_calibration.cpp | 135 +++-- .../sensors/sensor_corrections/CMakeLists.txt | 2 + .../sensor_corrections/SensorCorrections.cpp | 87 +++ .../sensor_corrections/SensorCorrections.hpp | 6 +- src/modules/sensors/voted_sensors_update.cpp | 175 +----- src/modules/sensors/voted_sensors_update.h | 18 +- src/modules/uORB/SubscriptionBlocking.hpp | 31 +- 43 files changed, 564 insertions(+), 1179 deletions(-) delete mode 100644 src/drivers/drv_accel.h delete mode 100644 src/drivers/drv_gyro.h diff --git a/.ci/Jenkinsfile-hardware b/.ci/Jenkinsfile-hardware index 5ce6f64fd297..42be1a478ee2 100644 --- a/.ci/Jenkinsfile-hardware +++ b/.ci/Jenkinsfile-hardware @@ -759,6 +759,8 @@ void statusFTDI() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "adc test"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander check"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander status"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dataman status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "dmesg"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-FTDI_*` --cmd "ekf2 status"' @@ -817,6 +819,8 @@ void statusSEGGER() { sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "adc test"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander check"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander status"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate gyro; sleep 2; param show CAL_GYRO*"' + sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "commander calibrate level; sleep 2; param show SENS_BOARD*"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dataman status"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "dmesg"' sh './Tools/HIL/run_nsh_cmd.py --device `find /dev/serial -name *usb-SEGGER_*` --cmd "ekf2 status"' diff --git a/boards/atlflight/eagle/default.cmake b/boards/atlflight/eagle/default.cmake index 31ffca63d2cb..b86627189046 100644 --- a/boards/atlflight/eagle/default.cmake +++ b/boards/atlflight/eagle/default.cmake @@ -89,7 +89,6 @@ px4_add_board( vtol_att_control SYSTEMCMDS #bl_update - #config #dumpfile esc_calib #hardfault_log diff --git a/boards/atlflight/excelsior/default.cmake b/boards/atlflight/excelsior/default.cmake index ef8ef133c105..d5be4b6c2c05 100644 --- a/boards/atlflight/excelsior/default.cmake +++ b/boards/atlflight/excelsior/default.cmake @@ -88,7 +88,6 @@ px4_add_board( vtol_att_control SYSTEMCMDS #bl_update - #config #dumpfile esc_calib #hardfault_log diff --git a/boards/px4/fmu-v2/default.cmake b/boards/px4/fmu-v2/default.cmake index eb1870704e87..64573c79a0b4 100644 --- a/boards/px4/fmu-v2/default.cmake +++ b/boards/px4/fmu-v2/default.cmake @@ -99,7 +99,6 @@ px4_add_board( #vtol_att_control SYSTEMCMDS bl_update - #config #dmesg #dumpfile #esc_calib diff --git a/boards/px4/fmu-v2/fixedwing.cmake b/boards/px4/fmu-v2/fixedwing.cmake index 10e9ab2107ca..a940b3832e09 100644 --- a/boards/px4/fmu-v2/fixedwing.cmake +++ b/boards/px4/fmu-v2/fixedwing.cmake @@ -62,7 +62,6 @@ px4_add_board( #vmount SYSTEMCMDS #bl_update - #config #dumpfile #esc_calib hardfault_log diff --git a/boards/px4/fmu-v2/lpe.cmake b/boards/px4/fmu-v2/lpe.cmake index f62e1df08e8d..db737270b319 100644 --- a/boards/px4/fmu-v2/lpe.cmake +++ b/boards/px4/fmu-v2/lpe.cmake @@ -87,7 +87,6 @@ px4_add_board( SYSTEMCMDS bl_update - #config #dumpfile #esc_calib hardfault_log diff --git a/boards/px4/fmu-v2/multicopter.cmake b/boards/px4/fmu-v2/multicopter.cmake index 7bda7d2f2bdf..08dceecfb306 100644 --- a/boards/px4/fmu-v2/multicopter.cmake +++ b/boards/px4/fmu-v2/multicopter.cmake @@ -60,7 +60,6 @@ px4_add_board( vmount SYSTEMCMDS #bl_update - #config #dumpfile #esc_calib hardfault_log diff --git a/boards/px4/fmu-v2/rover.cmake b/boards/px4/fmu-v2/rover.cmake index 0d21c0f4cdd0..412fd3ae0d36 100644 --- a/boards/px4/fmu-v2/rover.cmake +++ b/boards/px4/fmu-v2/rover.cmake @@ -55,7 +55,6 @@ px4_add_board( SYSTEMCMDS bl_update - #config #dumpfile #esc_calib hardfault_log diff --git a/boards/px4/fmu-v2/test.cmake b/boards/px4/fmu-v2/test.cmake index 1d99a04e6420..2e918e92cf3e 100644 --- a/boards/px4/fmu-v2/test.cmake +++ b/boards/px4/fmu-v2/test.cmake @@ -92,7 +92,6 @@ px4_add_board( #vtol_att_control SYSTEMCMDS #bl_update - #config #dmesg #dumpfile #esc_calib diff --git a/boards/px4/sitl/default.cmake b/boards/px4/sitl/default.cmake index 6851856df3be..3185101c4a88 100644 --- a/boards/px4/sitl/default.cmake +++ b/boards/px4/sitl/default.cmake @@ -53,7 +53,6 @@ px4_add_board( uuv_att_control SYSTEMCMDS - #config #dumpfile dyn esc_calib diff --git a/boards/px4/sitl/rtps.cmake b/boards/px4/sitl/rtps.cmake index d764464867d0..0375489f3da8 100644 --- a/boards/px4/sitl/rtps.cmake +++ b/boards/px4/sitl/rtps.cmake @@ -52,7 +52,6 @@ px4_add_board( vmount vtol_att_control SYSTEMCMDS - #config #dumpfile dyn esc_calib diff --git a/boards/px4/sitl/test.cmake b/boards/px4/sitl/test.cmake index bd003ba060b7..041df406e255 100644 --- a/boards/px4/sitl/test.cmake +++ b/boards/px4/sitl/test.cmake @@ -50,7 +50,6 @@ px4_add_board( vmount vtol_att_control SYSTEMCMDS - #config #dumpfile dyn esc_calib diff --git a/platforms/common/include/px4_platform_common/module_params.h b/platforms/common/include/px4_platform_common/module_params.h index d2e518f0cebc..4b4a46977d0e 100644 --- a/platforms/common/include/px4_platform_common/module_params.h +++ b/platforms/common/include/px4_platform_common/module_params.h @@ -52,6 +52,14 @@ class ModuleParams : public ListNode setParent(parent); } + // empty copy and move constructors (don't copy _children) + ModuleParams(const ModuleParams &) {}; + ModuleParams(ModuleParams &&) {}; + + // no assignment + ModuleParams &operator=(const ModuleParams &) = delete; + ModuleParams &operator=(ModuleParams &&) = delete; + /** * @brief Sets the parent module. This is typically not required, * only in cases where the parent cannot be set via constructor. @@ -65,12 +73,6 @@ class ModuleParams : public ListNode virtual ~ModuleParams() = default; - // Disallow copy construction and move assignment. - ModuleParams(const ModuleParams &) = delete; - ModuleParams &operator=(const ModuleParams &) = delete; - ModuleParams(ModuleParams &&) = delete; - ModuleParams &operator=(ModuleParams &&) = delete; - protected: /** * @brief Call this method whenever the module gets a parameter change notification. diff --git a/src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp b/src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp index 4b591e3f4525..5ede856f7013 100644 --- a/src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp +++ b/src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp @@ -33,6 +33,8 @@ #include "CM8JL65.hpp" +#include + static constexpr unsigned char crc_msb_vector[] = { 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, 0x01, 0xC0, 0x80, 0x41, 0x00, 0xC1, 0x81, 0x40, diff --git a/src/drivers/distance_sensor/leddar_one/LeddarOne.cpp b/src/drivers/distance_sensor/leddar_one/LeddarOne.cpp index 410c04f84384..edc447ac3ce6 100644 --- a/src/drivers/distance_sensor/leddar_one/LeddarOne.cpp +++ b/src/drivers/distance_sensor/leddar_one/LeddarOne.cpp @@ -33,6 +33,7 @@ #include "LeddarOne.hpp" +#include #include #include diff --git a/src/drivers/distance_sensor/sf0x/SF0X.cpp b/src/drivers/distance_sensor/sf0x/SF0X.cpp index 45800e10f407..eefdb781f86a 100644 --- a/src/drivers/distance_sensor/sf0x/SF0X.cpp +++ b/src/drivers/distance_sensor/sf0x/SF0X.cpp @@ -33,6 +33,7 @@ #include "SF0X.hpp" +#include #include /* Configuration Constants */ diff --git a/src/drivers/distance_sensor/tfmini/TFMINI.cpp b/src/drivers/distance_sensor/tfmini/TFMINI.cpp index 4e18c849e26e..25c5b80d55de 100644 --- a/src/drivers/distance_sensor/tfmini/TFMINI.cpp +++ b/src/drivers/distance_sensor/tfmini/TFMINI.cpp @@ -33,6 +33,8 @@ #include "TFMINI.hpp" +#include + 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) diff --git a/src/drivers/drv_accel.h b/src/drivers/drv_accel.h deleted file mode 100644 index 00002ad7b223..000000000000 --- a/src/drivers/drv_accel.h +++ /dev/null @@ -1,75 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 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. - * - ****************************************************************************/ - -/** - * @file drv_accel.h - * - * Accelerometer driver interface. - */ - -#ifndef _DRV_ACCEL_H -#define _DRV_ACCEL_H - -#include -#include - -#include "drv_sensor.h" -#include "drv_orb_dev.h" - -#define ACCEL_BASE_DEVICE_PATH "/dev/accel" - -#include - -/** accel scaling factors; Vout = Vscale * (Vin + Voffset) */ -struct accel_calibration_s { - float x_offset; - float x_scale; - float y_offset; - float y_scale; - float z_offset; - float z_scale; -}; -/* - * ioctl() definitions - * - * Accelerometer drivers also implement the generic sensor driver - * interfaces from drv_sensor.h - */ - -#define _ACCELIOCBASE (0x2100) -#define _ACCELIOC(_n) (_PX4_IOC(_ACCELIOCBASE, _n)) - -/** set the accel scaling constants to the structure pointed to by (arg) */ -#define ACCELIOCSSCALE _ACCELIOC(5) - -#endif /* _DRV_ACCEL_H */ diff --git a/src/drivers/drv_gyro.h b/src/drivers/drv_gyro.h deleted file mode 100644 index 945ee92e97ae..000000000000 --- a/src/drivers/drv_gyro.h +++ /dev/null @@ -1,70 +0,0 @@ -/**************************************************************************** - * - * Copyright (c) 2012-2016 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. - * - ****************************************************************************/ - -/** - * @file drv_gyro.h - * - * Gyroscope driver interface. - */ - -#ifndef _DRV_GYRO_H -#define _DRV_GYRO_H - -#include -#include - -#include "drv_sensor.h" -#include "drv_orb_dev.h" - -#define GYRO_BASE_DEVICE_PATH "/dev/gyro" - -#include - -/** gyro scaling factors; Vout = Vin + Voffset */ -struct gyro_calibration_s { - float x_offset; - float y_offset; - float z_offset; -}; - -/* - * ioctl() definitions - */ - -#define _GYROIOCBASE (0x2300) -#define _GYROIOC(_n) (_PX4_IOC(_GYROIOCBASE, _n)) - -/** set the gyro scaling constants to (arg) */ -#define GYROIOCSSCALE _GYROIOC(4) - -#endif /* _DRV_GYRO_H */ diff --git a/src/drivers/drv_mixer.h b/src/drivers/drv_mixer.h index 317eb33942e9..2c54885d7909 100644 --- a/src/drivers/drv_mixer.h +++ b/src/drivers/drv_mixer.h @@ -85,4 +85,4 @@ * - save/serialise for saving tuned mixers. */ -#endif /* _DRV_ACCEL_H */ +#endif /* _DRV_MIXER_H */ diff --git a/src/examples/matlab_csv_serial/matlab_csv_serial.c b/src/examples/matlab_csv_serial/matlab_csv_serial.c index c1c14f0d448f..78a7b79a0e0c 100644 --- a/src/examples/matlab_csv_serial/matlab_csv_serial.c +++ b/src/examples/matlab_csv_serial/matlab_csv_serial.c @@ -56,8 +56,6 @@ #include #include #include -#include -#include #include #include #include diff --git a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp index 5dc95b84fef4..55581f01c58d 100644 --- a/src/lib/drivers/accelerometer/PX4Accelerometer.cpp +++ b/src/lib/drivers/accelerometer/PX4Accelerometer.cpp @@ -39,7 +39,7 @@ using namespace time_literals; using matrix::Vector3f; -static inline int32_t sum(const int16_t samples[16], uint8_t len) +static constexpr int32_t sum(const int16_t samples[16], uint8_t len) { int32_t sum = 0; @@ -64,7 +64,6 @@ static constexpr unsigned clipping(const int16_t samples[16], int16_t clip_limit } PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Rotation rotation) : - CDev(nullptr), _sensor_pub{ORB_ID(sensor_accel), priority}, _sensor_fifo_pub{ORB_ID(sensor_accel_fifo), priority}, _sensor_integrated_pub{ORB_ID(sensor_accel_integrated), priority}, @@ -73,36 +72,6 @@ PX4Accelerometer::PX4Accelerometer(uint32_t device_id, uint8_t priority, enum Ro _rotation{rotation}, _rotation_dcm{get_rot_matrix(rotation)} { - _class_device_instance = register_class_devname(ACCEL_BASE_DEVICE_PATH); -} - -PX4Accelerometer::~PX4Accelerometer() -{ - if (_class_device_instance != -1) { - unregister_class_devname(ACCEL_BASE_DEVICE_PATH, _class_device_instance); - } -} - -int PX4Accelerometer::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) -{ - switch (cmd) { - case ACCELIOCSSCALE: { - // Copy offsets and scale factors in - accel_calibration_s cal{}; - memcpy(&cal, (accel_calibration_s *) arg, sizeof(cal)); - - _calibration_offset = Vector3f{cal.x_offset, cal.y_offset, cal.z_offset}; - _calibration_scale = Vector3f{cal.x_scale, cal.y_scale, cal.z_scale}; - } - - return PX4_OK; - - case DEVIOCGDEVICEID: - return _device_id; - - default: - return -ENOTTY; - } } void PX4Accelerometer::set_device_type(uint8_t devtype) @@ -127,7 +96,7 @@ void PX4Accelerometer::set_update_rate(uint16_t rate) _integrator_reset_samples = 2500 / update_interval; } -void PX4Accelerometer::update(hrt_abstime timestamp_sample, float x, float y, float z) +void PX4Accelerometer::update(const hrt_abstime ×tamp_sample, float x, float y, float z) { // Apply rotation (before scaling) rotate_3f(_rotation, x, y, z); @@ -142,8 +111,8 @@ void PX4Accelerometer::update(hrt_abstime timestamp_sample, float x, float y, fl } } - // Apply range scale and the calibrating offset/scale - const Vector3f val_calibrated{(((raw * _scale) - _calibration_offset).emult(_calibration_scale))}; + // Apply range scale + const Vector3f val{raw * _scale}; // publish raw data immediately { @@ -152,9 +121,9 @@ void PX4Accelerometer::update(hrt_abstime timestamp_sample, float x, float y, fl report.timestamp_sample = timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; - report.x = val_calibrated(0); - report.y = val_calibrated(1); - report.z = val_calibrated(2); + report.x = val(0); + report.y = val(1); + report.z = val(2); report.timestamp = hrt_absolute_time(); _sensor_pub.publish(report); @@ -166,7 +135,7 @@ void PX4Accelerometer::update(hrt_abstime timestamp_sample, float x, float y, fl _integrator_samples++; - if (_integrator.put(timestamp_sample, val_calibrated, delta_velocity, integral_dt)) { + if (_integrator.put(timestamp_sample, val, delta_velocity, integral_dt)) { // fill sensor_accel_integrated and publish sensor_accel_integrated_s report; @@ -212,17 +181,17 @@ void PX4Accelerometer::updateFIFO(const FIFOSample &sample) // Apply rotation (before scaling) rotate_3f(_rotation, x, y, z); - // Apply range scale and the calibrating offset/scale - const Vector3f val_calibrated{((Vector3f{x, y, z} * _scale) - _calibration_offset).emult(_calibration_scale)}; + // Apply range scale + const Vector3f val{Vector3f{x, y, z} *_scale}; sensor_accel_s report; report.timestamp_sample = sample.timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; - report.x = val_calibrated(0); - report.y = val_calibrated(1); - report.z = val_calibrated(2); + report.x = val(0); + report.y = val(1); + report.z = val(2); report.timestamp = hrt_absolute_time(); _sensor_pub.publish(report); @@ -268,14 +237,7 @@ void PX4Accelerometer::updateFIFO(const FIFOSample &sample) // Apply rotation and scale // integrated in microseconds, convert to seconds - const Vector3f delta_velocity_uncalibrated{_rotation_dcm *_integration_raw * _scale}; - - // scale calibration offset to number of samples - const Vector3f offset{_calibration_offset * _integrator_fifo_samples}; - - // Apply calibration and scale to seconds - Vector3f delta_velocity{((delta_velocity_uncalibrated - offset).emult(_calibration_scale))}; - delta_velocity *= 1e-6f * dt; + const Vector3f delta_velocity{_rotation_dcm *_integration_raw *_scale * 1e-6f * dt}; // fill sensor_accel_integrated and publish sensor_accel_integrated_s report; @@ -376,10 +338,8 @@ void PX4Accelerometer::UpdateVibrationMetrics(const Vector3f &delta_velocity) void PX4Accelerometer::print_status() { - PX4_INFO(ACCEL_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); - - PX4_INFO("calibration scale: %.5f %.5f %.5f", (double)_calibration_scale(0), (double)_calibration_scale(1), - (double)_calibration_scale(2)); - PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1), - (double)_calibration_offset(2)); + char device_id_buffer[80] {}; + device::Device::device_id_print_buffer(device_id_buffer, sizeof(device_id_buffer), _device_id); + PX4_INFO("device id: %d (%s)", _device_id, device_id_buffer); + PX4_INFO("rotation: %d", _rotation); } diff --git a/src/lib/drivers/accelerometer/PX4Accelerometer.hpp b/src/lib/drivers/accelerometer/PX4Accelerometer.hpp index 449cc6d56531..796b5de9d2fc 100644 --- a/src/lib/drivers/accelerometer/PX4Accelerometer.hpp +++ b/src/lib/drivers/accelerometer/PX4Accelerometer.hpp @@ -33,9 +33,7 @@ #pragma once -#include #include -#include #include #include #include @@ -46,13 +44,11 @@ #include #include -class PX4Accelerometer : public cdev::CDev +class PX4Accelerometer { public: PX4Accelerometer(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE); - ~PX4Accelerometer() override; - - int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override; + ~PX4Accelerometer() = default; uint32_t get_device_id() const { return _device_id; } @@ -65,7 +61,7 @@ class PX4Accelerometer : public cdev::CDev void set_temperature(float temperature) { _temperature = temperature; } void set_update_rate(uint16_t rate); - void update(hrt_abstime timestamp_sample, float x, float y, float z); + void update(const hrt_abstime ×tamp_sample, float x, float y, float z); void print_status(); @@ -100,14 +96,9 @@ class PX4Accelerometer : public cdev::CDev Integrator _integrator{2500, false}; - matrix::Vector3f _calibration_scale{1.f, 1.f, 1.f}; - matrix::Vector3f _calibration_offset{0.f, 0.f, 0.f}; - matrix::Vector3f _delta_velocity_prev{0.f, 0.f, 0.f}; // delta velocity from the previous IMU measurement float _vibration_metric{0.f}; // high frequency vibration level in the IMU delta velocity data (m/s) - int _class_device_instance{-1}; - uint32_t _device_id{0}; const enum Rotation _rotation; const matrix::Dcmf _rotation_dcm; diff --git a/src/lib/drivers/barometer/PX4Barometer.cpp b/src/lib/drivers/barometer/PX4Barometer.cpp index ac37f086026f..4dae13446463 100644 --- a/src/lib/drivers/barometer/PX4Barometer.cpp +++ b/src/lib/drivers/barometer/PX4Barometer.cpp @@ -52,8 +52,7 @@ PX4Barometer::~PX4Barometer() } } -void -PX4Barometer::set_device_type(uint8_t devtype) +void PX4Barometer::set_device_type(uint8_t devtype) { // current DeviceStructure union device::Device::DeviceId device_id; @@ -66,19 +65,17 @@ PX4Barometer::set_device_type(uint8_t devtype) _sensor_baro_pub.get().device_id = device_id.devid; } -void -PX4Barometer::update(hrt_abstime timestamp, float pressure) +void PX4Barometer::update(const hrt_abstime ×tamp_sample, float pressure) { sensor_baro_s &report = _sensor_baro_pub.get(); - report.timestamp = timestamp; + report.timestamp = timestamp_sample; report.pressure = pressure; _sensor_baro_pub.update(); } -void -PX4Barometer::print_status() +void PX4Barometer::print_status() { PX4_INFO(BARO_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); diff --git a/src/lib/drivers/barometer/PX4Barometer.hpp b/src/lib/drivers/barometer/PX4Barometer.hpp index a2de6b51087b..3008ff48cb81 100644 --- a/src/lib/drivers/barometer/PX4Barometer.hpp +++ b/src/lib/drivers/barometer/PX4Barometer.hpp @@ -55,7 +55,7 @@ class PX4Barometer : public cdev::CDev void set_temperature(float temperature) { _sensor_baro_pub.get().temperature = temperature; } - void update(hrt_abstime timestamp, float pressure); + void update(const hrt_abstime ×tamp_sample, float pressure); int get_class_instance() { return _class_device_instance; }; diff --git a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp index 633738dec1be..f70c9711176c 100644 --- a/src/lib/drivers/gyroscope/PX4Gyroscope.cpp +++ b/src/lib/drivers/gyroscope/PX4Gyroscope.cpp @@ -39,7 +39,7 @@ using namespace time_literals; using matrix::Vector3f; -static inline int32_t sum(const int16_t samples[16], uint8_t len) +static constexpr int32_t sum(const int16_t samples[16], uint8_t len) { int32_t sum = 0; @@ -64,7 +64,6 @@ static constexpr unsigned clipping(const int16_t samples[16], int16_t clip_limit } PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation rotation) : - CDev(nullptr), ModuleParams(nullptr), _sensor_pub{ORB_ID(sensor_gyro), priority}, _sensor_fifo_pub{ORB_ID(sensor_gyro_fifo), priority}, @@ -74,39 +73,9 @@ PX4Gyroscope::PX4Gyroscope(uint32_t device_id, uint8_t priority, enum Rotation r _rotation{rotation}, _rotation_dcm{get_rot_matrix(rotation)} { - _class_device_instance = register_class_devname(GYRO_BASE_DEVICE_PATH); - updateParams(); } -PX4Gyroscope::~PX4Gyroscope() -{ - if (_class_device_instance != -1) { - unregister_class_devname(GYRO_BASE_DEVICE_PATH, _class_device_instance); - } -} - -int PX4Gyroscope::ioctl(cdev::file_t *filp, int cmd, unsigned long arg) -{ - switch (cmd) { - case GYROIOCSSCALE: { - // Copy offsets and scale factors in - gyro_calibration_s cal{}; - memcpy(&cal, (gyro_calibration_s *) arg, sizeof(cal)); - - _calibration_offset = Vector3f{cal.x_offset, cal.y_offset, cal.z_offset}; - } - - return PX4_OK; - - case DEVIOCGDEVICEID: - return _device_id; - - default: - return -ENOTTY; - } -} - void PX4Gyroscope::set_device_type(uint8_t devtype) { // current DeviceStructure @@ -129,7 +98,7 @@ void PX4Gyroscope::set_update_rate(uint16_t rate) _integrator_reset_samples = 2500 / update_interval; } -void PX4Gyroscope::update(hrt_abstime timestamp_sample, float x, float y, float z) +void PX4Gyroscope::update(const hrt_abstime ×tamp_sample, float x, float y, float z) { // Apply rotation (before scaling) rotate_3f(_rotation, x, y, z); @@ -144,8 +113,8 @@ void PX4Gyroscope::update(hrt_abstime timestamp_sample, float x, float y, float } } - // Apply range scale and the calibrating offset/scale - const Vector3f val_calibrated{((raw * _scale) - _calibration_offset)}; + // Apply range scale + const Vector3f val{raw * _scale}; // publish raw data immediately { @@ -154,9 +123,9 @@ void PX4Gyroscope::update(hrt_abstime timestamp_sample, float x, float y, float report.timestamp_sample = timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; - report.x = val_calibrated(0); - report.y = val_calibrated(1); - report.z = val_calibrated(2); + report.x = val(0); + report.y = val(1); + report.z = val(2); report.timestamp = hrt_absolute_time(); _sensor_pub.publish(report); @@ -168,7 +137,7 @@ void PX4Gyroscope::update(hrt_abstime timestamp_sample, float x, float y, float _integrator_samples++; - if (_integrator.put(timestamp_sample, val_calibrated, delta_angle, integral_dt)) { + if (_integrator.put(timestamp_sample, val, delta_angle, integral_dt)) { // fill sensor_gyro_integrated and publish sensor_gyro_integrated_s report; @@ -214,17 +183,17 @@ void PX4Gyroscope::updateFIFO(const FIFOSample &sample) // Apply rotation (before scaling) rotate_3f(_rotation, x, y, z); - // Apply range scale and the calibration offset - const Vector3f val_calibrated{(Vector3f{x, y, z} * _scale) - _calibration_offset}; + // Apply range scale + const Vector3f val{Vector3f{x, y, z} *_scale}; sensor_gyro_s report; report.timestamp_sample = sample.timestamp_sample; report.device_id = _device_id; report.temperature = _temperature; - report.x = val_calibrated(0); - report.y = val_calibrated(1); - report.z = val_calibrated(2); + report.x = val(0); + report.y = val(1); + report.z = val(2); report.timestamp = hrt_absolute_time(); _sensor_pub.publish(report); @@ -270,14 +239,7 @@ void PX4Gyroscope::updateFIFO(const FIFOSample &sample) // Apply rotation and scale // integrated in microseconds, convert to seconds - const Vector3f delta_angle_uncalibrated{_rotation_dcm *_integration_raw * _scale}; - - // scale calibration offset to number of samples - const Vector3f offset{_calibration_offset * _integrator_fifo_samples}; - - // Apply calibration and scale to seconds - Vector3f delta_angle{delta_angle_uncalibrated - offset}; - delta_angle *= 1e-6f * dt; + const Vector3f delta_angle{_rotation_dcm *_integration_raw *_scale * 1e-6f * dt}; // fill sensor_gyro_integrated and publish sensor_gyro_integrated_s report; @@ -383,8 +345,8 @@ void PX4Gyroscope::UpdateVibrationMetrics(const Vector3f &delta_angle) void PX4Gyroscope::print_status() { - PX4_INFO(GYRO_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); - - PX4_INFO("calibration offset: %.5f %.5f %.5f", (double)_calibration_offset(0), (double)_calibration_offset(1), - (double)_calibration_offset(2)); + char device_id_buffer[80] {}; + device::Device::device_id_print_buffer(device_id_buffer, sizeof(device_id_buffer), _device_id); + PX4_INFO("device id: %d (%s)", _device_id, device_id_buffer); + PX4_INFO("rotation: %d", _rotation); } diff --git a/src/lib/drivers/gyroscope/PX4Gyroscope.hpp b/src/lib/drivers/gyroscope/PX4Gyroscope.hpp index 97a1b6ed7c8b..e46c34835253 100644 --- a/src/lib/drivers/gyroscope/PX4Gyroscope.hpp +++ b/src/lib/drivers/gyroscope/PX4Gyroscope.hpp @@ -1,6 +1,6 @@ /**************************************************************************** * - * Copyright (c) 2018 PX4 Development Team. All rights reserved. + * Copyright (c) 2018-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 @@ -33,9 +33,7 @@ #pragma once -#include #include -#include #include #include #include @@ -46,13 +44,11 @@ #include #include -class PX4Gyroscope : public cdev::CDev, public ModuleParams +class PX4Gyroscope : public ModuleParams { public: PX4Gyroscope(uint32_t device_id, uint8_t priority = ORB_PRIO_DEFAULT, enum Rotation rotation = ROTATION_NONE); - ~PX4Gyroscope() override; - - int ioctl(cdev::file_t *filp, int cmd, unsigned long arg) override; + ~PX4Gyroscope() override = default; uint32_t get_device_id() const { return _device_id; } @@ -67,7 +63,7 @@ class PX4Gyroscope : public cdev::CDev, public ModuleParams void set_temperature(float temperature) { _temperature = temperature; } void set_update_rate(uint16_t rate); - void update(hrt_abstime timestamp_sample, float x, float y, float z); + void update(const hrt_abstime ×tamp_sample, float x, float y, float z); void print_status(); @@ -102,14 +98,10 @@ class PX4Gyroscope : public cdev::CDev, public ModuleParams Integrator _integrator{2500, true}; - matrix::Vector3f _calibration_offset{0.f, 0.f, 0.f}; - matrix::Vector3f _delta_angle_prev{0.f, 0.f, 0.f}; // delta angle from the previous IMU measurement float _vibration_metric{0.f}; // high frequency vibration level in the IMU delta angle data (rad) float _coning_vibration{0.f}; // Level of coning vibration in the IMU delta angles (rad^2) - int _class_device_instance{-1}; - uint32_t _device_id{0}; const enum Rotation _rotation; const matrix::Dcmf _rotation_dcm; diff --git a/src/lib/drivers/magnetometer/PX4Magnetometer.cpp b/src/lib/drivers/magnetometer/PX4Magnetometer.cpp index f8cd38f2d931..927fbec036a3 100644 --- a/src/lib/drivers/magnetometer/PX4Magnetometer.cpp +++ b/src/lib/drivers/magnetometer/PX4Magnetometer.cpp @@ -107,7 +107,7 @@ void PX4Magnetometer::set_device_type(uint8_t devtype) _sensor_mag_pub.get().device_id = device_id.devid; } -void PX4Magnetometer::update(hrt_abstime timestamp_sample, float x, float y, float z) +void PX4Magnetometer::update(const hrt_abstime ×tamp_sample, float x, float y, float z) { sensor_mag_s &report = _sensor_mag_pub.get(); report.timestamp = timestamp_sample; diff --git a/src/lib/drivers/magnetometer/PX4Magnetometer.hpp b/src/lib/drivers/magnetometer/PX4Magnetometer.hpp index 946315c6c5de..4f79579c382b 100644 --- a/src/lib/drivers/magnetometer/PX4Magnetometer.hpp +++ b/src/lib/drivers/magnetometer/PX4Magnetometer.hpp @@ -60,7 +60,7 @@ class PX4Magnetometer : public cdev::CDev void set_external(bool external) { _sensor_mag_pub.get().is_external = external; } void set_sensitivity(float x, float y, float z) { _sensitivity = matrix::Vector3f{x, y, z}; } - void update(hrt_abstime timestamp_sample, float x, float y, float z); + void update(const hrt_abstime ×tamp_sample, float x, float y, float z); int get_class_instance() { return _class_device_instance; }; diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp index 7bcdf36406de..bb8a98ed0aeb 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.cpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.cpp @@ -36,24 +36,13 @@ #include PX4Rangefinder::PX4Rangefinder(const uint32_t device_id, const uint8_t priority, const uint8_t device_orientation) : - CDev(nullptr), _distance_sensor_pub{ORB_ID(distance_sensor), priority} { - _class_device_instance = register_class_devname(RANGE_FINDER_BASE_DEVICE_PATH); - set_device_id(device_id); set_orientation(device_orientation); } -PX4Rangefinder::~PX4Rangefinder() -{ - if (_class_device_instance != -1) { - unregister_class_devname(RANGE_FINDER_BASE_DEVICE_PATH, _class_device_instance); - } -} - -void -PX4Rangefinder::set_device_type(uint8_t device_type) +void PX4Rangefinder::set_device_type(uint8_t device_type) { // TODO: range finders should have device ids @@ -68,18 +57,16 @@ PX4Rangefinder::set_device_type(uint8_t device_type) // _distance_sensor_pub.get().device_id = device_id.devid; } -void -PX4Rangefinder::set_orientation(const uint8_t device_orientation) +void PX4Rangefinder::set_orientation(const uint8_t device_orientation) { _distance_sensor_pub.get().orientation = device_orientation; } -void -PX4Rangefinder::update(const hrt_abstime timestamp, const float distance, const int8_t quality) +void PX4Rangefinder::update(const hrt_abstime ×tamp_sample, const float distance, const int8_t quality) { distance_sensor_s &report = _distance_sensor_pub.get(); - report.timestamp = timestamp; + report.timestamp = timestamp_sample; report.current_distance = distance; report.signal_quality = quality; @@ -93,10 +80,6 @@ PX4Rangefinder::update(const hrt_abstime timestamp, const float distance, const _distance_sensor_pub.update(); } -void -PX4Rangefinder::print_status() +void PX4Rangefinder::print_status() { - PX4_INFO(RANGE_FINDER_BASE_DEVICE_PATH " device instance: %d", _class_device_instance); - - print_message(_distance_sensor_pub.get()); } diff --git a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp index bbef35238416..a405bc75e387 100644 --- a/src/lib/drivers/rangefinder/PX4Rangefinder.hpp +++ b/src/lib/drivers/rangefinder/PX4Rangefinder.hpp @@ -35,20 +35,18 @@ #include #include -#include #include -#include #include #include -class PX4Rangefinder : public cdev::CDev +class PX4Rangefinder { public: PX4Rangefinder(const uint32_t device_id, const uint8_t priority = ORB_PRIO_DEFAULT, const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING); - ~PX4Rangefinder() override; + ~PX4Rangefinder() = default; void print_status(); @@ -66,12 +64,10 @@ class PX4Rangefinder : public cdev::CDev void set_orientation(const uint8_t device_orientation = distance_sensor_s::ROTATION_DOWNWARD_FACING); - void update(const hrt_abstime timestamp, const float distance, const int8_t quality = -1); + void update(const hrt_abstime ×tamp_sample, const float distance, const int8_t quality = -1); private: uORB::PublicationMultiData _distance_sensor_pub; - int _class_device_instance{-1}; - }; diff --git a/src/modules/commander/Commander.cpp b/src/modules/commander/Commander.cpp index 0b02cb04ef64..98c1e2f15cd0 100644 --- a/src/modules/commander/Commander.cpp +++ b/src/modules/commander/Commander.cpp @@ -3523,7 +3523,7 @@ void *commander_low_prio_loop(void *arg) } } - px4_close(cmd_sub); + orb_unsubscribe(cmd_sub); return nullptr; } diff --git a/src/modules/commander/accelerometer_calibration.cpp b/src/modules/commander/accelerometer_calibration.cpp index 579f45841940..601fc1dde218 100644 --- a/src/modules/commander/accelerometer_calibration.cpp +++ b/src/modules/commander/accelerometer_calibration.cpp @@ -138,149 +138,68 @@ #include #include #include -#include #include #include -#include -#include +#include +#include #include #include #include +#include #include #include +#include using namespace time_literals; using namespace matrix; -static const char *sensor_name = "accel"; +static constexpr char sensor_name[] {"accel"}; -static int32_t device_id[max_accel_sens]; +static constexpr unsigned MAX_ACCEL_SENS = 3; + +static int32_t device_id[MAX_ACCEL_SENS] {}; static int device_prio_max = 0; static int32_t device_id_primary = 0; calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub, - float (&accel_offs)[max_accel_sens][3], float (&accel_T)[max_accel_sens][3][3], unsigned *active_sensors); -calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[max_accel_sens], - float (&accel_avg)[max_accel_sens][detect_orientation_side_count][3], unsigned orient, unsigned samples_num); -int mat_invert3(float src[3][3], float dst[3][3]); + float (&accel_offs)[MAX_ACCEL_SENS][3], float (&accel_T)[MAX_ACCEL_SENS][3][3], unsigned *active_sensors); + +calibrate_return read_accelerometer_avg(float (&accel_avg)[MAX_ACCEL_SENS][detect_orientation_side_count][3], + unsigned orient, unsigned samples_num); + calibrate_return calculate_calibration_values(unsigned sensor, - float (&accel_ref)[max_accel_sens][detect_orientation_side_count][3], float (&accel_T)[max_accel_sens][3][3], - float (&accel_offs)[max_accel_sens][3], float g); + float (&accel_ref)[MAX_ACCEL_SENS][detect_orientation_side_count][3], float (&accel_T)[MAX_ACCEL_SENS][3][3], + float (&accel_offs)[MAX_ACCEL_SENS][3], float g); /// Data passed to calibration worker routine typedef struct { - orb_advert_t *mavlink_log_pub; - unsigned done_count; - int subs[max_accel_sens]; - float accel_ref[max_accel_sens][detect_orientation_side_count][3]; - int sensor_correction_sub; + orb_advert_t *mavlink_log_pub{nullptr}; + unsigned done_count{0}; + float accel_ref[MAX_ACCEL_SENS][detect_orientation_side_count][3] {}; } accel_worker_data_t; int do_accel_calibration(orb_advert_t *mavlink_log_pub) { -#if 1 // TODO: replace all IOCTL usage - int fd; -#endif - calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name); - struct accel_calibration_s accel_scale; - accel_scale.x_offset = 0.0f; - accel_scale.x_scale = 1.0f; - accel_scale.y_offset = 0.0f; - accel_scale.y_scale = 1.0f; - accel_scale.z_offset = 0.0f; - accel_scale.z_scale = 1.0f; - int res = PX4_OK; - char str[30]; - - /* reset all sensors */ - for (unsigned s = 0; s < max_accel_sens; s++) { -#if 1 // TODO: replace all IOCTL usage - sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, s); - /* reset all offsets to zero and all scales to one */ - fd = px4_open(str, 0); - - if (fd < 0) { - continue; - } - - device_id[s] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); - - res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); - px4_close(fd); - - if (res != PX4_OK) { - calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, s); - } - -#else - (void)sprintf(str, "CAL_ACC%u_XOFF", s); - res = param_set_no_notification(param_find(str), &accel_scale.x_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_ACC%u_YOFF", s); - res = param_set_no_notification(param_find(str), &accel_scale.y_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_ACC%u_ZOFF", s); - res = param_set_no_notification(param_find(str), &accel_scale.z_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_ACC%u_XSCALE", s); - res = param_set_no_notification(param_find(str), &accel_scale.x_scale); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_ACC%u_YSCALE", s); - res = param_set_no_notification(param_find(str), &accel_scale.y_scale); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_ACC%u_ZSCALE", s); - res = param_set_no_notification(param_find(str), &accel_scale.z_scale); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - param_notify_changes(); -#endif - } - - float accel_offs[max_accel_sens][3]; - float accel_T[max_accel_sens][3][3]; + float accel_offs[MAX_ACCEL_SENS][3] {}; + float accel_T[MAX_ACCEL_SENS][3][3] {}; unsigned active_sensors = 0; /* measure and calculate offsets & scales */ - if (res == PX4_OK) { - calibrate_return cal_return = do_accel_calibration_measurements(mavlink_log_pub, accel_offs, accel_T, &active_sensors); + calibrate_return cal_return = do_accel_calibration_measurements(mavlink_log_pub, accel_offs, accel_T, &active_sensors); - if (cal_return == calibrate_return_cancelled) { - // Cancel message already displayed, nothing left to do - return PX4_ERROR; + if (cal_return == calibrate_return_cancelled) { + // Cancel message already displayed, nothing left to do + return PX4_ERROR; - } else if (cal_return == calibrate_return_ok) { - res = PX4_OK; + } else if (cal_return == calibrate_return_ok) { + res = PX4_OK; - } else { - res = PX4_ERROR; - } + } else { + res = PX4_ERROR; } if (res != PX4_OK) { @@ -292,77 +211,70 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) } /* measurements completed successfully, rotate calibration values */ - param_t board_rotation_h = param_find("SENS_BOARD_ROT"); - int32_t board_rotation_int; - param_get(board_rotation_h, &(board_rotation_int)); - enum Rotation board_rotation_id = (enum Rotation)board_rotation_int; - Dcmf board_rotation = get_rot_matrix(board_rotation_id); - - Dcmf board_rotation_t = board_rotation.transpose(); + int32_t board_rotation_int = 0; + param_get(param_find("SENS_BOARD_ROT"), &board_rotation_int); + const Dcmf board_rotation = get_rot_matrix((enum Rotation)board_rotation_int); + const Dcmf board_rotation_t = board_rotation.transpose(); - bool tc_locked[3] = {false}; // true when the thermal parameter instance has already been adjusted by the calibrator + /* check if thermal compensation is enabled */ + int32_t tc_enabled_int = 0; + param_get(param_find("TC_A_ENABLE"), &tc_enabled_int); - for (unsigned uorb_index = 0; uorb_index < active_sensors; uorb_index++) { + for (unsigned uorb_index = 0; uorb_index < MAX_ACCEL_SENS; uorb_index++) { - /* handle individual sensors, one by one */ - Vector3f accel_offs_vec(accel_offs[uorb_index]); - Vector3f accel_offs_rotated = board_rotation_t *accel_offs_vec; - Matrix3f accel_T_mat(accel_T[uorb_index]); - Matrix3f accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation; + float x_offset = 0.f; + float y_offset = 0.f; + float z_offset = 0.f; - accel_scale.x_offset = accel_offs_rotated(0); - accel_scale.x_scale = accel_T_rotated(0, 0); - accel_scale.y_offset = accel_offs_rotated(1); - accel_scale.y_scale = accel_T_rotated(1, 1); - accel_scale.z_offset = accel_offs_rotated(2); - accel_scale.z_scale = accel_T_rotated(2, 2); + float x_scale = 1.f; + float y_scale = 1.f; + float z_scale = 1.f; bool failed = false; - failed = failed || (PX4_OK != param_set_no_notification(param_find("CAL_ACC_PRIME"), &(device_id_primary))); + if (uorb_index < active_sensors) { + failed = failed || (PX4_OK != param_set_no_notification(param_find("CAL_ACC_PRIME"), &device_id_primary)); + /* handle individual sensors, one by one */ + const Vector3f accel_offs_vec(accel_offs[uorb_index]); + const Vector3f accel_offs_rotated = board_rotation_t *accel_offs_vec; + const Matrix3f accel_T_mat(accel_T[uorb_index]); + const Matrix3f accel_T_rotated = board_rotation_t *accel_T_mat * board_rotation; - PX4_INFO("found offset %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, - (double)accel_scale.x_offset, - (double)accel_scale.y_offset, - (double)accel_scale.z_offset); - PX4_INFO("found scale %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, - (double)accel_scale.x_scale, - (double)accel_scale.y_scale, - (double)accel_scale.z_scale); + x_offset = accel_offs_rotated(0); + y_offset = accel_offs_rotated(1); + z_offset = accel_offs_rotated(2); - /* check if thermal compensation is enabled */ - int32_t tc_enabled_int; - param_get(param_find("TC_A_ENABLE"), &(tc_enabled_int)); + x_scale = accel_T_rotated(0, 0); + y_scale = accel_T_rotated(1, 1); + z_scale = accel_T_rotated(2, 2); - if (tc_enabled_int == 1) { - /* Get struct containing sensor thermal compensation data */ - sensor_correction_s sensor_correction{}; /**< sensor thermal corrections */ - uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)}; - sensor_correction_sub.copy(&sensor_correction); + PX4_INFO("found offset %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, (double)x_offset, (double)y_offset, + (double)z_offset); + PX4_INFO("found scale %d: x: %.6f, y: %.6f, z: %.6f", uorb_index, (double)x_scale, (double)y_scale, (double)z_scale); - /* don't allow a parameter instance to be calibrated more than once by another uORB instance */ - if (!tc_locked[sensor_correction.accel_mapping[uorb_index]]) { - tc_locked[sensor_correction.accel_mapping[uorb_index]] = true; + if (tc_enabled_int == 1) { + /* Get struct containing sensor thermal compensation data */ + sensor_correction_s sensor_correction{}; /**< sensor thermal corrections */ + uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)}; + sensor_correction_sub.copy(&sensor_correction); /* update the _X0_ terms to include the additional offset */ - int32_t handle; - float val; - for (unsigned axis_index = 0; axis_index < 3; axis_index++) { - val = 0.0f; - (void)sprintf(str, "TC_A%u_X0_%u", sensor_correction.accel_mapping[uorb_index], axis_index); - handle = param_find(str); + char str[30] {}; + sprintf(str, "TC_A%u_X0_%u", sensor_correction.accel_mapping[uorb_index], axis_index); + param_t handle = param_find(str); + float val = 0.0f; param_get(handle, &val); if (axis_index == 0) { - val += accel_scale.x_offset; + val += x_offset; } else if (axis_index == 1) { - val += accel_scale.y_offset; + val += y_offset; } else if (axis_index == 2) { - val += accel_scale.z_offset; + val += z_offset; } failed |= (PX4_OK != param_set_no_notification(handle, &val)); @@ -370,76 +282,73 @@ int do_accel_calibration(orb_advert_t *mavlink_log_pub) /* update the _SCL_ terms to include the scale factor */ for (unsigned axis_index = 0; axis_index < 3; axis_index++) { - val = 1.0f; - (void)sprintf(str, "TC_A%u_SCL_%u", sensor_correction.accel_mapping[uorb_index], axis_index); - handle = param_find(str); + char str[30] {}; + sprintf(str, "TC_A%u_SCL_%u", sensor_correction.accel_mapping[uorb_index], axis_index); + param_t handle = param_find(str); + + float val = 1.0f; if (axis_index == 0) { - val = accel_scale.x_scale; + val = x_scale; } else if (axis_index == 1) { - val = accel_scale.y_scale; + val = y_scale; } else if (axis_index == 2) { - val = accel_scale.z_scale; + val = z_scale; } failed |= (PX4_OK != param_set_no_notification(handle, &val)); } - param_notify_changes(); + // Ensure the calibration values used by the driver are at default settings when we are using thermal calibration data + x_offset = 0.f; + y_offset = 0.f; + z_offset = 0.f; + x_scale = 1.f; + y_scale = 1.f; + z_scale = 1.f; } - - // Ensure the calibration values used by the driver are at default settings when we are using thermal calibration data - accel_scale.x_offset = 0.f; - accel_scale.y_offset = 0.f; - accel_scale.z_offset = 0.f; - accel_scale.x_scale = 1.f; - accel_scale.y_scale = 1.f; - accel_scale.z_scale = 1.f; } - // save the driver level calibration data + char str[30] {}; + + + // calibration offsets (void)sprintf(str, "CAL_ACC%u_XOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.x_offset))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &x_offset)); + (void)sprintf(str, "CAL_ACC%u_YOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.y_offset))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &y_offset)); + (void)sprintf(str, "CAL_ACC%u_ZOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.z_offset))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &z_offset)); + + + // calibration scale (void)sprintf(str, "CAL_ACC%u_XSCALE", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.x_scale))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &x_scale)); + (void)sprintf(str, "CAL_ACC%u_YSCALE", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.y_scale))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &y_scale)); + (void)sprintf(str, "CAL_ACC%u_ZSCALE", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(accel_scale.z_scale))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &z_scale)); + + + // calibration device ID (void)sprintf(str, "CAL_ACC%u_ID", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(device_id[uorb_index]))); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &device_id[uorb_index])); + if (failed) { calibration_log_critical(mavlink_log_pub, CAL_ERROR_SET_PARAMS_MSG); return PX4_ERROR; } - -#if 1 // TODO: replace all IOCTL usage - sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, uorb_index); - fd = px4_open(str, 0); - - if (fd < 0) { - calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "sensor does not exist"); - res = PX4_ERROR; - - } else { - res = px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&accel_scale); - px4_close(fd); - } - - if (res != PX4_OK) { - calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG); - } - -#endif } + param_notify_changes(); + if (res == PX4_OK) { /* if there is a any preflight-check system response, let the barrage of messages through */ px4_usleep(200000); @@ -464,8 +373,7 @@ static calibrate_return accel_calibration_worker(detect_orientation_return orien calibration_log_info(worker_data->mavlink_log_pub, "[cal] Hold still, measuring %s side", detect_orientation_str(orientation)); - read_accelerometer_avg(worker_data->sensor_correction_sub, worker_data->subs, worker_data->accel_ref, orientation, - samples_num); + read_accelerometer_avg(worker_data->accel_ref, orientation, samples_num); calibration_log_info(worker_data->mavlink_log_pub, "[cal] %s side result: [%8.4f %8.4f %8.4f]", detect_orientation_str(orientation), @@ -480,84 +388,35 @@ static calibrate_return accel_calibration_worker(detect_orientation_return orien } calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub, - float (&accel_offs)[max_accel_sens][3], float (&accel_T)[max_accel_sens][3][3], unsigned *active_sensors) + float (&accel_offs)[MAX_ACCEL_SENS][3], float (&accel_T)[MAX_ACCEL_SENS][3][3], unsigned *active_sensors) { calibrate_return result = calibrate_return_ok; *active_sensors = 0; - accel_worker_data_t worker_data; - + accel_worker_data_t worker_data{}; worker_data.mavlink_log_pub = mavlink_log_pub; - worker_data.done_count = 0; - - bool data_collected[detect_orientation_side_count] = { false, false, false, false, false, false }; - - // Initialise sub to sensor thermal compensation data - worker_data.sensor_correction_sub = orb_subscribe(ORB_ID(sensor_correction)); - - // Initialize subs to error condition so we know which ones are open and which are not - for (size_t i = 0; i < max_accel_sens; i++) { - worker_data.subs[i] = -1; - } - uint64_t timestamps[max_accel_sens] = {}; + bool data_collected[detect_orientation_side_count] {}; // We should not try to subscribe if the topic doesn't actually exist and can be counted. const unsigned orb_accel_count = orb_group_count(ORB_ID(sensor_accel)); // Warn that we will not calibrate more than max_accels accelerometers - if (orb_accel_count > max_accel_sens) { + if (orb_accel_count > MAX_ACCEL_SENS) { calibration_log_critical(mavlink_log_pub, "Detected %u accels, but will calibrate only %u", orb_accel_count, - max_accel_sens); + MAX_ACCEL_SENS); } - for (unsigned cur_accel = 0; cur_accel < orb_accel_count && cur_accel < max_accel_sens; cur_accel++) { - - // Lock in to correct ORB instance - bool found_cur_accel = false; - - for (unsigned i = 0; i < orb_accel_count && !found_cur_accel; i++) { - worker_data.subs[cur_accel] = orb_subscribe_multi(ORB_ID(sensor_accel), i); - - sensor_accel_s report = {}; - orb_copy(ORB_ID(sensor_accel), worker_data.subs[cur_accel], &report); - -#if 1 // TODO: replace all IOCTL usage - - // For NuttX, we get the UNIQUE device ID from the sensor driver via an IOCTL - // and match it up with the one from the uORB subscription, because the - // instance ordering of uORB and the order of the FDs may not be the same. - - if (report.device_id == (uint32_t)device_id[cur_accel]) { - // Device IDs match, correct ORB instance for this accel - found_cur_accel = true; - // store initial timestamp - used to infer which sensors are active - timestamps[cur_accel] = report.timestamp; + for (uint8_t cur_accel = 0; cur_accel < orb_accel_count && cur_accel < MAX_ACCEL_SENS; cur_accel++) { - } else { - orb_unsubscribe(worker_data.subs[cur_accel]); - } - -#else + uORB::SubscriptionData accel_sub{ORB_ID(sensor_accel), cur_accel}; - // For the DriverFramework drivers, we fill device ID (this is the first time) by copying one report. - device_id[cur_accel] = report.device_id; - found_cur_accel = true; - -#endif - } - - if (!found_cur_accel) { - calibration_log_critical(mavlink_log_pub, "Accel #%u (ID %u) no matching uORB devid", cur_accel, device_id[cur_accel]); - result = calibrate_return_error; - break; - } + device_id[cur_accel] = accel_sub.get().device_id; if (device_id[cur_accel] != 0) { // Get priority - int32_t prio; - orb_priority(worker_data.subs[cur_accel], &prio); + int32_t prio = accel_sub.get_priority(); if (prio > device_prio_max) { device_prio_max = prio; @@ -574,27 +433,11 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub if (result == calibrate_return_ok) { int cancel_sub = calibrate_cancel_subscribe(); result = calibrate_from_orientation(mavlink_log_pub, cancel_sub, data_collected, accel_calibration_worker, &worker_data, - false /* normal still */); - calibrate_cancel_unsubscribe(cancel_sub); - } - - /* close all subscriptions */ - for (unsigned i = 0; i < max_accel_sens; i++) { - if (worker_data.subs[i] >= 0) { - /* figure out which sensors were active */ - sensor_accel_s arp = {}; - (void)orb_copy(ORB_ID(sensor_accel), worker_data.subs[i], &arp); + false); - if (arp.timestamp != 0 && timestamps[i] != arp.timestamp) { - (*active_sensors)++; - } - - px4_close(worker_data.subs[i]); - } + calibrate_cancel_unsubscribe(cancel_sub); } - orb_unsubscribe(worker_data.sensor_correction_sub); - if (result == calibrate_return_ok) { /* calculate offsets and transform matrix */ for (unsigned i = 0; i < (*active_sensors); i++) { @@ -613,47 +456,35 @@ calibrate_return do_accel_calibration_measurements(orb_advert_t *mavlink_log_pub /* * Read specified number of accelerometer samples, calculate average and dispersion. */ -calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[max_accel_sens], - float (&accel_avg)[max_accel_sens][detect_orientation_side_count][3], unsigned orient, unsigned samples_num) +calibrate_return read_accelerometer_avg(float (&accel_avg)[MAX_ACCEL_SENS][detect_orientation_side_count][3], + unsigned orient, unsigned samples_num) { /* get total sensor board rotation matrix */ - param_t board_rotation_h = param_find("SENS_BOARD_ROT"); - param_t board_offset_x = param_find("SENS_BOARD_X_OFF"); - param_t board_offset_y = param_find("SENS_BOARD_Y_OFF"); - param_t board_offset_z = param_find("SENS_BOARD_Z_OFF"); + float board_offset[3] {}; + param_get(param_find("SENS_BOARD_X_OFF"), &board_offset[0]); + param_get(param_find("SENS_BOARD_Y_OFF"), &board_offset[1]); + param_get(param_find("SENS_BOARD_Z_OFF"), &board_offset[2]); - float board_offset[3]; - param_get(board_offset_x, &board_offset[0]); - param_get(board_offset_y, &board_offset[1]); - param_get(board_offset_z, &board_offset[2]); + const Dcmf board_rotation_offset{Eulerf{math::radians(board_offset[0]), math::radians(board_offset[1]), math::radians(board_offset[2])}}; - Dcmf board_rotation_offset = Eulerf( - M_DEG_TO_RAD_F * board_offset[0], - M_DEG_TO_RAD_F * board_offset[1], - M_DEG_TO_RAD_F * board_offset[2]); + int32_t board_rotation_int = 0; + param_get(param_find("SENS_BOARD_ROT"), &board_rotation_int); - int32_t board_rotation_int; - param_get(board_rotation_h, &(board_rotation_int)); + const Dcmf board_rotation = board_rotation_offset * get_rot_matrix((enum Rotation)board_rotation_int); - Dcmf board_rotation = board_rotation_offset * get_rot_matrix((enum Rotation)board_rotation_int); - - px4_pollfd_struct_t fds[max_accel_sens]; - - for (unsigned i = 0; i < max_accel_sens; i++) { - fds[i].fd = subs[i]; - fds[i].events = POLLIN; - } - - unsigned counts[max_accel_sens] = { 0 }; - float accel_sum[max_accel_sens][3] {}; + unsigned counts[MAX_ACCEL_SENS] {}; + float accel_sum[MAX_ACCEL_SENS][3] {}; unsigned errcount = 0; - struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */ + + // sensor thermal corrections + uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)}; + sensor_correction_s sensor_correction{}; /* try to get latest thermal corrections */ - if (orb_copy(ORB_ID(sensor_correction), sensor_correction_sub, &sensor_correction) != 0) { + if (!sensor_correction_sub.copy(&sensor_correction)) { /* use default values */ - memset(&sensor_correction, 0, sizeof(sensor_correction)); + sensor_correction = sensor_correction_s{}; for (unsigned i = 0; i < 3; i++) { sensor_correction.accel_scale_0[i] = 1.0f; @@ -662,20 +493,20 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m } } + uORB::SubscriptionBlocking accel_sub[MAX_ACCEL_SENS] { + {ORB_ID(sensor_accel), 0, 0}, + {ORB_ID(sensor_accel), 0, 1}, + {ORB_ID(sensor_accel), 0, 2}, + }; + /* use the first sensor to pace the readout, but do per-sensor counts */ while (counts[0] < samples_num) { - int poll_ret = px4_poll(&fds[0], max_accel_sens, 1000); - - if (poll_ret > 0) { + if (accel_sub[0].updatedBlocking(100)) { + for (unsigned s = 0; s < MAX_ACCEL_SENS; s++) { - for (unsigned s = 0; s < max_accel_sens; s++) { - bool changed; - orb_check(subs[s], &changed); + sensor_accel_s arp; - if (changed) { - - sensor_accel_s arp; - orb_copy(ORB_ID(sensor_accel), subs[s], &arp); + if (accel_sub[s].update(&arp)) { // Apply thermal offset corrections in sensor/board frame if (s == 0) { @@ -714,7 +545,7 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m } // rotate sensor measurements from sensor to body frame using board rotation matrix - for (unsigned i = 0; i < max_accel_sens; i++) { + for (unsigned i = 0; i < MAX_ACCEL_SENS; i++) { Vector3f accel_sum_vec(&accel_sum[i][0]); accel_sum_vec = board_rotation * accel_sum_vec; @@ -723,7 +554,7 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m } } - for (unsigned s = 0; s < max_accel_sens; s++) { + for (unsigned s = 0; s < MAX_ACCEL_SENS; s++) { for (unsigned i = 0; i < 3; i++) { accel_avg[s][orient][i] = accel_sum[s][i] / counts[s]; } @@ -732,7 +563,7 @@ calibrate_return read_accelerometer_avg(int sensor_correction_sub, int (&subs)[m return calibrate_return_ok; } -int mat_invert3(float src[3][3], float dst[3][3]) +static int mat_invert3(float src[3][3], float dst[3][3]) { float det = src[0][0] * (src[1][1] * src[2][2] - src[1][2] * src[2][1]) - src[0][1] * (src[1][0] * src[2][2] - src[1][2] * src[2][0]) + @@ -756,8 +587,8 @@ int mat_invert3(float src[3][3], float dst[3][3]) } calibrate_return calculate_calibration_values(unsigned sensor, - float (&accel_ref)[max_accel_sens][detect_orientation_side_count][3], float (&accel_T)[max_accel_sens][3][3], - float (&accel_offs)[max_accel_sens][3], float g) + float (&accel_ref)[MAX_ACCEL_SENS][detect_orientation_side_count][3], float (&accel_T)[MAX_ACCEL_SENS][3][3], + float (&accel_offs)[MAX_ACCEL_SENS][3], float g) { /* calculate offsets */ for (unsigned i = 0; i < 3; i++) { @@ -765,8 +596,7 @@ calibrate_return calculate_calibration_values(unsigned sensor, } /* fill matrix A for linear equations system*/ - float mat_A[3][3]; - memset(mat_A, 0, sizeof(mat_A)); + float mat_A[3][3] {}; for (unsigned i = 0; i < 3; i++) { for (unsigned j = 0; j < 3; j++) { @@ -776,7 +606,7 @@ calibrate_return calculate_calibration_values(unsigned sensor, } /* calculate inverse matrix for A */ - float mat_A_inv[3][3]; + float mat_A_inv[3][3] {}; if (mat_invert3(mat_A, mat_A_inv) != PX4_OK) { return calibrate_return_error; @@ -796,38 +626,31 @@ calibrate_return calculate_calibration_values(unsigned sensor, int do_level_calibration(orb_advert_t *mavlink_log_pub) { bool success = false; - int att_sub = orb_subscribe(ORB_ID(vehicle_attitude)); - vehicle_attitude_s att{}; calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, "level"); param_t roll_offset_handle = param_find("SENS_BOARD_X_OFF"); param_t pitch_offset_handle = param_find("SENS_BOARD_Y_OFF"); - param_t board_rot_handle = param_find("SENS_BOARD_ROT"); // get old values - float roll_offset_current; - float pitch_offset_current; - int32_t board_rot_current = 0; + float roll_offset_current = 0.f; + float pitch_offset_current = 0.f; param_get(roll_offset_handle, &roll_offset_current); param_get(pitch_offset_handle, &pitch_offset_current); - param_get(board_rot_handle, &board_rot_current); - Dcmf board_rotation_offset = Eulerf( - math::radians(roll_offset_current), - math::radians(pitch_offset_current), - 0.f); + int32_t board_rot_current = 0; + param_get(param_find("SENS_BOARD_ROT"), &board_rot_current); - px4_pollfd_struct_t fds[1]; - fds[0].fd = att_sub; - fds[0].events = POLLIN; + const Dcmf board_rotation_offset{Eulerf{math::radians(roll_offset_current), math::radians(pitch_offset_current), 0.f}}; - float roll_mean = 0.0f; - float pitch_mean = 0.0f; + float roll_mean = 0.f; + float pitch_mean = 0.f; unsigned counter = 0; bool had_motion = true; int num_retries = 0; + uORB::SubscriptionBlocking att_sub{ORB_ID(vehicle_attitude)}; + while (had_motion && num_retries++ < 50) { Vector2f min_angles{100.f, 100.f}; Vector2f max_angles{-100.f, -100.f}; @@ -839,9 +662,10 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub) const hrt_abstime start = hrt_absolute_time(); while (hrt_elapsed_time(&start) < calibration_duration) { - int pollret = px4_poll(&fds[0], (sizeof(fds) / sizeof(fds[0])), 100); - if (pollret <= 0) { + vehicle_attitude_s att{}; + + if (!att_sub.updateBlocking(att)) { // attitude estimator is not running calibration_log_critical(mavlink_log_pub, "attitude estimator not running - check system boot"); calibration_log_critical(mavlink_log_pub, CAL_QGC_FAILED_MSG, "level"); @@ -855,18 +679,14 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub) last_progress_report = progress; } - orb_copy(ORB_ID(vehicle_attitude), att_sub, &att); - Eulerf att_euler = Quatf(att.q); + Eulerf att_euler{Quatf{att.q}}; // keep min + max angles - for (int i = 0; i < 2; ++i) { - if (att_euler(i) < min_angles(i)) { min_angles(i) = att_euler(i); } - - if (att_euler(i) > max_angles(i)) { max_angles(i) = att_euler(i); } - } - + att_euler(0) = math::constrain(att_euler(0), min_angles(0), max_angles(0)); + att_euler(1) = math::constrain(att_euler(1), min_angles(1), max_angles(1)); att_euler(2) = 0.f; // ignore yaw - att_euler = Eulerf(board_rotation_offset * Dcmf(att_euler)); // subtract existing board rotation + + att_euler = Eulerf{board_rotation_offset *Dcmf{att_euler}}; // subtract existing board rotation roll_mean += att_euler.phi(); pitch_mean += att_euler.theta(); ++counter; @@ -876,6 +696,7 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub) // The difference is typically <0.1 deg while at rest if (max_angles(0) - min_angles(0) < math::radians(0.5f) && max_angles(1) - min_angles(1) < math::radians(0.5f)) { + had_motion = false; } } @@ -895,8 +716,8 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub) calibration_log_critical(mavlink_log_pub, "excess pitch angle"); } else { - roll_mean *= (float)M_RAD_TO_DEG; - pitch_mean *= (float)M_RAD_TO_DEG; + roll_mean = math::degrees(roll_mean); + pitch_mean = math::degrees(pitch_mean); param_set_no_notification(roll_offset_handle, &roll_mean); param_set_no_notification(pitch_offset_handle, &pitch_mean); param_notify_changes(); @@ -905,8 +726,6 @@ int do_level_calibration(orb_advert_t *mavlink_log_pub) out: - orb_unsubscribe(att_sub); - if (success) { calibration_log_info(mavlink_log_pub, CAL_QGC_DONE_MSG, "level"); return 0; diff --git a/src/modules/commander/calibration_routines.cpp b/src/modules/commander/calibration_routines.cpp index 429bdce152cb..0231c7962695 100644 --- a/src/modules/commander/calibration_routines.cpp +++ b/src/modules/commander/calibration_routines.cpp @@ -793,7 +793,7 @@ calibrate_return calibrate_from_orientation(orb_advert_t *mavlink_log_pub, } if (sub_accel >= 0) { - px4_close(sub_accel); + orb_unsubscribe(sub_accel); } return result; diff --git a/src/modules/commander/calibration_routines.h b/src/modules/commander/calibration_routines.h index ff94941eeb47..dd84d8703a0c 100644 --- a/src/modules/commander/calibration_routines.h +++ b/src/modules/commander/calibration_routines.h @@ -72,9 +72,6 @@ int run_lm_ellipsoid_fit(const float x[], const float y[], const float z[], floa bool inverse4x4(float m[], float invOut[]); bool mat_inverse(float *A, float *inv, uint8_t n); -// FIXME: Change the name -static const unsigned max_accel_sens = 3; - // The order of these cannot change since the calibration calculations depend on them in this order enum detect_orientation_return { DETECT_ORIENTATION_TAIL_DOWN, diff --git a/src/modules/commander/gyro_calibration.cpp b/src/modules/commander/gyro_calibration.cpp index 044ba15211c5..76e6d4482458 100644 --- a/src/modules/commander/gyro_calibration.cpp +++ b/src/modules/commander/gyro_calibration.cpp @@ -46,45 +46,46 @@ #include #include #include -#include -#include -#include -#include + #include -#include + #include +#include +#include #include #include -#include +#include #include -#include +#include #include -static const char *sensor_name = "gyro"; +static constexpr char sensor_name[] {"gyro"}; +static constexpr unsigned MAX_GYROS = 3; -static constexpr unsigned max_gyros = 3; +struct gyro_calibration_s { + float x_offset{0.f}; + float y_offset{0.f}; + float z_offset{0.f}; +}; /// Data passed to calibration worker routine -typedef struct { - orb_advert_t *mavlink_log_pub; - int32_t device_id[max_gyros]; - int gyro_sensor_sub[max_gyros]; - int sensor_correction_sub; - struct gyro_calibration_s gyro_scale[max_gyros]; - float last_sample_0[3]; -} gyro_worker_data_t; - -static calibrate_return gyro_calibration_worker(int cancel_sub, void *data) +struct gyro_worker_data_t { + orb_advert_t *mavlink_log_pub{nullptr}; + int32_t device_id[MAX_GYROS] {}; + gyro_calibration_s gyro_scale[MAX_GYROS] {}; + float last_sample_0[3] {}; +}; + +static calibrate_return gyro_calibration_worker(int cancel_sub, gyro_worker_data_t *worker_data) { - gyro_worker_data_t *worker_data = (gyro_worker_data_t *)(data); - unsigned calibration_counter[max_gyros] = { 0 }, slow_count = 0; - const unsigned calibration_count = 250; - sensor_gyro_s gyro_report; - unsigned poll_errcount = 0; + unsigned calibration_counter[MAX_GYROS] {}; + static constexpr unsigned calibration_count = 250; + unsigned poll_errcount = 0; - struct sensor_correction_s sensor_correction {}; /**< sensor thermal corrections */ + uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)}; + sensor_correction_s sensor_correction{}; /**< sensor thermal corrections */ - if (orb_copy(ORB_ID(sensor_correction), worker_data->sensor_correction_sub, &sensor_correction) != 0) { + if (!sensor_correction_sub.copy(&sensor_correction)) { for (unsigned i = 0; i < 3; i++) { sensor_correction.gyro_scale_0[i] = 1.0f; sensor_correction.gyro_scale_1[i] = 1.0f; @@ -92,46 +93,39 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void *data) } } - px4_pollfd_struct_t fds[max_gyros]; - - for (unsigned s = 0; s < max_gyros; s++) { - fds[s].fd = worker_data->gyro_sensor_sub[s]; - fds[s].events = POLLIN; - } + uORB::SubscriptionBlocking gyro_sub[MAX_GYROS] { + {ORB_ID(sensor_gyro), 0, 0}, + {ORB_ID(sensor_gyro), 0, 1}, + {ORB_ID(sensor_gyro), 0, 2}, + }; memset(&worker_data->last_sample_0, 0, sizeof(worker_data->last_sample_0)); /* use slowest gyro to pace, but count correctly per-gyro for statistics */ + unsigned slow_count = 0; + while (slow_count < calibration_count) { if (calibrate_cancel_check(worker_data->mavlink_log_pub, cancel_sub)) { return calibrate_return_cancelled; } /* check if there are new thermal corrections */ - bool updated; - orb_check(worker_data->sensor_correction_sub, &updated); + sensor_correction_sub.update(&sensor_correction); - if (updated) { - orb_copy(ORB_ID(sensor_correction), worker_data->sensor_correction_sub, &sensor_correction); - } - - int poll_ret = px4_poll(&fds[0], max_gyros, 1000); - - if (poll_ret > 0) { + if (gyro_sub[0].updatedBlocking(1000)) { unsigned update_count = calibration_count; - for (unsigned s = 0; s < max_gyros; s++) { + for (unsigned s = 0; s < MAX_GYROS; s++) { if (calibration_counter[s] >= calibration_count) { // Skip if instance has enough samples continue; } - bool changed; - orb_check(worker_data->gyro_sensor_sub[s], &changed); + sensor_gyro_s gyro_report; + + if (gyro_sub[s].update(&gyro_report)) { - if (changed) { - orb_copy(ORB_ID(sensor_gyro), worker_data->gyro_sensor_sub[s], &gyro_report); - float sample[3]; + float sample[3] {}; if (s == 0) { // take a working copy @@ -157,21 +151,19 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void *data) sample[0] = gyro_report.x; sample[1] = gyro_report.y; sample[2] = gyro_report.z; - } worker_data->gyro_scale[s].x_offset += sample[0]; worker_data->gyro_scale[s].y_offset += sample[1]; worker_data->gyro_scale[s].z_offset += sample[2]; - calibration_counter[s]++; + calibration_counter[s]++; } // Maintain the sample count of the slowest sensor if (calibration_counter[s] && calibration_counter[s] < update_count) { update_count = calibration_counter[s]; } - } if (update_count % (calibration_count / 20) == 0) { @@ -193,7 +185,7 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void *data) } } - for (unsigned s = 0; s < max_gyros; s++) { + for (unsigned s = 0; s < MAX_GYROS; s++) { if (worker_data->device_id[s] != 0 && calibration_counter[s] < calibration_count / 2) { calibration_log_critical(worker_data->mavlink_log_pub, "ERROR: missing data, sensor %d", s) return calibrate_return_error; @@ -209,131 +201,35 @@ static calibrate_return gyro_calibration_worker(int cancel_sub, void *data) int do_gyro_calibration(orb_advert_t *mavlink_log_pub) { - int res = PX4_OK; - gyro_worker_data_t worker_data = {}; + int res = PX4_OK; + gyro_worker_data_t worker_data{}; calibration_log_info(mavlink_log_pub, CAL_QGC_STARTED_MSG, sensor_name); worker_data.mavlink_log_pub = mavlink_log_pub; - gyro_calibration_s gyro_scale_zero{}; int device_prio_max = 0; int32_t device_id_primary = 0; - worker_data.sensor_correction_sub = orb_subscribe(ORB_ID(sensor_correction)); - - for (unsigned s = 0; s < max_gyros; s++) { - char str[30]; - - // Reset gyro ids to unavailable. - worker_data.device_id[s] = 0; - // And set default subscriber values. - worker_data.gyro_sensor_sub[s] = -1; - (void)sprintf(str, "CAL_GYRO%u_ID", s); - res = param_set_no_notification(param_find(str), &(worker_data.device_id[s])); - - if (res != PX4_OK) { - calibration_log_critical(mavlink_log_pub, "Unable to reset CAL_GYRO%u_ID", s); - return PX4_ERROR; - } - - // Reset all offsets to 0 - (void)memcpy(&worker_data.gyro_scale[s], &gyro_scale_zero, sizeof(gyro_scale_zero)); -#if 1 // TODO: replace all IOCTL usage - sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, s); - int fd = px4_open(str, 0); - - if (fd >= 0) { - worker_data.device_id[s] = px4_ioctl(fd, DEVIOCGDEVICEID, 0); - res = px4_ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gyro_scale_zero); - px4_close(fd); - - if (res != PX4_OK) { - calibration_log_critical(mavlink_log_pub, CAL_ERROR_RESET_CAL_MSG, s); - return PX4_ERROR; - } - } - -#else - (void)sprintf(str, "CAL_GYRO%u_XOFF", s); - res = param_set_no_notification(param_find(str), &gyro_scale_zero.x_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_GYRO%u_YOFF", s); - res = param_set_no_notification(param_find(str), &gyro_scale_zero.y_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - (void)sprintf(str, "CAL_GYRO%u_ZOFF", s); - res = param_set_no_notification(param_find(str), &gyro_scale_zero.z_offset); - - if (res != PX4_OK) { - PX4_ERR("unable to reset %s", str); - } - - param_notify_changes(); -#endif - - } - // 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)); - // Warn that we will not calibrate more than max_gyros gyroscopes - if (orb_gyro_count > max_gyros) { - calibration_log_critical(mavlink_log_pub, "Detected %u gyros, but will calibrate only %u", orb_gyro_count, max_gyros); + // Warn that we will not calibrate more than MAX_GYROS gyroscopes + if (orb_gyro_count > MAX_GYROS) { + calibration_log_critical(mavlink_log_pub, "Detected %u gyros, but will calibrate only %u", orb_gyro_count, MAX_GYROS); } - for (unsigned cur_gyro = 0; cur_gyro < orb_gyro_count && cur_gyro < max_gyros; cur_gyro++) { - - // Lock in to correct ORB instance - bool found_cur_gyro = false; - - for (unsigned i = 0; i < orb_gyro_count && !found_cur_gyro; i++) { - worker_data.gyro_sensor_sub[cur_gyro] = orb_subscribe_multi(ORB_ID(sensor_gyro), i); - - sensor_gyro_s report{}; - orb_copy(ORB_ID(sensor_gyro), worker_data.gyro_sensor_sub[cur_gyro], &report); - -#if 1 // TODO: replace all IOCTL usage + for (uint8_t cur_gyro = 0; cur_gyro < orb_gyro_count && cur_gyro < MAX_GYROS; cur_gyro++) { - // For NuttX, we get the UNIQUE device ID from the sensor driver via an IOCTL - // and match it up with the one from the uORB subscription, because the - // instance ordering of uORB and the order of the FDs may not be the same. - - if (report.device_id == (uint32_t)worker_data.device_id[cur_gyro]) { - // Device IDs match, correct ORB instance for this gyro - found_cur_gyro = true; - - } else { - orb_unsubscribe(worker_data.gyro_sensor_sub[cur_gyro]); - } + uORB::Subscription gyro_sensor_sub{ORB_ID(sensor_gyro), cur_gyro}; + sensor_gyro_s report{}; + gyro_sensor_sub.copy(&report); -#else - - // For the DriverFramework drivers, we fill device ID (this is the first time) by copying one report. - worker_data.device_id[cur_gyro] = report.device_id; - found_cur_gyro = true; - -#endif - } - - if (!found_cur_gyro) { - calibration_log_critical(mavlink_log_pub, "Gyro #%u (ID %u) no matching uORB devid", cur_gyro, - worker_data.device_id[cur_gyro]); - res = calibrate_return_error; - break; - } + worker_data.device_id[cur_gyro] = report.device_id; if (worker_data.device_id[cur_gyro] != 0) { // Get priority - int32_t prio; - orb_priority(worker_data.gyro_sensor_sub[cur_gyro], &prio); + int32_t prio = gyro_sensor_sub.get_priority(); if (prio > device_prio_max) { device_prio_max = prio; @@ -345,7 +241,7 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) } } - int cancel_sub = calibrate_cancel_subscribe(); + int cancel_sub = calibrate_cancel_subscribe(); unsigned try_count = 0; unsigned max_tries = 20; @@ -398,99 +294,63 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) calibrate_cancel_unsubscribe(cancel_sub); - for (unsigned s = 0; s < max_gyros; s++) { - px4_close(worker_data.gyro_sensor_sub[s]); - } - if (res == PX4_OK) { /* set offset parameters to new values */ - bool failed = false; + bool failed = (PX4_OK != param_set_no_notification(param_find("CAL_GYRO_PRIME"), &device_id_primary)); - failed = failed || (PX4_OK != param_set_no_notification(param_find("CAL_GYRO_PRIME"), &(device_id_primary))); + /* check if thermal compensation is enabled */ + int32_t tc_enabled_int = 0; + param_get(param_find("TC_G_ENABLE"), &tc_enabled_int); - bool tc_locked[3] = {false}; // true when the thermal parameter instance has already been adjusted by the calibrator + for (unsigned uorb_index = 0; uorb_index < MAX_GYROS; uorb_index++) { + if (tc_enabled_int == 1) { + /* Get struct containing sensor thermal compensation data */ + uORB::Subscription sensor_correction_sub{ORB_ID(sensor_correction)}; + sensor_correction_s sensor_correction{}; + sensor_correction_sub.copy(&sensor_correction); - for (unsigned uorb_index = 0; uorb_index < max_gyros; uorb_index++) { - if (worker_data.device_id[uorb_index] != 0) { - char str[30]; + /* update the _X0_ terms to include the additional offset */ + for (unsigned axis_index = 0; axis_index < 3; axis_index++) { - /* check if thermal compensation is enabled */ - int32_t tc_enabled_int; - param_get(param_find("TC_G_ENABLE"), &(tc_enabled_int)); + char str[30] {}; + sprintf(str, "TC_G%u_X0_%u", sensor_correction.gyro_mapping[uorb_index], axis_index); + param_t handle = param_find(str); + float val = 0.0f; + param_get(handle, &val); - if (tc_enabled_int == 1) { - /* Get struct containing sensor thermal compensation data */ - struct sensor_correction_s sensor_correction; /**< sensor thermal corrections */ - memset(&sensor_correction, 0, sizeof(sensor_correction)); - orb_copy(ORB_ID(sensor_correction), worker_data.sensor_correction_sub, &sensor_correction); + if (axis_index == 0) { + val += worker_data.gyro_scale[uorb_index].x_offset; - /* don't allow a parameter instance to be calibrated again by another uORB instance */ - if (!tc_locked[sensor_correction.gyro_mapping[uorb_index]]) { - tc_locked[sensor_correction.gyro_mapping[uorb_index]] = true; + } else if (axis_index == 1) { + val += worker_data.gyro_scale[uorb_index].y_offset; - /* update the _X0_ terms to include the additional offset */ - int32_t handle; - float val; - - for (unsigned axis_index = 0; axis_index < 3; axis_index++) { - val = 0.0f; - (void)sprintf(str, "TC_G%u_X0_%u", sensor_correction.gyro_mapping[uorb_index], axis_index); - handle = param_find(str); - param_get(handle, &val); - - if (axis_index == 0) { - val += worker_data.gyro_scale[uorb_index].x_offset; - - } else if (axis_index == 1) { - val += worker_data.gyro_scale[uorb_index].y_offset; - - } else if (axis_index == 2) { - val += worker_data.gyro_scale[uorb_index].z_offset; - - } - - failed |= (PX4_OK != param_set_no_notification(handle, &val)); - } - - param_notify_changes(); + } else if (axis_index == 2) { + val += worker_data.gyro_scale[uorb_index].z_offset; } - // Ensure the calibration values used the driver are at default settings - worker_data.gyro_scale[uorb_index].x_offset = 0.f; - worker_data.gyro_scale[uorb_index].y_offset = 0.f; - worker_data.gyro_scale[uorb_index].z_offset = 0.f; + failed |= (PX4_OK != param_set_no_notification(handle, &val)); } - (void)sprintf(str, "CAL_GYRO%u_XOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(worker_data.gyro_scale[uorb_index].x_offset))); - (void)sprintf(str, "CAL_GYRO%u_YOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(worker_data.gyro_scale[uorb_index].y_offset))); - (void)sprintf(str, "CAL_GYRO%u_ZOFF", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(worker_data.gyro_scale[uorb_index].z_offset))); - - (void)sprintf(str, "CAL_GYRO%u_ID", uorb_index); - failed |= (PX4_OK != param_set_no_notification(param_find(str), &(worker_data.device_id[uorb_index]))); + // Ensure the calibration values used the driver are at default settings + worker_data.gyro_scale[uorb_index].x_offset = 0.f; + worker_data.gyro_scale[uorb_index].y_offset = 0.f; + worker_data.gyro_scale[uorb_index].z_offset = 0.f; + } -#if 1 // TODO: replace all IOCTL usage - /* apply new scaling and offsets */ - (void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, uorb_index); - int fd = px4_open(str, 0); + char str[30] {}; - if (fd < 0) { - failed = true; - continue; - } + (void)sprintf(str, "CAL_GYRO%u_XOFF", uorb_index); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &worker_data.gyro_scale[uorb_index].x_offset)); - res = px4_ioctl(fd, GYROIOCSSCALE, (long unsigned int)&worker_data.gyro_scale[uorb_index]); - px4_close(fd); + (void)sprintf(str, "CAL_GYRO%u_YOFF", uorb_index); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &worker_data.gyro_scale[uorb_index].y_offset)); - if (res != PX4_OK) { - calibration_log_critical(mavlink_log_pub, CAL_ERROR_APPLY_CAL_MSG); - } + (void)sprintf(str, "CAL_GYRO%u_ZOFF", uorb_index); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &worker_data.gyro_scale[uorb_index].z_offset)); -#endif - } + (void)sprintf(str, "CAL_GYRO%u_ID", uorb_index); + failed |= (PX4_OK != param_set_no_notification(param_find(str), &worker_data.device_id[uorb_index])); } if (failed) { @@ -499,6 +359,8 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) } } + param_notify_changes(); + /* if there is a any preflight-check system response, let the barrage of messages through */ px4_usleep(200000); @@ -509,8 +371,6 @@ int do_gyro_calibration(orb_advert_t *mavlink_log_pub) calibration_log_info(mavlink_log_pub, CAL_QGC_FAILED_MSG, sensor_name); } - orb_unsubscribe(worker_data.sensor_correction_sub); - /* give this message enough time to propagate */ px4_usleep(600000); diff --git a/src/modules/commander/mag_calibration.cpp b/src/modules/commander/mag_calibration.cpp index 1a45c10e1937..65f1ec1df847 100644 --- a/src/modules/commander/mag_calibration.cpp +++ b/src/modules/commander/mag_calibration.cpp @@ -52,17 +52,16 @@ #include #include #include -#include -#include #include #include +#include #include #include #include -#include +#include -static const char *sensor_name = "mag"; -static constexpr unsigned max_mags = 4; +static constexpr char sensor_name[] {"mag"}; +static constexpr unsigned MAX_MAGS = 4; static constexpr float mag_sphere_radius = 0.2f; static unsigned int calibration_sides = 6; ///< The total number of sides static constexpr unsigned int calibration_total_points = 240; ///< The total points per magnetometer @@ -71,8 +70,8 @@ static constexpr unsigned int calibraton_duration_seconds = 42; ///< The total static constexpr float MAG_MAX_OFFSET_LEN = 1.3f; ///< The maximum measurement range is ~1.9 Ga, the earth field is ~0.6 Ga, so an offset larger than ~1.3 Ga means the mag will saturate in some directions. -int32_t device_ids[max_mags]; -bool internal[max_mags]; +int32_t device_ids[MAX_MAGS] {}; +bool internal[MAX_MAGS] {}; int device_prio_max = 0; int32_t device_id_primary = 0; static unsigned _last_mag_progress = 0; @@ -80,20 +79,19 @@ static unsigned _last_mag_progress = 0; calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_mask); /// Data passed to calibration worker routine -typedef struct { - orb_advert_t *mavlink_log_pub; - unsigned done_count; - int sub_mag[max_mags]; - unsigned int calibration_points_perside; - unsigned int calibration_interval_perside_seconds; - uint64_t calibration_interval_perside_useconds; - unsigned int calibration_counter_total[max_mags]; - bool side_data_collected[detect_orientation_side_count]; - float *x[max_mags]; - float *y[max_mags]; - float *z[max_mags]; -} mag_worker_data_t; - +struct mag_worker_data_t { + orb_advert_t *mavlink_log_pub{nullptr}; + unsigned done_count{0}; + int sub_mag[MAX_MAGS] {-1, -1, -1}; + unsigned int calibration_points_perside{0}; + unsigned int calibration_interval_perside_seconds{0}; + uint64_t calibration_interval_perside_useconds{0}; + unsigned int calibration_counter_total[MAX_MAGS] {}; + bool side_data_collected[detect_orientation_side_count] {}; + float *x[MAX_MAGS] {nullptr}; + float *y[MAX_MAGS] {nullptr}; + float *z[MAX_MAGS] {nullptr}; +}; int do_mag_calibration(orb_advert_t *mavlink_log_pub) { @@ -136,7 +134,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub) PX4_ERR("unable to reset %s", str); } - for (size_t i = 0; i < max_mags; i++) { + for (size_t i = 0; i < MAX_MAGS; i++) { device_ids[i] = 0; // signals no mag } @@ -151,7 +149,7 @@ int do_mag_calibration(orb_advert_t *mavlink_log_pub) const bool append_to_existing_calibration = cal_mask < ((1 << 6) - 1); (void)append_to_existing_calibration; - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { #if 1 // TODO: replace all IOCTL usage // Reset mag id to mag not available (void)sprintf(str, "CAL_MAG%u_ID", cur_mag); @@ -369,29 +367,27 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta hrt_abstime detection_deadline = hrt_absolute_time() + worker_data->calibration_interval_perside_useconds * 5; hrt_abstime last_gyro = 0; - float gyro_x_integral = 0.0f; - float gyro_y_integral = 0.0f; - float gyro_z_integral = 0.0f; + matrix::Vector3f gyro_integral{0.0f, 0.0f, 0.0f}; const float gyro_int_thresh_rad = 0.5f; - int sub_gyro = orb_subscribe(ORB_ID(sensor_gyro)); + int sub_gyro = orb_subscribe(ORB_ID(vehicle_angular_velocity)); - while (fabsf(gyro_x_integral) < gyro_int_thresh_rad && - fabsf(gyro_y_integral) < gyro_int_thresh_rad && - fabsf(gyro_z_integral) < gyro_int_thresh_rad) { + while (fabsf(gyro_integral(0)) < gyro_int_thresh_rad && + fabsf(gyro_integral(1)) < gyro_int_thresh_rad && + fabsf(gyro_integral(2)) < gyro_int_thresh_rad) { /* abort on request */ if (calibrate_cancel_check(worker_data->mavlink_log_pub, cancel_sub)) { result = calibrate_return_cancelled; - px4_close(sub_gyro); + orb_unsubscribe(sub_gyro); return result; } /* abort with timeout */ if (hrt_absolute_time() > detection_deadline) { result = calibrate_return_error; - warnx("int: %8.4f, %8.4f, %8.4f", (double)gyro_x_integral, (double)gyro_y_integral, (double)gyro_z_integral); + warnx("int: %8.4f, %8.4f, %8.4f", (double)gyro_integral(0), (double)gyro_integral(1), (double)gyro_integral(2)); calibration_log_critical(worker_data->mavlink_log_pub, "Failed: This calibration requires rotation."); break; } @@ -405,24 +401,21 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta int poll_ret = px4_poll(fds, fd_count, 1000); if (poll_ret > 0) { - sensor_gyro_s gyro{}; - orb_copy(ORB_ID(sensor_gyro), sub_gyro, &gyro); + vehicle_angular_velocity_s gyro{}; + orb_copy(ORB_ID(vehicle_angular_velocity), sub_gyro, &gyro); /* ensure we have a valid first timestamp */ if (last_gyro > 0) { - - /* integrate */ + // integrate float delta_t = (gyro.timestamp - last_gyro) / 1e6f; - gyro_x_integral += gyro.x * delta_t; - gyro_y_integral += gyro.y * delta_t; - gyro_z_integral += gyro.z * delta_t; + gyro_integral += matrix::Vector3f{gyro.xyz} * delta_t; } last_gyro = gyro.timestamp; } } - px4_close(sub_gyro); + orb_unsubscribe(sub_gyro); uint64_t calibration_deadline = hrt_absolute_time() + worker_data->calibration_interval_perside_useconds; unsigned poll_errcount = 0; @@ -438,10 +431,10 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta } // Wait clocking for new data on all mags - px4_pollfd_struct_t fds[max_mags]; + px4_pollfd_struct_t fds[MAX_MAGS]; size_t fd_count = 0; - for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { if (worker_data->sub_mag[cur_mag] >= 0 && device_ids[cur_mag] != 0) { fds[fd_count].fd = worker_data->sub_mag[cur_mag]; fds[fd_count].events = POLLIN; @@ -453,10 +446,10 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta if (poll_ret > 0) { - int prev_count[max_mags]; + int prev_count[MAX_MAGS]; bool rejected = false; - for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { prev_count[cur_mag] = worker_data->calibration_counter_total[cur_mag]; @@ -481,7 +474,7 @@ static calibrate_return mag_calibration_worker(detect_orientation_return orienta // Keep calibration of all mags in lockstep if (rejected) { // Reset counts, since one of the mags rejected the measurement - for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { worker_data->calibration_counter_total[cur_mag] = prev_count[cur_mag]; } @@ -558,7 +551,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma } } - for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { // Initialize to no subscription worker_data.sub_mag[cur_mag] = -1; @@ -576,12 +569,12 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma // Get actual mag count and alloate only as much memory as needed const unsigned orb_mag_count = orb_group_count(ORB_ID(sensor_mag)); - // Warn that we will not calibrate more than max_mags magnetometers - if (orb_mag_count > max_mags) { - calibration_log_critical(mavlink_log_pub, "Detected %u mags, but will calibrate only %u", orb_mag_count, max_mags); + // Warn that we will not calibrate more than MAX_MAGS magnetometers + if (orb_mag_count > MAX_MAGS) { + calibration_log_critical(mavlink_log_pub, "Detected %u mags, but will calibrate only %u", orb_mag_count, MAX_MAGS); } - for (size_t cur_mag = 0; cur_mag < orb_mag_count && cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < orb_mag_count && cur_mag < MAX_MAGS; cur_mag++) { worker_data.x[cur_mag] = static_cast(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.y[cur_mag] = static_cast(malloc(sizeof(float) * calibration_points_maxcount)); worker_data.z[cur_mag] = static_cast(malloc(sizeof(float) * calibration_points_maxcount)); @@ -597,7 +590,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma if (result == calibrate_return_ok) { // We should not try to subscribe if the topic doesn't actually exist and can be counted. - for (unsigned cur_mag = 0; cur_mag < orb_mag_count && cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < orb_mag_count && cur_mag < MAX_MAGS; cur_mag++) { // Lock in to correct ORB instance bool found_cur_mag = false; @@ -657,7 +650,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma // Limit update rate to get equally spaced measurements over time (in ms) if (result == calibrate_return_ok) { - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available unsigned int orb_interval_msecs = (worker_data.calibration_interval_perside_useconds / 1000) / @@ -683,26 +676,26 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma } // Close subscriptions - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { if (worker_data.sub_mag[cur_mag] >= 0) { - px4_close(worker_data.sub_mag[cur_mag]); + orb_unsubscribe(worker_data.sub_mag[cur_mag]); } } // Calculate calibration values for each mag - float sphere_x[max_mags]; - float sphere_y[max_mags]; - float sphere_z[max_mags]; - float sphere_radius[max_mags]; - float diag_x[max_mags]; - float diag_y[max_mags]; - float diag_z[max_mags]; - float offdiag_x[max_mags]; - float offdiag_y[max_mags]; - float offdiag_z[max_mags]; - - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + float sphere_x[MAX_MAGS]; + float sphere_y[MAX_MAGS]; + float sphere_z[MAX_MAGS]; + float sphere_radius[MAX_MAGS]; + float diag_x[MAX_MAGS]; + float diag_y[MAX_MAGS]; + float diag_z[MAX_MAGS]; + float offdiag_x[MAX_MAGS]; + float offdiag_y[MAX_MAGS]; + float offdiag_z[MAX_MAGS]; + + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { sphere_x[cur_mag] = 0.0f; sphere_y[cur_mag] = 0.0f; sphere_z[cur_mag] = 0.0f; @@ -717,7 +710,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma // Sphere fit the data to get calibration values if (result == calibrate_return_ok) { - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { if (device_ids[cur_mag] != 0) { // Mag in this slot is available and we should have values for it to calibrate @@ -751,7 +744,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma // DO NOT REMOVE! Critical validation data! // printf("RAW DATA:\n--------------------\n"); - // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + // for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; @@ -770,7 +763,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma // } // printf("CALIBRATED DATA:\n--------------------\n"); - // for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + // for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { // if (worker_data.calibration_counter_total[cur_mag] == 0) { // continue; @@ -791,7 +784,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma } // Data points are no longer needed - for (size_t cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (size_t cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { free(worker_data.x[cur_mag]); free(worker_data.y[cur_mag]); free(worker_data.z[cur_mag]); @@ -799,7 +792,7 @@ calibrate_return mag_calibrate_all(orb_advert_t *mavlink_log_pub, int32_t cal_ma if (result == calibrate_return_ok) { - for (unsigned cur_mag = 0; cur_mag < max_mags; cur_mag++) { + for (unsigned cur_mag = 0; cur_mag < MAX_MAGS; cur_mag++) { if (device_ids[cur_mag] != 0) { mag_calibration_s mscale; diff --git a/src/modules/sensors/sensor_corrections/CMakeLists.txt b/src/modules/sensors/sensor_corrections/CMakeLists.txt index 932e2029c5bd..560975ebd31e 100644 --- a/src/modules/sensors/sensor_corrections/CMakeLists.txt +++ b/src/modules/sensors/sensor_corrections/CMakeLists.txt @@ -35,3 +35,5 @@ px4_add_library(sensor_corrections SensorCorrections.cpp SensorCorrections.hpp ) + +target_include_directories(sensor_corrections PRIVATE ${CMAKE_CURRENT_SOURCE_DIR}/..) diff --git a/src/modules/sensors/sensor_corrections/SensorCorrections.cpp b/src/modules/sensors/sensor_corrections/SensorCorrections.cpp index f5b51d523bcb..75890208b0ec 100644 --- a/src/modules/sensors/sensor_corrections/SensorCorrections.cpp +++ b/src/modules/sensors/sensor_corrections/SensorCorrections.cpp @@ -51,6 +51,7 @@ void SensorCorrections::set_device_id(uint32_t device_id) if (_device_id != device_id) { _device_id = device_id; SensorCorrectionsUpdate(true); + ParametersUpdate(); } } @@ -67,6 +68,67 @@ const char *SensorCorrections::SensorString() const return nullptr; } +int SensorCorrections::FindCalibrationIndex(uint32_t device_id) const +{ + if (device_id == 0) { + return -1; + } + + for (unsigned i = 0; i < MAX_SENSOR_COUNT; ++i) { + char str[16] {}; + sprintf(str, "CAL_%s%u_ID", SensorString(), i); + + int32_t device_id_val = 0; + + if (param_get(param_find(str), &device_id_val) != OK) { + PX4_ERR("Could not access param %s", str); + continue; + } + + if ((uint32_t)device_id_val == device_id) { + return i; + } + } + + return -1; +} + +Vector3f SensorCorrections::CalibrationOffset(uint8_t calibration_index) const +{ + // offsets (x, y, z) + Vector3f offset{0.f, 0.f, 0.f}; + char str[20] {}; + + sprintf(str, "CAL_%s%u_XOFF", SensorString(), calibration_index); + param_get(param_find(str), &offset(0)); + + sprintf(str, "CAL_%s%u_YOFF", SensorString(), calibration_index); + param_get(param_find(str), &offset(1)); + + sprintf(str, "CAL_%s%u_ZOFF", SensorString(), calibration_index); + param_get(param_find(str), &offset(2)); + + return offset; +} + +Vector3f SensorCorrections::CalibrationScale(uint8_t calibration_index) const +{ + // scale factors (x, y, z) + Vector3f scale{1.f, 1.f, 1.f}; + char str[20] {}; + + sprintf(str, "CAL_%s%u_XSCALE", SensorString(), calibration_index); + param_get(param_find(str), &scale(0)); + + sprintf(str, "CAL_%s%u_YSCALE", SensorString(), calibration_index); + param_get(param_find(str), &scale(1)); + + sprintf(str, "CAL_%s%u_ZSCALE", SensorString(), calibration_index); + param_get(param_find(str), &scale(2)); + + return scale; +} + void SensorCorrections::SensorCorrectionsUpdate(bool force) { // check if the selected sensor has updated @@ -152,10 +214,35 @@ void SensorCorrections::ParametersUpdate() // get transformation matrix from sensor/board to body frame _board_rotation = board_rotation_offset * get_rot_matrix((enum Rotation)_param_sens_board_rot.get()); + + // temperature calibration disabled + if (_corrections_selected_instance < 0) { + int calibration_index = FindCalibrationIndex(_device_id); + + if (calibration_index >= 0) { + _offset = CalibrationOffset(calibration_index); + + // gyroscope doesn't have a scale factor calibration + if (_type != SensorType::Gyroscope) { + _scale = CalibrationScale(calibration_index); + + } else { + _scale = Vector3f{1.f, 1.f, 1.f}; + } + + } else { + _offset.zero(); + _scale = Vector3f{1.f, 1.f, 1.f}; + } + } } void SensorCorrections::PrintStatus() { + if (_corrections_selected_instance >= 0) { + PX4_INFO("%s %d temperature calibration enabled", SensorString(), _device_id); + } + if (_offset.norm() > 0.f) { PX4_INFO("%s %d offset: [%.3f %.3f %.3f]", SensorString(), _device_id, (double)_offset(0), (double)_offset(1), (double)_offset(2)); diff --git a/src/modules/sensors/sensor_corrections/SensorCorrections.hpp b/src/modules/sensors/sensor_corrections/SensorCorrections.hpp index 75881e72f884..e0d5fb33ce48 100644 --- a/src/modules/sensors/sensor_corrections/SensorCorrections.hpp +++ b/src/modules/sensors/sensor_corrections/SensorCorrections.hpp @@ -53,7 +53,6 @@ class SensorCorrections : public ModuleParams Gyroscope, }; - SensorCorrections() = delete; SensorCorrections(ModuleParams *parent, SensorType type); ~SensorCorrections() override = default; @@ -73,6 +72,11 @@ class SensorCorrections : public ModuleParams static constexpr int MAX_SENSOR_COUNT = 3; + int FindCalibrationIndex(uint32_t device_id) const; + + matrix::Vector3f CalibrationOffset(uint8_t calibration_index) const; + matrix::Vector3f CalibrationScale(uint8_t calibration_index) const; + const char *SensorString() const; uORB::Subscription _sensor_correction_sub{ORB_ID(sensor_correction)}; diff --git a/src/modules/sensors/voted_sensors_update.cpp b/src/modules/sensors/voted_sensors_update.cpp index d920e18820e9..7c2e093617d9 100644 --- a/src/modules/sensors/voted_sensors_update.cpp +++ b/src/modules/sensors/voted_sensors_update.cpp @@ -52,18 +52,12 @@ using namespace sensors; using namespace matrix; using math::radians; -VotedSensorsUpdate::VotedSensorsUpdate(const Parameters ¶meters, bool hil_enabled) - : ModuleParams(nullptr), _parameters(parameters), _hil_enabled(hil_enabled), _mag_compensator(this) +VotedSensorsUpdate::VotedSensorsUpdate(const Parameters ¶meters, bool hil_enabled) : + ModuleParams(nullptr), + _parameters(parameters), + _hil_enabled(hil_enabled), + _mag_compensator(this) { - for (unsigned i = 0; i < 3; i++) { - _corrections.gyro_scale_0[i] = 1.0f; - _corrections.accel_scale_0[i] = 1.0f; - _corrections.gyro_scale_1[i] = 1.0f; - _corrections.accel_scale_1[i] = 1.0f; - _corrections.gyro_scale_2[i] = 1.0f; - _corrections.accel_scale_2[i] = 1.0f; - } - _mag.voter.set_timeout(300000); _mag.voter.set_equal_value_threshold(1000); @@ -113,19 +107,11 @@ void VotedSensorsUpdate::parametersUpdate() unsigned gyro_count = 0; unsigned gyro_cal_found_count = 0; - for (unsigned driver_index = 0; driver_index < GYRO_COUNT_MAX; driver_index++) { + for (uint8_t driver_index = 0; driver_index < GYRO_COUNT_MAX; driver_index++) { + uORB::SubscriptionData report{ORB_ID(sensor_gyro_integrated), driver_index}; _gyro.enabled[driver_index] = true; - char str[30] {}; - (void)sprintf(str, "%s%u", GYRO_BASE_DEVICE_PATH, driver_index); - - int fd = px4_open(str, O_RDWR); - - if (fd < 0) { - continue; - } - - uint32_t driver_device_id = px4_ioctl(fd, DEVIOCGDEVICEID, 0); + uint32_t driver_device_id = report.get().device_id; bool config_ok = false; /* run through all stored calibrations that are applied at the driver level*/ @@ -133,8 +119,9 @@ void VotedSensorsUpdate::parametersUpdate() /* initially status is ok per config */ failed = false; + char str[16] {}; (void)sprintf(str, "CAL_GYRO%u_ID", i); - int32_t device_id = 0; + int32_t device_id = -1; failed = failed || (PX4_OK != param_get(param_find(str), &device_id)); (void)sprintf(str, "CAL_GYRO%u_EN", i); @@ -157,29 +144,6 @@ void VotedSensorsUpdate::parametersUpdate() _gyro.priority[driver_index] = 0; } - gyro_calibration_s gscale{}; - - (void)sprintf(str, "CAL_GYRO%u_XOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &gscale.x_offset)); - - (void)sprintf(str, "CAL_GYRO%u_YOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &gscale.y_offset)); - - (void)sprintf(str, "CAL_GYRO%u_ZOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &gscale.z_offset)); - - if (failed) { - PX4_ERR(CAL_ERROR_APPLY_CAL_MSG, "gyro", i); - - } else { - /* apply new scaling and offsets */ - config_ok = (px4_ioctl(fd, GYROIOCSSCALE, (long unsigned int)&gscale) == 0); - - if (!config_ok) { - PX4_ERR(CAL_ERROR_APPLY_CAL_MSG, "gyro ", i); - } - } - break; } } @@ -187,41 +151,17 @@ void VotedSensorsUpdate::parametersUpdate() if (config_ok) { gyro_count++; } - - px4_close(fd); - } - - // There are fewer gyros than calibrations - // reset the board calibration and fail the initial load - if (gyro_count < gyro_cal_found_count) { - PX4_ERR("fewer accels than calibrations, resetting all CAL_GYROx_ID"); - - // run through all stored calibrations and reset them - for (unsigned i = 0; i < GYRO_COUNT_MAX; i++) { - char str[30] {}; - (void)sprintf(str, "CAL_GYRO%u_ID", i); - int32_t device_id = 0; - (void)param_set(param_find(str), &device_id); - } } /* run through all accel sensors */ unsigned accel_count = 0; unsigned accel_cal_found_count = 0; - for (unsigned driver_index = 0; driver_index < ACCEL_COUNT_MAX; driver_index++) { + for (uint8_t driver_index = 0; driver_index < ACCEL_COUNT_MAX; driver_index++) { + uORB::SubscriptionData report{ORB_ID(sensor_accel_integrated), driver_index}; _accel.enabled[driver_index] = true; - char str[30] {}; - (void)sprintf(str, "%s%u", ACCEL_BASE_DEVICE_PATH, driver_index); - - int fd = px4_open(str, O_RDWR); - - if (fd < 0) { - continue; - } - - uint32_t driver_device_id = px4_ioctl(fd, DEVIOCGDEVICEID, 0); + uint32_t driver_device_id = report.get().device_id; bool config_ok = false; /* run through all stored calibrations */ @@ -229,8 +169,9 @@ void VotedSensorsUpdate::parametersUpdate() /* initially status is ok per config */ failed = false; + char str[16] {}; (void)sprintf(str, "CAL_ACC%u_ID", i); - int32_t device_id = 0; + int32_t device_id = -1; failed = failed || (PX4_OK != param_get(param_find(str), &device_id)); (void)sprintf(str, "CAL_ACC%u_EN", i); @@ -253,38 +194,6 @@ void VotedSensorsUpdate::parametersUpdate() _accel.priority[driver_index] = 0; } - accel_calibration_s ascale{}; - - (void)sprintf(str, "CAL_ACC%u_XOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.x_offset)); - - (void)sprintf(str, "CAL_ACC%u_YOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.y_offset)); - - (void)sprintf(str, "CAL_ACC%u_ZOFF", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.z_offset)); - - (void)sprintf(str, "CAL_ACC%u_XSCALE", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.x_scale)); - - (void)sprintf(str, "CAL_ACC%u_YSCALE", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.y_scale)); - - (void)sprintf(str, "CAL_ACC%u_ZSCALE", i); - failed = failed || (PX4_OK != param_get(param_find(str), &ascale.z_scale)); - - if (failed) { - PX4_ERR(CAL_ERROR_APPLY_CAL_MSG, "accel", i); - - } else { - /* apply new scaling and offsets */ - config_ok = (px4_ioctl(fd, ACCELIOCSSCALE, (long unsigned int)&ascale) == 0); - - if (!config_ok) { - PX4_ERR(CAL_ERROR_APPLY_CAL_MSG, "accel ", i); - } - } - break; } } @@ -292,22 +201,6 @@ void VotedSensorsUpdate::parametersUpdate() if (config_ok) { accel_count++; } - - px4_close(fd); - } - - // There are fewer accels than calibrations - // reset the board calibration and fail the initial load - if (accel_count < accel_cal_found_count) { - PX4_ERR("fewer accels than calibrations, resetting all CAL_ACCx_ID"); - - // run through all stored calibrations and reset them - for (unsigned i = 0; i < ACCEL_COUNT_MAX; i++) { - char str[30] {}; - (void)sprintf(str, "CAL_ACC%u_ID", i); - int32_t device_id = 0; - (void)param_set(param_find(str), &device_id); - } } /* run through all mag sensors @@ -465,9 +358,6 @@ void VotedSensorsUpdate::parametersUpdate() void VotedSensorsUpdate::accelPoll(struct sensor_combined_s &raw) { - float *offsets[] = {_corrections.accel_offset_0, _corrections.accel_offset_1, _corrections.accel_offset_2 }; - float *scales[] = {_corrections.accel_scale_0, _corrections.accel_scale_1, _corrections.accel_scale_2 }; - for (int uorb_index = 0; uorb_index < _accel.subscription_count; uorb_index++) { sensor_accel_integrated_s accel_report; @@ -480,23 +370,12 @@ void VotedSensorsUpdate::accelPoll(struct sensor_combined_s &raw) } _accel_device_id[uorb_index] = accel_report.device_id; - - /* - * Correct the raw sensor data for scale factor errors - * and offsets due to temperature variation. It is assumed that any filtering of input - * data required is performed in the sensor driver, preferably before downsampling. - */ + _last_sensor_data[uorb_index].accelerometer_integral_dt = accel_report.dt; // convert the delta velocities to an equivalent acceleration before application of corrections const float dt_inv = 1.e6f / (float)accel_report.dt; - Vector3f accel_data = Vector3f{accel_report.delta_velocity} * dt_inv; - - _last_sensor_data[uorb_index].accelerometer_integral_dt = accel_report.dt; - // apply temperature compensation - accel_data(0) = (accel_data(0) - offsets[uorb_index][0]) * scales[uorb_index][0]; // X - accel_data(1) = (accel_data(1) - offsets[uorb_index][1]) * scales[uorb_index][1]; // Y - accel_data(2) = (accel_data(2) - offsets[uorb_index][2]) * scales[uorb_index][2]; // Z + Vector3f accel_data{_accel_corrections[uorb_index].Correct(Vector3f{accel_report.delta_velocity} * dt_inv)}; // rotate corrected measurements from sensor to body frame accel_data = _board_rotation * accel_data; @@ -557,9 +436,6 @@ void VotedSensorsUpdate::accelPoll(struct sensor_combined_s &raw) void VotedSensorsUpdate::gyroPoll(struct sensor_combined_s &raw) { - float *offsets[] = {_corrections.gyro_offset_0, _corrections.gyro_offset_1, _corrections.gyro_offset_2 }; - float *scales[] = {_corrections.gyro_scale_0, _corrections.gyro_scale_1, _corrections.gyro_scale_2 }; - for (int uorb_index = 0; uorb_index < _gyro.subscription_count; uorb_index++) { sensor_gyro_integrated_s gyro_report; @@ -571,23 +447,12 @@ void VotedSensorsUpdate::gyroPoll(struct sensor_combined_s &raw) } _gyro_device_id[uorb_index] = gyro_report.device_id; - - /* - * Correct the raw sensor data for scale factor errors - * and offsets due to temperature variation. It is assumed that any filtering of input - * data required is performed in the sensor driver, preferably before downsampling. - */ + _last_sensor_data[uorb_index].gyro_integral_dt = gyro_report.dt; // convert the delta angles to an equivalent angular rate before application of corrections const float dt_inv = 1.e6f / (float)gyro_report.dt; - Vector3f gyro_rate = Vector3f{gyro_report.delta_angle} * dt_inv; - - _last_sensor_data[uorb_index].gyro_integral_dt = gyro_report.dt; - // apply temperature compensation - gyro_rate(0) = (gyro_rate(0) - offsets[uorb_index][0]) * scales[uorb_index][0]; // X - gyro_rate(1) = (gyro_rate(1) - offsets[uorb_index][1]) * scales[uorb_index][1]; // Y - gyro_rate(2) = (gyro_rate(2) - offsets[uorb_index][2]) * scales[uorb_index][2]; // Z + Vector3f gyro_rate{_gyro_corrections[uorb_index].Correct(Vector3f{gyro_report.delta_angle} * dt_inv)}; // rotate corrected measurements from sensor to body frame gyro_rate = _board_rotation * gyro_rate; @@ -784,8 +649,6 @@ void VotedSensorsUpdate::printStatus() void VotedSensorsUpdate::sensorsPoll(sensor_combined_s &raw, vehicle_magnetometer_s &magnetometer) { - _corrections_sub.update(&_corrections); - accelPoll(raw); gyroPoll(raw); magPoll(magnetometer); diff --git a/src/modules/sensors/voted_sensors_update.h b/src/modules/sensors/voted_sensors_update.h index ab89386b9e9f..ad8335a0f252 100644 --- a/src/modules/sensors/voted_sensors_update.h +++ b/src/modules/sensors/voted_sensors_update.h @@ -41,8 +41,6 @@ #include "parameters.h" -#include -#include #include #include @@ -52,7 +50,8 @@ #include #include #include - +#include +#include #include #include #include @@ -204,6 +203,18 @@ class VotedSensorsUpdate : public ModuleParams SensorData _gyro{ORB_ID::sensor_gyro_integrated}; SensorData _mag{ORB_ID::sensor_mag}; + SensorCorrections _accel_corrections[ACCEL_COUNT_MAX] { + {this, SensorCorrections::SensorType::Accelerometer}, + {this, SensorCorrections::SensorType::Accelerometer}, + {this, SensorCorrections::SensorType::Accelerometer}, + }; + + SensorCorrections _gyro_corrections[GYRO_COUNT_MAX] { + {this, SensorCorrections::SensorType::Gyroscope}, + {this, SensorCorrections::SensorType::Gyroscope}, + {this, SensorCorrections::SensorType::Gyroscope}, + }; + orb_advert_t _mavlink_log_pub{nullptr}; uORB::Publication _sensor_selection_pub{ORB_ID(sensor_selection)}; /**< handle to the sensor selection uORB topic */ @@ -236,7 +247,6 @@ class VotedSensorsUpdate : public ModuleParams uint64_t _last_accel_timestamp[ACCEL_COUNT_MAX] {}; /**< latest full timestamp */ - sensor_correction_s _corrections {}; /**< struct containing the sensor corrections to be published to the uORB */ sensor_selection_s _selection {}; /**< struct containing the sensor selection to be published to the uORB */ subsystem_info_s _info {}; /**< subsystem info publication */ }; diff --git a/src/modules/uORB/SubscriptionBlocking.hpp b/src/modules/uORB/SubscriptionBlocking.hpp index 3d9de3f023a6..83d8d0d5201b 100644 --- a/src/modules/uORB/SubscriptionBlocking.hpp +++ b/src/modules/uORB/SubscriptionBlocking.hpp @@ -94,21 +94,20 @@ class SubscriptionBlocking : public SubscriptionCallback } /** - * Copy the struct if updated. - * @param data The data reference where the struct will be copied. + * Block until updated. * @param timeout_us The requested timeout in microseconds, or 0 to wait indefinitely. * - * @return true only if topic was updated and copied successfully. + * @return true only if topic was updated */ - bool updateBlocking(T &data, uint32_t timeout_us = 0) + bool updatedBlocking(uint32_t timeout_us = 0) { if (!_registered) { registerCallback(); } if (updated()) { - // copy immediately if updated - return copy(&data); + // return immediately if updated + return true; } else { // otherwise wait @@ -118,7 +117,7 @@ class SubscriptionBlocking : public SubscriptionCallback if (timeout_us == 0) { // wait with no timeout if (pthread_cond_wait(&_cv, &_mutex) == 0) { - return update(&data); + return updated(); } } else { @@ -134,7 +133,7 @@ class SubscriptionBlocking : public SubscriptionCallback ts.tv_nsec = nsecs; if (px4_pthread_cond_timedwait(&_cv, &_mutex, &ts) == 0) { - return update(&data); + return updated(); } } } @@ -142,6 +141,22 @@ class SubscriptionBlocking : public SubscriptionCallback return false; } + /** + * Copy the struct if updated. + * @param data The data reference where the struct will be copied. + * @param timeout_us The requested timeout in microseconds, or 0 to wait indefinitely. + * + * @return true only if topic was updated and copied successfully. + */ + bool updateBlocking(T &data, uint32_t timeout_us = 0) + { + if (updatedBlocking(timeout_us)) { + return copy(&data); + } + + return false; + } + private: pthread_mutex_t _mutex = PTHREAD_MUTEX_INITIALIZER;