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

sensors: add parameter to silence imu clipping #22441

Merged
merged 1 commit into from Nov 28, 2023
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
1 change: 1 addition & 0 deletions boards/ark/can-flow/init/rc.board_sensors
Expand Up @@ -4,6 +4,7 @@
#------------------------------------------------------------------------------

param set-default IMU_GYRO_RATEMAX 1000
param set-default SENS_IMU_CLPNOTI 0

# Internal SPI
if ! paw3902 -s start -Y 180
Expand Down
1 change: 1 addition & 0 deletions boards/ark/can-gps/init/rc.board_defaults
Expand Up @@ -5,6 +5,7 @@

param set-default CBRK_IO_SAFETY 0
param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0

safety_button start
tone_alarm start
1 change: 1 addition & 0 deletions boards/ark/can-rtk-gps/init/rc.board_defaults
Expand Up @@ -7,6 +7,7 @@ param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1
param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0

safety_button start
tone_alarm start
2 changes: 2 additions & 0 deletions boards/ark/cannode/init/rc.board_defaults
Expand Up @@ -3,6 +3,8 @@
# board specific defaults
#------------------------------------------------------------------------------

param set-default SENS_IMU_CLPNOTI 0

pwm_out start

dshot start
6 changes: 4 additions & 2 deletions src/modules/sensors/vehicle_imu/VehicleIMU.cpp
Expand Up @@ -70,6 +70,8 @@ VehicleIMU::VehicleIMU(int instance, uint8_t accel_index, uint8_t gyro_index, co
_sensor_gyro_sub.set_required_updates(sensor_gyro_s::ORB_QUEUE_LENGTH / 2);
#endif

_notify_clipping = _param_sens_imu_notify_clipping.get();

// advertise immediately to ensure consistent ordering
_vehicle_imu_pub.advertise();
_vehicle_imu_status_pub.advertise();
Expand Down Expand Up @@ -374,7 +376,7 @@ bool VehicleIMU::UpdateAccel()

_publish_status = true;

if (_accel_calibration.enabled() && (hrt_elapsed_time(&_last_accel_clipping_notify_time) > 3_s)) {
if (_notify_clipping && _accel_calibration.enabled() && (hrt_elapsed_time(&_last_accel_clipping_notify_time) > 3_s)) {
// start notifying the user periodically if there's significant continuous clipping
const uint64_t clipping_total = _status.accel_clipping[0] + _status.accel_clipping[1] + _status.accel_clipping[2];

Expand Down Expand Up @@ -503,7 +505,7 @@ bool VehicleIMU::UpdateGyro()

_publish_status = true;

if (_gyro_calibration.enabled() && (hrt_elapsed_time(&_last_gyro_clipping_notify_time) > 3_s)) {
if (_notify_clipping && _gyro_calibration.enabled() && (hrt_elapsed_time(&_last_gyro_clipping_notify_time) > 3_s)) {
// start notifying the user periodically if there's significant continuous clipping
const uint64_t clipping_total = _status.gyro_clipping[0] + _status.gyro_clipping[1] + _status.gyro_clipping[2];

Expand Down
5 changes: 4 additions & 1 deletion src/modules/sensors/vehicle_imu/VehicleIMU.hpp
Expand Up @@ -158,6 +158,8 @@ class VehicleIMU : public ModuleParams, public px4::ScheduledWorkItem
uint8_t _delta_angle_clipping{0};
uint8_t _delta_velocity_clipping{0};

bool _notify_clipping{true};

hrt_abstime _last_accel_clipping_notify_time{0};
hrt_abstime _last_gyro_clipping_notify_time{0};

Expand Down Expand Up @@ -198,7 +200,8 @@ class VehicleIMU : public ModuleParams, public px4::ScheduledWorkItem

DEFINE_PARAMETERS(
(ParamInt<px4::params::IMU_INTEG_RATE>) _param_imu_integ_rate,
(ParamBool<px4::params::SENS_IMU_AUTOCAL>) _param_sens_imu_autocal
(ParamBool<px4::params::SENS_IMU_AUTOCAL>) _param_sens_imu_autocal,
(ParamBool<px4::params::SENS_IMU_CLPNOTI>) _param_sens_imu_notify_clipping
)
};

Expand Down
12 changes: 12 additions & 0 deletions src/modules/sensors/vehicle_imu/imu_parameters.c
Expand Up @@ -60,3 +60,15 @@ PARAM_DEFINE_INT32(IMU_INTEG_RATE, 200);
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_IMU_AUTOCAL, 1);

/**
* IMU notify clipping
*
* Notify the user if the IMU is clipping
*
* @boolean
*
* @category system
* @group Sensors
*/
PARAM_DEFINE_INT32(SENS_IMU_CLPNOTI, 1);