mirror of https://github.com/ArduPilot/ardupilot
HAL_ChibiOS: use a 16 bit sysinterval_t on 16 bit timers
prevent mixed size subtraction errors
This commit is contained in:
parent
8c0a6e0b3e
commit
5e4de872ac
|
@ -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
|
||||
|
||||
/**
|
||||
|
|
|
@ -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
|
||||
|
|
Loading…
Reference in New Issue