mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-11 02:18:29 -04:00
HAL_ChibiOS: pat watchdog immediately in expect_delay_ms()
this fixes a watchdog issue on AP_Periph if we don't have a timer thread
This commit is contained in:
parent
e848d5d0cc
commit
fd239825be
@ -543,6 +543,10 @@ void Scheduler::expect_delay_ms(uint32_t ms)
|
||||
// only for main thread
|
||||
return;
|
||||
}
|
||||
|
||||
// pat once immediately
|
||||
watchdog_pat();
|
||||
|
||||
if (ms == 0) {
|
||||
if (expect_delay_nesting > 0) {
|
||||
expect_delay_nesting--;
|
||||
|
Loading…
Reference in New Issue
Block a user