sensors/vehicle_imu: increase threshold for clipping warning

This commit is contained in:
Daniel Agar 2021-04-06 13:41:19 -04:00
parent f33fee99c1
commit 31b9efdaeb

View File

@ -332,7 +332,7 @@ void VehicleIMU::Run()
const uint64_t clipping_total = _status.accel_clipping[0] + _status.accel_clipping[1] + _status.accel_clipping[2];
if ((hrt_elapsed_time(&_last_clipping_notify_time) > 3_s)
&& (clipping_total > _last_clipping_notify_total_count + 10)) {
&& (clipping_total > _last_clipping_notify_total_count + 100)) {
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, land immediately!", _instance);
_last_clipping_notify_time = accel.timestamp_sample;