From 31b9efdaebe76937cf7ecda95014946ed98fcdc8 Mon Sep 17 00:00:00 2001 From: Daniel Agar Date: Tue, 6 Apr 2021 13:41:19 -0400 Subject: [PATCH] sensors/vehicle_imu: increase threshold for clipping warning --- src/modules/sensors/vehicle_imu/VehicleIMU.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp index fb231eb2c4..a2cc0ebe5e 100644 --- a/src/modules/sensors/vehicle_imu/VehicleIMU.cpp +++ b/src/modules/sensors/vehicle_imu/VehicleIMU.cpp @@ -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;