forked from Archive/PX4-Autopilot
sensors/vehicle_imu: periodically send mavlink critical message if clipping
This commit is contained in:
parent
588883f663
commit
b30f3917d3
|
@ -34,6 +34,7 @@
|
|||
#include "VehicleIMU.hpp"
|
||||
|
||||
#include <px4_platform_common/log.h>
|
||||
#include <lib/systemlib/mavlink_log.h>
|
||||
|
||||
#include <float.h>
|
||||
|
||||
|
@ -326,6 +327,17 @@ 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 ((hrt_elapsed_time(&_last_clipping_notify_time) > 3_s)
|
||||
&& (clipping_total > _last_clipping_notify_total_count + 10)) {
|
||||
|
||||
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;
|
||||
}
|
||||
}
|
||||
|
||||
// break once caught up to gyro
|
||||
|
|
|
@ -129,6 +129,10 @@ private:
|
|||
|
||||
uint8_t _delta_velocity_clipping{0};
|
||||
|
||||
hrt_abstime _last_clipping_notify_time{0};
|
||||
uint64_t _last_clipping_notify_total_count{0};
|
||||
orb_advert_t _mavlink_log_pub{nullptr};
|
||||
|
||||
bool _intervals_configured{false};
|
||||
|
||||
const uint8_t _instance;
|
||||
|
|
Loading…
Reference in New Issue