AP_HAL: add util method boot_to_dfu()

This commit is contained in:
bugobliterator 2022-08-16 08:41:54 +05:30 committed by Andrew Tridgell
parent c70643f0e7
commit 441ce2e593

View File

@ -81,6 +81,7 @@ public:
int8_t scheduler_task; int8_t scheduler_task;
bool armed; // true if vehicle was armed bool armed; // true if vehicle was armed
enum safety_state safety_state; enum safety_state safety_state;
bool boot_to_dfu; // true if we should reboot to DFU on boot
}; };
struct PersistentData persistent_data; struct PersistentData persistent_data;
// last_persistent_data is only filled in if we've suffered a watchdog reset // last_persistent_data is only filled in if we've suffered a watchdog reset
@ -201,6 +202,9 @@ public:
virtual void* last_crash_dump_ptr() const { return nullptr; } virtual void* last_crash_dump_ptr() const { return nullptr; }
#endif #endif
#if HAL_ENABLE_DFU_BOOT
virtual void boot_to_dfu(void) {}
#endif
protected: protected:
// we start soft_armed false, so that actuators don't send any // we start soft_armed false, so that actuators don't send any
// values until the vehicle code has fully started // values until the vehicle code has fully started