sensors: add parameter to silence imu clipping

This commit is contained in:
alexklimaj 2023-11-26 11:48:09 -07:00 committed by Daniel Agar
parent a9213e3862
commit 59abab8379
7 changed files with 25 additions and 3 deletions

View File

@ -4,6 +4,7 @@
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
param set-default IMU_GYRO_RATEMAX 1000 param set-default IMU_GYRO_RATEMAX 1000
param set-default SENS_IMU_CLPNOTI 0
# Internal SPI # Internal SPI
if ! paw3902 -s start -Y 180 if ! paw3902 -s start -Y 180

View File

@ -5,6 +5,7 @@
param set-default CBRK_IO_SAFETY 0 param set-default CBRK_IO_SAFETY 0
param set-default MBE_ENABLE 1 param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0
safety_button start safety_button start
tone_alarm start tone_alarm start

View File

@ -7,6 +7,7 @@ param set-default CBRK_IO_SAFETY 0
param set-default CANNODE_SUB_MBD 1 param set-default CANNODE_SUB_MBD 1
param set-default CANNODE_SUB_RTCM 1 param set-default CANNODE_SUB_RTCM 1
param set-default MBE_ENABLE 1 param set-default MBE_ENABLE 1
param set-default SENS_IMU_CLPNOTI 0
safety_button start safety_button start
tone_alarm start tone_alarm start

View File

@ -3,6 +3,8 @@
# board specific defaults # board specific defaults
#------------------------------------------------------------------------------ #------------------------------------------------------------------------------
param set-default SENS_IMU_CLPNOTI 0
pwm_out start pwm_out start
dshot start dshot start

View File

@ -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); _sensor_gyro_sub.set_required_updates(sensor_gyro_s::ORB_QUEUE_LENGTH / 2);
#endif #endif
_notify_clipping = _param_sens_imu_notify_clipping.get();
// advertise immediately to ensure consistent ordering // advertise immediately to ensure consistent ordering
_vehicle_imu_pub.advertise(); _vehicle_imu_pub.advertise();
_vehicle_imu_status_pub.advertise(); _vehicle_imu_status_pub.advertise();
@ -374,7 +376,7 @@ bool VehicleIMU::UpdateAccel()
_publish_status = true; _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 // 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]; 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; _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 // 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]; const uint64_t clipping_total = _status.gyro_clipping[0] + _status.gyro_clipping[1] + _status.gyro_clipping[2];

View File

@ -158,6 +158,8 @@ private:
uint8_t _delta_angle_clipping{0}; uint8_t _delta_angle_clipping{0};
uint8_t _delta_velocity_clipping{0}; uint8_t _delta_velocity_clipping{0};
bool _notify_clipping{true};
hrt_abstime _last_accel_clipping_notify_time{0}; hrt_abstime _last_accel_clipping_notify_time{0};
hrt_abstime _last_gyro_clipping_notify_time{0}; hrt_abstime _last_gyro_clipping_notify_time{0};
@ -198,7 +200,8 @@ private:
DEFINE_PARAMETERS( DEFINE_PARAMETERS(
(ParamInt<px4::params::IMU_INTEG_RATE>) _param_imu_integ_rate, (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
) )
}; };

View File

@ -60,3 +60,15 @@ PARAM_DEFINE_INT32(IMU_INTEG_RATE, 200);
* @group Sensors * @group Sensors
*/ */
PARAM_DEFINE_INT32(SENS_IMU_AUTOCAL, 1); 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);