HAL_ChibiOS: change to 2s timeout on watchdog

a bit more of a safety net against false positives for stable release
This commit is contained in:
Andrew Tridgell 2019-04-20 09:29:01 +10:00
parent 5a34470256
commit 54cbf8ea9e
2 changed files with 3 additions and 3 deletions

View File

@ -231,7 +231,7 @@ static void main_loop()
static bool done_pause; static bool done_pause;
if (!done_pause && AP_HAL::millis() > 20000) { if (!done_pause && AP_HAL::millis() > 20000) {
done_pause = true; done_pause = true;
while (AP_HAL::millis() < 22000) ; while (AP_HAL::millis() < 22200) ;
} }
#endif #endif

View File

@ -59,9 +59,9 @@ static bool watchdog_enabled;
*/ */
void stm32_watchdog_init(void) void stm32_watchdog_init(void)
{ {
// setup for 1s reset // setup for 2s reset
IWDGD.KR = 0x5555; IWDGD.KR = 0x5555;
IWDGD.PR = 8; IWDGD.PR = 16;
IWDGD.RLR = 0xFFF; IWDGD.RLR = 0xFFF;
IWDGD.KR = 0xCCCC; IWDGD.KR = 0xCCCC;
watchdog_enabled = true; watchdog_enabled = true;