mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: support wider range of clock frequencies
This commit is contained in:
parent
cfed364dd0
commit
f732a482fe
|
@ -41,16 +41,12 @@
|
||||||
for micros64()
|
for micros64()
|
||||||
*/
|
*/
|
||||||
|
|
||||||
#if CH_CFG_ST_FREQUENCY != 1000000U && CH_CFG_ST_FREQUENCY != 1000U
|
|
||||||
#error "unsupported tick frequency"
|
|
||||||
#endif
|
|
||||||
|
|
||||||
#if CH_CFG_ST_RESOLUTION == 16
|
#if CH_CFG_ST_RESOLUTION == 16
|
||||||
static uint32_t system_time_u32_us(void)
|
static uint32_t system_time_u32_us(void)
|
||||||
{
|
{
|
||||||
systime_t now = chVTGetSystemTimeX();
|
systime_t now = chVTGetSystemTimeX();
|
||||||
#if CH_CFG_ST_FREQUENCY == 1000U
|
#if CH_CFG_ST_FREQUENCY != 1000000U
|
||||||
now *= 1000U;
|
now *= 1000000U/CH_CFG_ST_FREQUENCY;
|
||||||
#endif
|
#endif
|
||||||
static systime_t last_systime;
|
static systime_t last_systime;
|
||||||
static uint32_t timer_base_us32;
|
static uint32_t timer_base_us32;
|
||||||
|
@ -63,8 +59,8 @@ static uint32_t system_time_u32_us(void)
|
||||||
static uint32_t system_time_u32_us(void)
|
static uint32_t system_time_u32_us(void)
|
||||||
{
|
{
|
||||||
systime_t now = chVTGetSystemTimeX();
|
systime_t now = chVTGetSystemTimeX();
|
||||||
#if CH_CFG_ST_FREQUENCY == 1000U
|
#if CH_CFG_ST_FREQUENCY != 1000000U
|
||||||
now *= 1000U;
|
now *= 1000000U/CH_CFG_ST_FREQUENCY;
|
||||||
#endif
|
#endif
|
||||||
return now;
|
return now;
|
||||||
}
|
}
|
||||||
|
|
Loading…
Reference in New Issue