diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h index 966e05ecb8..195b0e521e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h @@ -99,7 +99,7 @@ extern "C" { * @note Allowed values are 16, 32 or 64 bits. */ #if !defined(CH_CFG_INTERVALS_SIZE) -#define CH_CFG_INTERVALS_SIZE 32 +#define CH_CFG_INTERVALS_SIZE CH_CFG_ST_RESOLUTION #endif /** diff --git a/libraries/AP_HAL_ChibiOS/system.cpp b/libraries/AP_HAL_ChibiOS/system.cpp index 2bd587fed7..178ca2da3b 100644 --- a/libraries/AP_HAL_ChibiOS/system.cpp +++ b/libraries/AP_HAL_ChibiOS/system.cpp @@ -33,6 +33,7 @@ static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t"); #elif CH_CFG_ST_RESOLUTION == 32 static_assert(sizeof(systime_t) == 4, "expected 32 bit systime_t"); #endif +static_assert(sizeof(systime_t) == sizeof(sysinterval_t), "expected systime_t same size as sysinterval_t"); #if defined(HAL_EXPECTED_SYSCLOCK) #ifdef STM32_SYS_CK