From 6f8a873b1457a63980d4c3fb165d9520b28305f3 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Thu, 11 Apr 2019 21:14:38 +1000 Subject: [PATCH] AP_Bootloader: use fast boot after watchdog reset --- Tools/AP_Bootloader/AP_Bootloader.cpp | 6 +++++- 1 file changed, 5 insertions(+), 1 deletion(-) diff --git a/Tools/AP_Bootloader/AP_Bootloader.cpp b/Tools/AP_Bootloader/AP_Bootloader.cpp index 417a39ced1..966d0f09f1 100644 --- a/Tools/AP_Bootloader/AP_Bootloader.cpp +++ b/Tools/AP_Bootloader/AP_Bootloader.cpp @@ -27,6 +27,7 @@ #include "hwdef.h" #include #include +#include #include "support.h" #include "bl_protocol.h" @@ -53,7 +54,10 @@ int main(void) uint32_t timeout = HAL_BOOTLOADER_TIMEOUT; enum rtc_boot_magic m = check_fast_reboot(); - if (m == RTC_BOOT_HOLD) { + if (stm32_was_watchdog_reset()) { + try_boot = true; + timeout = 0; + } else if (m == RTC_BOOT_HOLD) { timeout = 0; } else if (m == RTC_BOOT_FAST) { try_boot = true;