mirror of
https://github.com/PX4/PX4-Autopilot.git
synced 2026-06-01 19:07:45 +08:00
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:
@@ -328,17 +328,17 @@ void VehicleIMU::Run()
|
|||||||
|
|
||||||
publish_status = true;
|
publish_status = true;
|
||||||
|
|
||||||
|
if (_accel_calibration.enabled() && (hrt_elapsed_time(&_last_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];
|
||||||
|
|
||||||
if ((hrt_elapsed_time(&_last_clipping_notify_time) > 3_s)
|
if (clipping_total > _last_clipping_notify_total_count + 1000) {
|
||||||
&& (clipping_total > _last_clipping_notify_total_count + 100)) {
|
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, not safe to fly!", _instance);
|
||||||
|
|
||||||
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, land immediately!", _instance);
|
|
||||||
_last_clipping_notify_time = accel.timestamp_sample;
|
_last_clipping_notify_time = accel.timestamp_sample;
|
||||||
_last_clipping_notify_total_count = clipping_total;
|
_last_clipping_notify_total_count = clipping_total;
|
||||||
}
|
}
|
||||||
}
|
}
|
||||||
|
}
|
||||||
|
|
||||||
// break once caught up to gyro
|
// break once caught up to gyro
|
||||||
if (!sensor_data_gap && _intervals_configured
|
if (!sensor_data_gap && _intervals_configured
|
||||||
|
|||||||
Reference in New Issue
Block a user