Skip to content

Commit

Permalink
accel and gyro calibration cleanup
Browse files Browse the repository at this point in the history
 - kill IOCTLs for accel and gyro calibration
 - move accel/calibration entirely to sensors module
  • Loading branch information
dagar committed Apr 25, 2020
1 parent 70329ce commit a7e1b82
Show file tree
Hide file tree
Showing 43 changed files with 564 additions and 1,179 deletions.
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
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 &) {};
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

0 comments on commit a7e1b82

Please sign in to comment.