AP_HAL: added get_last_armed_change() Util function

This commit is contained in:
Andrew Tridgell 2019-06-18 12:57:39 +10:00
parent 8fc8bc4d84
commit 0ca71ba725
2 changed files with 10 additions and 3 deletions

View File

@ -93,8 +93,11 @@ void AP_HAL::Util::set_hw_rtc(uint64_t time_utc_usec)
void AP_HAL::Util::set_soft_armed(const bool b)
{
soft_armed = b;
if (!was_watchdog_reset()) {
persistent_data.armed = b;
if (b != soft_armed) {
soft_armed = b;
last_armed_change_ms = AP_HAL::millis();
if (!was_watchdog_reset()) {
persistent_data.armed = b;
}
}
}

View File

@ -14,6 +14,9 @@ public:
void set_soft_armed(const bool b);
bool get_soft_armed() const { return soft_armed; }
// return the time that the armed state last changed
uint32_t get_last_armed_change() const { return last_armed_change_ms; };
// return true if the reason for the reboot was a watchdog reset
virtual bool was_watchdog_reset() const { return false; }
@ -158,4 +161,5 @@ protected:
// we start soft_armed false, so that actuators don't send any
// values until the vehicle code has fully started
bool soft_armed = false;
uint32_t last_armed_change_ms;
};