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:
Andrew Tridgell 2019-10-21 09:10:27 +11:00
parent e848d5d0cc
commit fd239825be

View File

@ -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--;