mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-23 17:18:28 -04:00
AP_Bootloader: use fast boot after watchdog reset
This commit is contained in:
parent
098b37b69f
commit
6f8a873b14
@ -27,6 +27,7 @@
|
|||||||
#include "hwdef.h"
|
#include "hwdef.h"
|
||||||
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
#include <AP_HAL_ChibiOS/hwdef/common/usbcfg.h>
|
||||||
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
|
#include <AP_HAL_ChibiOS/hwdef/common/stm32_util.h>
|
||||||
|
#include <AP_HAL_ChibiOS/hwdef/common/watchdog.h>
|
||||||
#include "support.h"
|
#include "support.h"
|
||||||
#include "bl_protocol.h"
|
#include "bl_protocol.h"
|
||||||
|
|
||||||
@ -53,7 +54,10 @@ int main(void)
|
|||||||
uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;
|
uint32_t timeout = HAL_BOOTLOADER_TIMEOUT;
|
||||||
|
|
||||||
enum rtc_boot_magic m = check_fast_reboot();
|
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;
|
timeout = 0;
|
||||||
} else if (m == RTC_BOOT_FAST) {
|
} else if (m == RTC_BOOT_FAST) {
|
||||||
try_boot = true;
|
try_boot = true;
|
||||||
|
Loading…
Reference in New Issue
Block a user