mirror of https://github.com/ArduPilot/ardupilot
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:
parent
2be23fff2b
commit
2aef3364bc
|
@ -259,7 +259,12 @@ void panic(const char *errormsg, ...)
|
|||
|
||||
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();
|
||||
#endif
|
||||
}
|
||||
|
||||
uint32_t millis()
|
||||
|
|
Loading…
Reference in New Issue