AP_Vehicle: add is_crashed method to AP_Vehicle

This commit is contained in:
Peter Barker 2020-07-16 12:52:11 +10:00 committed by Randy Mackay
parent 6ab9089fff
commit 34be953085
2 changed files with 12 additions and 0 deletions

View File

@ -2,6 +2,7 @@
#include <AP_BLHeli/AP_BLHeli.h>
#include <AP_Common/AP_FWVersion.h>
#include <AP_Arming/AP_Arming.h>
#define SCHED_TASK(func, rate_hz, max_time_micros) SCHED_TASK_CLASS(AP_Vehicle, &vehicle, func, rate_hz, max_time_micros)
@ -213,6 +214,14 @@ void AP_Vehicle::send_watchdog_reset_statustext()
);
}
bool AP_Vehicle::is_crashed() const
{
if (AP::arming().is_armed()) {
return false;
}
return AP::arming().last_disarm_method() == AP_Arming::Method::CRASH;
}
// @LoggerMessage: FTN
// @Description: Filter Tuning Messages
// @Field: TimeUS: microseconds since system startup

View File

@ -166,6 +166,9 @@ public:
return AP_HAL::millis() - _last_flying_ms;
}
// returns true if the vehicle has crashed
virtual bool is_crashed() const;
/*
methods to control vehicle for use by scripting
*/