Browse Source

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
master
Andrew Tridgell 5 years ago
parent
commit
6b841e781c
  1. 4
      libraries/AP_HAL_ChibiOS/Scheduler.cpp

4
libraries/AP_HAL_ChibiOS/Scheduler.cpp

@ -543,6 +543,10 @@ void Scheduler::expect_delay_ms(uint32_t ms) @@ -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…
Cancel
Save