From 4e6ac850573b99523e36e4d12a3709498cd90ba8 Mon Sep 17 00:00:00 2001 From: Andrew Tridgell Date: Fri, 3 Aug 2018 09:35:58 +1000 Subject: [PATCH] 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. --- libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h | 4 +++- libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py | 2 ++ 2 files changed, 5 insertions(+), 1 deletion(-) diff --git a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h index c0bb580be3..ff5c74915e 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h +++ b/libraries/AP_HAL_ChibiOS/hwdef/common/chconf.h @@ -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 @@ * @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 /** @} */ diff --git a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py index 080399d87b..c46fb424b1 100644 --- a/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py +++ b/libraries/AP_HAL_ChibiOS/hwdef/scripts/chibios_hwdef.py @@ -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 ''')