diff --git a/libraries/AP_HAL_ChibiOS/Scheduler.cpp b/libraries/AP_HAL_ChibiOS/Scheduler.cpp index ec5246ae162e4..c03b89b0e79af 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 37e19c21c6b03..966e05ecb81f8 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 /*