From 957740db4fe83a32203606820c3982ca01b915f6 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Sun, 22 Aug 2021 19:35:07 +1000 Subject: [PATCH] HAL_ChibiOS: switch to minimum scheduling delta of 10us this avoids an issue with the ChibiOS 20.3 virtual timer implementation that can result in a scheduling slip equal to the system timer period. Andy has been suggesting this change for a while. I resisted it as I thought it would impact on soft-serial parsing, but it turns out it doesn't. Fixes issue #18383 --- libraries/AP_HAL_ChibiOS/Scheduler.cpp | 2 +- libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index ec5246ae16..c03b89b0e7 100644 --- a/libraries/AP_HAL_ChibiOS/Scheduler.cpp +++ b/libraries/AP_HAL_ChibiOS/Scheduler.cpp @@ -142,7 +142,7 @@ void Scheduler::delay_microseconds(uint16_t usec) // calling with ticks == 0 causes a hard fault on ChibiOS ticks = 1; } - chThdSleep(ticks); //Suspends Thread for desired microseconds + chThdSleep(MAX(ticks,CH_CFG_ST_TIMEDELTA)); //Suspends Thread for desired microseconds } /* diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h index 37e19c21c6..966e05ecb8 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h @@ -119,7 +119,7 @@ extern "C" { * this value. */ #ifndef CH_CFG_ST_TIMEDELTA -#define CH_CFG_ST_TIMEDELTA 2 +#define CH_CFG_ST_TIMEDELTA 10 #endif /*