HAL_ChibiOS: optimisation for AP_HAL::micros() on systems with 32 bit timers

most ChibiOS boards have a 32 bit timer. This optimisation reduces the
cost of micros() from 0.3us to 0.06us, which is significant in
interrupt handlers and for accurate timing. It takes advantage of the
timer being 32 bit with 1MHz clock
This commit is contained in:
Andrew Tridgell 2021-10-02 14:55:20 +10:00
parent 2be23fff2b
commit 2aef3364bc
1 changed files with 5 additions and 0 deletions

View File

@ -259,7 +259,12 @@ void panic(const char *errormsg, ...)
uint32_t micros() uint32_t micros()
{ {
#if CH_CFG_ST_RESOLUTION == 32 && CH_CFG_ST_FREQUENCY==1000000U
// special case optimisation for 32 bit timers
return st_lld_get_counter();
#else
return hrt_micros32(); return hrt_micros32();
#endif
} }
uint32_t millis() uint32_t millis()