From 6b841e781c2c63c875de1200503e6acdbc2e3a21 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Mon, 21 Oct 2019 09:10:27 +1100 Subject: [PATCH] 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 --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 2468cccaa0..90d7007482 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -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--;