From 0ca71ba72579af24c653d7f950203d338b9f3c1d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Tue, 18 Jun 2019 12:57:39 +1000 Subject: [PATCH] AP_HAL: added get_last_armed_change() Util function --- libraries/AP_HAL/Util.cpp | 9 ++++++--- libraries/AP_HAL/Util.h | 4 ++++ 2 files changed, 10 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL/Util.cpp b/libraries/AP_HAL/Util.cpp index 8217ae2751..0baf3ab67a 100644 --- a/libraries/AP_HAL/Util.cpp +++ b/libraries/AP_HAL/Util.cpp @@ -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; + } } } diff --git a/libraries/AP_HAL/Util.h b/libraries/AP_HAL/Util.h index 8fd9e77914..aeb10d82cf 100644 --- a/libraries/AP_HAL/Util.h +++ b/libraries/AP_HAL/Util.h @@ -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; };