forked from Archive/PX4-Autopilot
sensors/vehicle_imu: accel clipping warning minor improvements
- no warning if accel is disabled - threshold increased 100 -> 1000 (only warn if severe ongoing clipping) - more generic warning message (vehicle isn't necessarily in air flying)
This commit is contained in:
parent
8478d1ea37
commit
6e9e503ee6
|
@ -328,15 +328,15 @@ void VehicleIMU::Run()
|
|||
|
||||
publish_status = true;
|
||||
|
||||
// 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];
|
||||
if (_accel_calibration.enabled() && (hrt_elapsed_time(&_last_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];
|
||||
|
||||
if ((hrt_elapsed_time(&_last_clipping_notify_time) > 3_s)
|
||||
&& (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;
|
||||
_last_clipping_notify_total_count = clipping_total;
|
||||
if (clipping_total > _last_clipping_notify_total_count + 1000) {
|
||||
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, not safe to fly!", _instance);
|
||||
_last_clipping_notify_time = accel.timestamp_sample;
|
||||
_last_clipping_notify_total_count = clipping_total;
|
||||
}
|
||||
}
|
||||
}
|
||||
|
||||
|
|
Loading…
Reference in New Issue