Browse Source

HAL_ChibiOS: use a 16 bit sysinterval_t on 16 bit timers

prevent mixed size subtraction errors
gps-1.3.1
Andrew Tridgell 3 years ago
parent
commit
f1ea4f5d01
  1. 2
      libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h
  2. 1
      libraries/AP_HAL_ChibiOS/system.cpp

2
libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h

@ -99,7 +99,7 @@ extern "C" { @@ -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
/**

1
libraries/AP_HAL_ChibiOS/system.cpp

@ -33,6 +33,7 @@ static_assert(sizeof(systime_t) == 2, "expected 16 bit systime_t"); @@ -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…
Cancel
Save