diff --git a/boards/ark/can-flow/init/rc.board_sensors b/boards/ark/can-flow/init/rc.board_sensors index 9099c97c410f..841049dc86bd 100644 --- a/boards/ark/can-flow/init/rc.board_sensors +++ b/boards/ark/can-flow/init/rc.board_sensors @@ -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 diff --git a/boards/ark/can-gps/init/rc.board_defaults b/boards/ark/can-gps/init/rc.board_defaults index 480d2c92c58d..13e16a24f11a 100644 --- a/boards/ark/can-gps/init/rc.board_defaults +++ b/boards/ark/can-gps/init/rc.board_defaults @@ -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 diff --git a/boards/ark/can-rtk-gps/init/rc.board_defaults b/boards/ark/can-rtk-gps/init/rc.board_defaults index 10419cee6b0b..c50d81602629 100644 --- a/boards/ark/can-rtk-gps/init/rc.board_defaults +++ b/boards/ark/can-rtk-gps/init/rc.board_defaults @@ -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 diff --git a/boards/ark/cannode/init/rc.board_defaults b/boards/ark/cannode/init/rc.board_defaults index 7de93ad4e854..7d149ce5ad49 100644 --- a/boards/ark/cannode/init/rc.board_defaults +++ b/boards/ark/cannode/init/rc.board_defaults @@ -3,6 +3,8 @@ # board specific defaults #------------------------------------------------------------------------------ +param set-default SENS_IMU_CLPNOTI 0 + pwm_out start dshot start diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp index 8ca2464b5efe..125d56758c69 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp @@ -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(); @@ -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]; @@ -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]; diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.hpp b/src/modules/sensors/vehicle_imu/VehicleIMU.hpp index ab06dbf03ef1..689d72f61426 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.hpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.hpp @@ -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}; @@ -198,7 +200,8 @@ class VehicleIMU : public ModuleParams, public px4::ScheduledWorkItem DEFINE_PARAMETERS( (ParamInt) _param_imu_integ_rate, - (ParamBool) _param_sens_imu_autocal + (ParamBool) _param_sens_imu_autocal, + (ParamBool) _param_sens_imu_notify_clipping ) }; diff --git a/src/modules/sensors/vehicle_imu/imu_parameters.c b/src/modules/sensors/vehicle_imu/imu_parameters.c index ebe8a465a672..eca9d9fc1248 100644 --- a/src/modules/sensors/vehicle_imu/imu_parameters.c +++ b/src/modules/sensors/vehicle_imu/imu_parameters.c @@ -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);