mirror of https://github.com/ArduPilot/ardupilot
AP_HAL_ChibiOS: error if system clock not 1mhz on 16 CH_CFG_ST_RESOLUTION. prevent variable overflow
if CH_CFG_ST_FREQUENCY not match 1000000U on 16 bit CH_CFG_ST_RESOLUTION we try to multiply now *= 1000000U/CH_CFG_ST_FREQUENCY; it may overflow 16 bit value.
This commit is contained in:
parent
f882bd0c3e
commit
3ab1b29397
|
@ -46,7 +46,7 @@ static uint32_t system_time_u32_us(void)
|
|||
{
|
||||
systime_t now = chVTGetSystemTimeX();
|
||||
#if CH_CFG_ST_FREQUENCY != 1000000U
|
||||
now *= 1000000U/CH_CFG_ST_FREQUENCY;
|
||||
#error "must use 32 bit timer if system clock not 1MHz"
|
||||
#endif
|
||||
static systime_t last_systime;
|
||||
static uint32_t timer_base_us32;
|
||||
|
|
Loading…
Reference in New Issue