diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index 03bd5d5dae..d858e3a908 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -498,6 +498,9 @@ void Scheduler::expect_delay_ms(uint32_t ms) } else { expect_delay_start = AP_HAL::millis(); expect_delay_length = ms; + + // also put our priority below timer thread if we are boosted + boost_end(); } }