Browse Source

HAL_ChibiOS: use 32 bit time intervals

this makes for smaller and faster code. We really don't need 64 bit
intervals as long sleeps are done with a loop.
master
Andrew Tridgell 7 years ago
parent
commit
4e6ac85057
  1. 4
      libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h
  2. 2
      libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

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

@ -66,7 +66,7 @@ @@ -66,7 +66,7 @@
* @brief Time intervals data size.
* @note Allowed values are 16, 32 or 64 bits.
*/
#define CH_CFG_INTERVALS_SIZE 64
#define CH_CFG_INTERVALS_SIZE 32
/**
* @brief Time types data size.
@ -159,7 +159,9 @@ @@ -159,7 +159,9 @@
* @note This is not related to the compiler optimization options.
* @note The default is @p TRUE.
*/
#ifndef CH_CFG_OPTIMIZE_SPEED
#define CH_CFG_OPTIMIZE_SPEED TRUE
#endif
/** @} */

2
libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py

@ -454,10 +454,12 @@ def write_mcu_config(f): @@ -454,10 +454,12 @@ def write_mcu_config(f):
#define CH_CFG_USE_MUTEXES FALSE
#define CH_CFG_USE_CONDVARS FALSE
#define CH_CFG_USE_CONDVARS_TIMEOUT FALSE
#define CH_CFG_USE_EVENTS FALSE
#define CH_CFG_USE_EVENTS_TIMEOUT FALSE
#define CH_CFG_USE_MESSAGES FALSE
#define CH_CFG_USE_MAILBOXES FALSE
#define CH_CFG_USE_FACTORY FALSE
#define CH_CFG_USE_MEMCORE FALSE
#define HAL_USE_I2C FALSE
#define HAL_USE_PWM FALSE
''')

Loading…
Cancel
Save