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
This commit is contained in:
Andrew Tridgell 2021-08-22 19:35:07 +10:00
parent e7e3b478fc
commit 957740db4f
2 changed files with 2 additions and 2 deletions

View File

@ -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
}
/*

View File

@ -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
/*