mirror of https://github.com/ArduPilot/ardupilot
AP_HAL: added was_watchdog_armed()
allow decisions to be based on whether this is a watchdog reset and we were armed
This commit is contained in:
parent
682362945c
commit
44e3b20038
|
@ -11,7 +11,7 @@ public:
|
||||||
int vsnprintf(char* str, size_t size,
|
int vsnprintf(char* str, size_t size,
|
||||||
const char *format, va_list ap);
|
const char *format, va_list ap);
|
||||||
|
|
||||||
void set_soft_armed(const bool b) { soft_armed = b; }
|
virtual void set_soft_armed(const bool b) { soft_armed = b; }
|
||||||
bool get_soft_armed() const { return soft_armed; }
|
bool get_soft_armed() const { return soft_armed; }
|
||||||
|
|
||||||
void set_capabilities(uint64_t cap) { capabilities |= cap; }
|
void set_capabilities(uint64_t cap) { capabilities |= cap; }
|
||||||
|
@ -23,6 +23,9 @@ public:
|
||||||
|
|
||||||
// return true if safety was off and this was a watchdog reset
|
// return true if safety was off and this was a watchdog reset
|
||||||
virtual bool was_watchdog_safety_off() const { return false; }
|
virtual bool was_watchdog_safety_off() const { return false; }
|
||||||
|
|
||||||
|
// return true if this is a watchdog reset boot and we were armed
|
||||||
|
virtual bool was_watchdog_armed() const { return false; }
|
||||||
|
|
||||||
virtual const char* get_custom_log_directory() const { return nullptr; }
|
virtual const char* get_custom_log_directory() const { return nullptr; }
|
||||||
virtual const char* get_custom_terrain_directory() const { return nullptr; }
|
virtual const char* get_custom_terrain_directory() const { return nullptr; }
|
||||||
|
|
Loading…
Reference in New Issue