From 54cbf8ea9ea30b7a9a4f9a05a414a554e5cae64d Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sat, 20 Apr 2019 09:29:01 +1000 Subject: [PATCH] HAL_ChibiOS: change to 2s timeout on watchdog a bit more of a safety net against false positives for stable release --- libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp | 2 +- libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c | 4 ++-- 2 files changed, 3 insertions(+), 3 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp index 53786048f7..6949c013a3 100644 --- a/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp +++ b/libraries/AP_HAL_ChibiOS/HAL_ChibiOS_Class.cpp @@ -231,7 +231,7 @@ static void main_loop() static bool done_pause; if (!done_pause && AP_HAL::millis() > 20000) { done_pause = true; - while (AP_HAL::millis() < 22000) ; + while (AP_HAL::millis() < 22200) ; } #endif diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c index 96e341ce2b..8dd7918e64 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/watchdog.c @@ -59,9 +59,9 @@ static bool watchdog_enabled; */ void stm32_watchdog_init(void) { - // setup for 1s reset + // setup for 2s reset IWDGD.KR = 0x5555; - IWDGD.PR = 8; + IWDGD.PR = 16; IWDGD.RLR = 0xFFF; IWDGD.KR = 0xCCCC; watchdog_enabled = true;