mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: fixed watchdog timeout setting
This commit is contained in:
parent
756a629b24
commit
3222084f2d
|
@ -63,7 +63,7 @@ void stm32_watchdog_init(void)
|
|||
{
|
||||
// setup for 2s reset
|
||||
IWDGD.KR = 0x5555;
|
||||
IWDGD.PR = 16;
|
||||
IWDGD.PR = 2; // div16
|
||||
IWDGD.RLR = 0xFFF;
|
||||
IWDGD.KR = 0xCCCC;
|
||||
watchdog_enabled = true;
|
||||
|
|
Loading…
Reference in New Issue