this fixes a watchdog issue on AP_Periph if we don't have a timer thread
@ -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--;