Skip to content

Commit b30f391

Browse files
committed
sensors/vehicle_imu: periodically send mavlink critical message if clipping
1 parent 588883f commit b30f391

File tree

2 files changed

+16
-0
lines changed

2 files changed

+16
-0
lines changed

src/modules/sensors/vehicle_imu/VehicleIMU.cpp

Lines changed: 12 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -34,6 +34,7 @@
3434
#include "VehicleIMU.hpp"
3535

3636
#include <px4_platform_common/log.h>
37+
#include <lib/systemlib/mavlink_log.h>
3738

3839
#include <float.h>
3940

@@ -326,6 +327,17 @@ void VehicleIMU::Run()
326327
}
327328

328329
publish_status = true;
330+
331+
// start notifying the user periodically if there's significant continuous clipping
332+
const uint64_t clipping_total = _status.accel_clipping[0] + _status.accel_clipping[1] + _status.accel_clipping[2];
333+
334+
if ((hrt_elapsed_time(&_last_clipping_notify_time) > 3_s)
335+
&& (clipping_total > _last_clipping_notify_total_count + 10)) {
336+
337+
mavlink_log_critical(&_mavlink_log_pub, "Accel %d clipping, land immediately!", _instance);
338+
_last_clipping_notify_time = accel.timestamp_sample;
339+
_last_clipping_notify_total_count = clipping_total;
340+
}
329341
}
330342

331343
// break once caught up to gyro

src/modules/sensors/vehicle_imu/VehicleIMU.hpp

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -129,6 +129,10 @@ class VehicleIMU : public ModuleParams, public px4::ScheduledWorkItem
129129

130130
uint8_t _delta_velocity_clipping{0};
131131

132+
hrt_abstime _last_clipping_notify_time{0};
133+
uint64_t _last_clipping_notify_total_count{0};
134+
orb_advert_t _mavlink_log_pub{nullptr};
135+
132136
bool _intervals_configured{false};
133137

134138
const uint8_t _instance;

0 commit comments

Comments
 (0)