mirror of
https://gitee.com/mirrors_PX4/PX4-Autopilot.git
synced 2026-05-02 05:04:08 +08:00
sensors/vehicle_imu: increase threshold for clipping warning
This commit is contained in:
parent
f33fee99c1
commit
31b9efdaeb
@ -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;
|
||||
|
||||
Loading…
x
Reference in New Issue
Block a user