AP_HAL_ChibiOS: use minimize_features.inc for HAL_WITH_DSP

This commit is contained in:
Peter Barker 2022-06-27 17:07:48 +10:00 committed by Peter Barker
parent bbbb8bcc2c
commit bb1c3d6545
13 changed files with 28 additions and 11 deletions

View File

@ -154,7 +154,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font0.bin
define STM32_PWM_USE_ADVANCED TRUE
# FFT option (disabled by default)
# define HAL_WITH_DSP 1
# define HAL_GYROFFT_ENABLED 1
# define AC_OAPATHPLANNER_ENABLED 0
# EK2 options (disabled by default)

View File

@ -152,7 +152,7 @@ ROMFS_WILDCARD libraries/AP_OSD/fonts/font*.bin
# -------reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0
# --------------------- save flash ----------------------
define AP_BATTMON_SMBUS_ENABLE 0

View File

@ -175,7 +175,7 @@ define HAL_DEFAULT_AIRSPEED_PIN 10
# -------reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0
# --------------------- save flash ----------------------
# save some flash

View File

@ -191,7 +191,7 @@ define HAL_SPRAYER_ENABLED 0
# reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0
# save some flash
include ../include/save_some_flash.inc

View File

@ -119,7 +119,7 @@ define HAL_I2C_INTERNAL_MASK 0
define GPS_MAX_RECEIVERS 1
define GPS_MAX_INSTANCES 1
define HAL_COMPASS_MAX_SENSORS 1
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0

View File

@ -23,4 +23,4 @@ define LANDING_GEAR_ENABLED 0
define HAL_MSP_OPTICALFLOW_ENABLED 0
define HAL_SUPPORT_RCOUT_SERIAL 0
define HAL_HOTT_TELEM_ENABLED 0
# define HAL_WITH_DSP 0
# define HAL_GYROFFT_ENABLED 0

View File

@ -20,3 +20,6 @@ define HAL_SPRAYER_ENABLED 0
# RunCam control isn't available on smaller boards
define HAL_RUNCAM_ENABLED 0
# disable use of onboard FFT library:
define HAL_GYROFFT_ENABLED 0

View File

@ -137,4 +137,3 @@ IOMCU_FW 1
MAIN_STACK 0x200
PROCESS_STACK 0x250
define HAL_DISABLE_LOOP_DELAY
define HAL_WITH_DSP FALSE

View File

@ -137,4 +137,3 @@ IOMCU_FW 1
MAIN_STACK 0x200
PROCESS_STACK 0x250
define HAL_DISABLE_LOOP_DELAY
define HAL_WITH_DSP FALSE

View File

@ -152,4 +152,4 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0

View File

@ -28,7 +28,7 @@ define HAL_SPRAYER_ENABLED 0
# reduce max size of embedded params for apj_tool.py
define AP_PARAM_MAX_EMBEDDED_PARAM 1024
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0
# save some flash
include ../include/save_some_flash.inc

View File

@ -130,5 +130,5 @@ SPIDEV dataflash SPI3 DEVID1 FLASH_CS MODE3 32*MHZ 32*MHZ
# enable logging to dataflash
define HAL_LOGGING_DATAFLASH_ENABLED 1
define HAL_WITH_DSP FALSE
define HAL_GYROFFT_ENABLED 0

View File

@ -2927,6 +2927,11 @@ def add_apperiph_defaults(f):
// no CAN manager in AP_Periph:
#define HAL_CANMANAGER_ENABLED 0
// Periphs don't use the FFT library:
#ifndef HAL_GYROFFT_ENABLED
#define HAL_GYROFFT_ENABLED 0
#endif
''')
def add_bootloader_defaults(f):
@ -2939,6 +2944,11 @@ def add_bootloader_defaults(f):
// AP_Bootloader defaults
#define HAL_DSHOT_ALARM_ENABLED 0
// bootloaders *definitely* don't use the FFT library:
#ifndef HAL_GYROFFT_ENABLED
#define HAL_GYROFFT_ENABLED 0
#endif
''')
def add_iomcu_firmware_defaults(f):
@ -2952,6 +2962,11 @@ def add_iomcu_firmware_defaults(f):
// IOMCU Firmware defaults
#define HAL_DSHOT_ALARM_ENABLED 0
// IOMCUs *definitely* don't use the FFT library:
#ifndef HAL_GYROFFT_ENABLED
#define HAL_GYROFFT_ENABLED 0
#endif
''')
def add_normal_firmware_defaults(f):
@ -2973,6 +2988,7 @@ def add_normal_firmware_defaults(f):
#ifndef HAL_DSHOT_ALARM_ENABLED
#define HAL_DSHOT_ALARM_ENABLED (HAL_PWM_COUNT>0)
#endif
''')
# process input file