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.
This commit is contained in:
Andrew Tridgell 2018-08-03 09:35:58 +10:00
parent 1bd0ea079b
commit 4e6ac85057
2 changed files with 5 additions and 1 deletions

View File

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

View File

@ -454,10 +454,12 @@ def write_mcu_config(f):
#define CH_CFG_USE_MUTEXES FALSE #define CH_CFG_USE_MUTEXES FALSE
#define CH_CFG_USE_CONDVARS FALSE #define CH_CFG_USE_CONDVARS FALSE
#define CH_CFG_USE_CONDVARS_TIMEOUT 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_EVENTS_TIMEOUT FALSE
#define CH_CFG_USE_MESSAGES FALSE #define CH_CFG_USE_MESSAGES FALSE
#define CH_CFG_USE_MAILBOXES FALSE #define CH_CFG_USE_MAILBOXES FALSE
#define CH_CFG_USE_FACTORY FALSE #define CH_CFG_USE_FACTORY FALSE
#define CH_CFG_USE_MEMCORE FALSE
#define HAL_USE_I2C FALSE #define HAL_USE_I2C FALSE
#define HAL_USE_PWM FALSE #define HAL_USE_PWM FALSE
''') ''')