Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

accel and gyro calibration cleanup #14237

Closed
wants to merge 2 commits into from
Closed
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 additions & 0 deletions .ci/Jenkinsfile-hardware
Original file line number Diff line number Diff line change
Expand Up @@ -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"'
Expand Down Expand Up @@ -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"'
Expand Down
1 change: 0 additions & 1 deletion boards/atlflight/eagle/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -89,7 +89,6 @@ px4_add_board(
vtol_att_control
SYSTEMCMDS
#bl_update
#config
#dumpfile
esc_calib
#hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/atlflight/excelsior/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -88,7 +88,6 @@ px4_add_board(
vtol_att_control
SYSTEMCMDS
#bl_update
#config
#dumpfile
esc_calib
#hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -99,7 +99,6 @@ px4_add_board(
#vtol_att_control
SYSTEMCMDS
bl_update
#config
#dmesg
#dumpfile
#esc_calib
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/fixedwing.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -62,7 +62,6 @@ px4_add_board(
#vmount
SYSTEMCMDS
#bl_update
#config
#dumpfile
#esc_calib
hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/lpe.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -87,7 +87,6 @@ px4_add_board(

SYSTEMCMDS
bl_update
#config
#dumpfile
#esc_calib
hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/multicopter.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -60,7 +60,6 @@ px4_add_board(
vmount
SYSTEMCMDS
#bl_update
#config
#dumpfile
#esc_calib
hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/rover.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -55,7 +55,6 @@ px4_add_board(

SYSTEMCMDS
bl_update
#config
#dumpfile
#esc_calib
hardfault_log
Expand Down
1 change: 0 additions & 1 deletion boards/px4/fmu-v2/test.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -92,7 +92,6 @@ px4_add_board(
#vtol_att_control
SYSTEMCMDS
#bl_update
#config
#dmesg
#dumpfile
#esc_calib
Expand Down
1 change: 0 additions & 1 deletion boards/px4/sitl/default.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -53,7 +53,6 @@ px4_add_board(
uuv_att_control

SYSTEMCMDS
#config
#dumpfile
dyn
esc_calib
Expand Down
1 change: 0 additions & 1 deletion boards/px4/sitl/rtps.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -52,7 +52,6 @@ px4_add_board(
vmount
vtol_att_control
SYSTEMCMDS
#config
#dumpfile
dyn
esc_calib
Expand Down
1 change: 0 additions & 1 deletion boards/px4/sitl/test.cmake
Original file line number Diff line number Diff line change
Expand Up @@ -50,7 +50,6 @@ px4_add_board(
vmount
vtol_att_control
SYSTEMCMDS
#config
#dumpfile
dyn
esc_calib
Expand Down
53 changes: 11 additions & 42 deletions msg/sensor_correction.msg
Original file line number Diff line number Diff line change
Expand Up @@ -6,52 +6,21 @@ uint64 timestamp # time since system start (microseconds)

# Corrections for gyro angular rate outputs where corrected_rate = raw_rate * gyro_scale + gyro_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
# corrections for uORB instance 0
float32[3] gyro_offset_0 # gyro XYZ offsets in the sensor frame in rad/s
float32[3] gyro_scale_0 # gyro XYZ scale factors in the sensor frame

# corrections for uORB instance 1
float32[3] gyro_offset_1 # gyro XYZ offsets in the sensor frame in rad/s
float32[3] gyro_scale_1 # gyro XYZ scale factors in the sensor frame

# corrections for uORB instance 2
float32[3] gyro_offset_2 # gyro XYZ offsets in the sensor frame in rad/s
float32[3] gyro_scale_2 # gyro XYZ scale factors in the sensor frame
uint32[3] gyro_device_ids
float32[3] gyro_offset_0 # gyro 0 XYZ offsets in the sensor frame in rad/s
float32[3] gyro_offset_1 # gyro 1 XYZ offsets in the sensor frame in rad/s
float32[3] gyro_offset_2 # gyro 2 XYZ offsets in the sensor frame in rad/s

# Corrections for acceleromter acceleration outputs where corrected_accel = raw_accel * accel_scale + accel_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
# corrections for uORB instance 0
float32[3] accel_offset_0 # accelerometer XYZ offsets in the sensor frame in m/s/s
float32[3] accel_scale_0 # accelerometer XYZ scale factors in the sensor frame

# corrections for uORB instance 1
float32[3] accel_offset_1 # accelerometer XYZ offsets in the sensor frame in m/s/s
float32[3] accel_scale_1 # accelerometer XYZ scale factors in the sensor frame

# corrections for uORB instance 2
float32[3] accel_offset_2 # accelerometer XYZ offsets in the sensor frame in m/s/s
float32[3] accel_scale_2 # accelerometer XYZ scale factors in the sensor frame
uint32[3] accel_device_ids
float32[3] accel_offset_0 # accelerometer 0 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_1 # accelerometer 1 XYZ offsets in the sensor frame in m/s/s
float32[3] accel_offset_2 # accelerometer 2 XYZ offsets in the sensor frame in m/s/s

# Corrections for barometric pressure outputs where corrected_pressure = raw_pressure * pressure_scale + pressure_offset
# Note the corrections are in the sensor frame and must be applied before the sensor data is rotated into body frame
# corrections for uORB instance 0
float32 baro_offset_0 # barometric pressure offsets in the sensor frame in m/s/s
float32 baro_scale_0 # barometric pressure scale factors in the sensor frame

# corrections for uORB instance 1
float32 baro_offset_1 # barometric pressure offsets in the sensor frame in m/s/s
float32 baro_scale_1 # barometric pressure scale factors in the sensor frame

# corrections for uORB instance 2
float32 baro_offset_2 # barometric pressure offsets in the sensor frame in m/s/s
float32 baro_scale_2 # barometric pressure scale factors in the sensor frame

# Mapping from uORB index to parameter index for each sensor type. For example accel_mapping[1] contains the
# compensation parameter system index for the sensor_accel uORB index 1 data.
uint8[3] gyro_mapping
uint8[3] accel_mapping
uint8[3] baro_mapping

uint32[3] gyro_device_ids
uint32[3] accel_device_ids
uint32[3] baro_device_ids
float32 baro_offset_0 # barometric pressure 0 offsets in the sensor frame in m/s/s
float32 baro_offset_1 # barometric pressure 1 offsets in the sensor frame in m/s/s
float32 baro_offset_2 # barometric pressure 2 offsets in the sensor frame in m/s/s
14 changes: 8 additions & 6 deletions platforms/common/include/px4_platform_common/module_params.h
Original file line number Diff line number Diff line change
Expand Up @@ -52,6 +52,14 @@ class ModuleParams : public ListNode<ModuleParams *>
setParent(parent);
}

// empty copy and move constructors (don't copy _children)
ModuleParams(const ModuleParams &) {};
Copy link
Member Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

TODO: review

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.
Expand All @@ -65,12 +73,6 @@ class ModuleParams : public ListNode<ModuleParams *>

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.
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/distance_sensor/cm8jl65/CM8JL65.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include "CM8JL65.hpp"

#include <fcntl.h>

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,
Expand Down
1 change: 1 addition & 0 deletions src/drivers/distance_sensor/leddar_one/LeddarOne.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

#include "LeddarOne.hpp"

#include <fcntl.h>
#include <stdlib.h>
#include <string.h>

Expand Down
1 change: 1 addition & 0 deletions src/drivers/distance_sensor/sf0x/SF0X.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,7 @@

#include "SF0X.hpp"

#include <fcntl.h>
#include <termios.h>

/* Configuration Constants */
Expand Down
2 changes: 2 additions & 0 deletions src/drivers/distance_sensor/tfmini/TFMINI.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -33,6 +33,8 @@

#include "TFMINI.hpp"

#include <fcntl.h>

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)
Expand Down
75 changes: 0 additions & 75 deletions src/drivers/drv_accel.h

This file was deleted.

70 changes: 0 additions & 70 deletions src/drivers/drv_gyro.h

This file was deleted.

2 changes: 1 addition & 1 deletion src/drivers/drv_mixer.h
Original file line number Diff line number Diff line change
Expand Up @@ -85,4 +85,4 @@
* - save/serialise for saving tuned mixers.
*/

#endif /* _DRV_ACCEL_H */
#endif /* _DRV_MIXER_H */
2 changes: 0 additions & 2 deletions src/examples/matlab_csv_serial/matlab_csv_serial.c
Original file line number Diff line number Diff line change
Expand Up @@ -56,8 +56,6 @@
#include <limits.h>
#include <math.h>
#include <uORB/uORB.h>
#include <drivers/drv_accel.h>
#include <drivers/drv_gyro.h>
#include <perf/perf_counter.h>
#include <systemlib/err.h>
#include <poll.h>
Expand Down
Loading