mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-09 09:28:31 -04:00
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:
parent
5a34470256
commit
54cbf8ea9e
@ -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
|
||||||
|
|
||||||
|
@ -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;
|
||||||
|
Loading…
Reference in New Issue
Block a user