atbetaflight/make/source.mk

413 lines
14 KiB
Makefile
Raw Normal View History

COMMON_SRC = \
build/build_config.c \
build/debug.c \
build/version.c \
$(TARGET_DIR_SRC) \
main.c \
$(addprefix pg/,$(notdir $(wildcard $(SRC_DIR)/pg/*.c))) \
$(addprefix common/,$(notdir $(wildcard $(SRC_DIR)/common/*.c))) \
$(addprefix config/,$(notdir $(wildcard $(SRC_DIR)/config/*.c))) \
cli/cli.c \
cli/settings.c \
drivers/adc.c \
drivers/buf_writer.c \
drivers/bus.c \
drivers/bus_i2c_config.c \
drivers/bus_i2c_busdev.c \
drivers/bus_i2c_soft.c \
[H7] System and build files Basic system files - Initial system files - Additional RCC clock enables for testing - Coding style tidy (target/system_stm32h7xx.c) and enable MCO for testing - Clock generator changes for SPI support - Setup MPU for "D2 SRAM as write-through by MPU, call it DMA_RAM" - Drop USB clock enabling from driver/system_stm32h7xx.c - stm32h7_hal_conf.h for persistent object storage Basic build files STM32H7.mk changes - STM32H7.mk for USE_UART and USE_SERIAL_RX - Modify STM32H7.mk for inclusion of SPI driver - STM32H7.mk change for D2 SRAM as write-through by MPU, call it DMA_RAM - STM32H7.mk for DMA facility - STM32H7.mk for [TIMER] For "Initial cut without Dshot" - STM32H7.mk change for [LED_STRIP] Add LED_STRIP - STM32H7.mk for [ADC] Initial cut without internal sensors - STM32H7.mk for Enable I2C (HAL) - STM32H7.mk for "Enable HAL-based DShot (no burst yet)" - STM32H7.mk change for transponder - STM32H750 - Add platform support. - STM32H750 - Add H750 MCU ID. - STM32H743 - Add MCU ID. STM32H7.mk change for "Burst Dshot First working version" Fix boot loader request STM32H750 - Add PERSISTENT memory support. STM32H743 - Add PERSISTENT memory support. Use PERSISTENT memory for bootloader request. Using DTCM RAM did not work on H750. Change flash latency from 4WS to 2WS STM32H750 - Fix reset of RCC_CR to reset value. Note: The comment above the code didn't match code. STM32H750 - Remove duplicate startup code, see SystemClock_Config. STM32H7.mk changes for Port RTC backup register based persistent storage for H7 Make use of persistent object facility Force reboot after possible boot loader activity Enable CRS stm32h7xx_hal_conf.h for H7 - QuadSPI support stm32h7xx_hal_conf.h for STM32H7 - SDCard/SDIO using HAL Driver stm32h7xx_hal_conf.h : Fix systick to be 0x00 instead of ST's default 0x0F. This fixes the ability to use HAL_Delay() from an ISR, as required by the ST's USB Library. Specifically, systick handler must be a higher priority than the USB FS/HS Interrupt handler priorities. stm32h7xx_hal_conf.h for Add PID-Audio support source.mk for H7 - QuadSPI support drivers/system_stm32h7xx.c for H7 - QuadSPI support STM32H7.mk for H7 - QuadSPI support STM32H7.mk change for CDC-HID support common_pre.h updates - Scheduler parameters to same as F4 & F7 - Enable some important default features - STM32H7 - Enable ITCM RAM. Requires voltage scaling fix from commit 6e684c609310024141c43de484a5e78103140e3c STM32H750 - Disable caches before reboot. Prior to this when EEPROM_IN_RAM was used the persistent data section would have corruption immediately after a reboot, prior to even the Reset_Handler code having been executed. drivers/system_stm32h7xx.c Touch-up after 2019-02-02 rebase STM32H7 - Write protect ITCM ram. Remove local defs for RESET_xxx symbols STM32H750 - EXST firmware reboots to FLASH bootloader, rather than ROM bootloader. STM32H750 - Disable some MCO/clock testing code as the pins interfere with new targets. STM32H750 - Don't disable data caches after bootloader. Observed that disabling dcache after cold boot with BOOT pin high causes segfault. drivers/system_stm32h7xx.c for STM32H7 - SDCard/SDIO using HAL Driver drivers/system_stm32h7xx.c change for Move SDMMC clock init into SDIO driver drivers/system_stm32h7xx.c: Cleanup some Clock/MCO/GPIO initialisation code. drivers/system_stm32h7xx.c for Reset if systick is stuck. STM32H7 - Fix missing CPU voltage scaling. It appears this was the cause of other seemingly random issues: * Crash soon after enabling USB. * Flash write failures. * Random un-explainable crashes. Change RCC_HSE_BYPASS to RCC_HSE_ON Even Nucleo-H743 seems to work without setting HSE_BYPASS. STM32H7xx - Move memory section initialisation earlier into the init sequence. Allows startup-code/libs/etc to be moved into different memory regions. Don't touch vector table in EXST targets STM32H750_EXST - fix boot loop target/system_stm32h7xx.c for STM32H7 - SDCard/SDIO using HAL Driver target/system_stm32h7xx.c change for Fix SD card clock speed selection STM32H750_EXST - Reset MPU regions on boot. * Failure to reset regions will result in mem-fault if bootloader has configured a similar region. STM32H750 - Fix missing include of platform.h in system_stm32h7xx.c This caused the SDMMC peripheral clock to be un-configured (at reset state) when USE_SDCARD_SDIO was defined. Change MPU region number for DMA_RAM from 0 to 1 Avoid conflict with ITCM-RAM write protection. STM32H7xx - HSERDY slow/stuck workarounds. STM32H7xx - Fix region MPU number for SDIO. * It was overwriting the previous region causing LED strip and transponder issues. Target/system_stmh7xx.c for Reset if systick is stuck. startup/system_stm32h7xx.c change for non-caching DMA_RAM H750 - Use SIZE optimization by default due to limited flash space. STM32H7.mk for STM32H7 - SDCard/SDIO using HAL Driver STM32H7.mk updates - Decrease HSE_STARTUP_TIMEOUT to 1 second * default is 5 seconds, which is too long when HSE gets stuck. - Add PID-Audio support Temporary override LINKER_DIR
2019-05-04 07:07:45 -07:00
drivers/bus_quadspi.c \
drivers/bus_spi.c \
drivers/bus_spi_config.c \
drivers/bus_spi_pinconfig.c \
drivers/buttons.c \
drivers/display.c \
2018-10-17 23:05:09 -07:00
drivers/dma_reqmap.c \
drivers/exti.c \
drivers/io.c \
drivers/light_led.c \
drivers/mco.c \
2018-02-02 01:39:56 -08:00
drivers/pinio.c \
drivers/resource.c \
drivers/rcc.c \
drivers/serial.c \
drivers/serial_pinconfig.c \
drivers/serial_uart.c \
drivers/serial_uart_pinconfig.c \
drivers/sound_beeper.c \
drivers/stack_check.c \
drivers/system.c \
drivers/timer_common.c \
drivers/timer.c \
drivers/transponder_ir_arcitimer.c \
drivers/transponder_ir_ilap.c \
drivers/transponder_ir_erlt.c \
2018-05-26 23:54:38 -07:00
fc/board_info.c \
fc/config.c \
fc/dispatch.c \
fc/hardfaults.c \
fc/tasks.c \
fc/runtime_config.c \
fc/stats.c \
io/beeper.c \
2018-02-02 18:18:18 -08:00
io/piniobox.c \
io/serial.c \
io/smartaudio_protocol.c \
io/statusindicator.c \
io/tramp_protocol.c \
io/transponder_ir.c \
io/usb_cdc_hid.c \
2018-07-14 23:48:12 -07:00
io/usb_msc.c \
msp/msp.c \
msp/msp_box.c \
msp/msp_serial.c \
scheduler/scheduler.c \
sensors/adcinternal.c \
sensors/battery.c \
sensors/current.c \
sensors/voltage.c \
2018-08-07 12:33:32 -07:00
target/config_helper.c \
fc/init.c \
fc/controlrate_profile.c \
drivers/camera_control.c \
drivers/accgyro/gyro_sync.c \
drivers/pwm_esc_detect.c \
drivers/pwm_output.c \
2017-12-23 15:10:19 -08:00
drivers/rx/rx_spi.c \
drivers/rx/rx_xn297.c \
drivers/rx/rx_pwm.c \
drivers/serial_softserial.c \
fc/core.c \
fc/rc.c \
fc/rc_adjustments.c \
fc/rc_controls.c \
fc/rc_modes.c \
flight/position.c \
flight/failsafe.c \
2018-05-15 14:32:03 -07:00
flight/gps_rescue.c \
2019-05-05 04:23:18 -07:00
flight/gyroanalyse.c \
flight/imu.c \
flight/mixer.c \
2017-12-31 07:40:35 -08:00
flight/mixer_tricopter.c \
flight/pid.c \
2019-05-05 04:23:18 -07:00
flight/rpm_filter.c \
flight/servos.c \
2017-12-31 07:40:35 -08:00
flight/servos_tricopter.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
rx/ibus.c \
rx/jetiexbus.c \
rx/msp.c \
rx/pwm.c \
rx/rx.c \
rx/rx_spi.c \
rx/rx_spi_common.c \
rx/crsf.c \
rx/sbus.c \
rx/sbus_channels.c \
rx/spektrum.c \
io/spektrum_vtx_control.c \
io/spektrum_rssi.c \
rx/sumd.c \
rx/sumh.c \
rx/xbus.c \
rx/fport.c \
sensors/acceleration.c \
sensors/boardalignment.c \
sensors/compass.c \
sensors/gyro.c \
sensors/initialisation.c \
blackbox/blackbox.c \
blackbox/blackbox_encoding.c \
blackbox/blackbox_io.c \
cms/cms.c \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
2019-03-23 10:13:02 -07:00
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \
cms/cms_menu_osd.c \
cms/cms_menu_power.c \
cms/cms_menu_saveexit.c \
cms/cms_menu_vtx_rtc6705.c \
cms/cms_menu_vtx_smartaudio.c \
cms/cms_menu_vtx_tramp.c \
drivers/display_ug2864hsweg01.c \
drivers/light_ws2811strip.c \
2017-12-14 06:44:22 -08:00
drivers/rangefinder/rangefinder_hcsr04.c \
2017-12-15 22:09:58 -08:00
drivers/rangefinder/rangefinder_lidartf.c \
drivers/serial_escserial.c \
drivers/vtx_common.c \
2018-12-19 06:08:24 -08:00
drivers/vtx_table.c \
io/dashboard.c \
io/displayport_max7456.c \
io/displayport_msp.c \
io/displayport_oled.c \
io/displayport_srxl.c \
io/displayport_crsf.c \
2018-06-21 07:11:28 -07:00
io/displayport_hott.c \
io/rcdevice_cam.c \
io/rcdevice.c \
io/gps.c \
io/ledstrip.c \
io/pidaudio.c \
osd/osd.c \
osd/osd_elements.c \
sensors/barometer.c \
2017-12-14 06:44:22 -08:00
sensors/rangefinder.c \
telemetry/telemetry.c \
telemetry/crsf.c \
telemetry/srxl.c \
telemetry/frsky_hub.c \
telemetry/hott.c \
telemetry/jetiexbus.c \
telemetry/smartport.c \
telemetry/ltm.c \
telemetry/mavlink.c \
telemetry/msp_shared.c \
telemetry/ibus.c \
telemetry/ibus_shared.c \
sensors/esc_sensor.c \
io/vtx_string.c \
io/vtx.c \
io/vtx_rtc6705.c \
io/vtx_smartaudio.c \
io/vtx_tramp.c \
io/vtx_control.c
COMMON_DEVICE_SRC = \
$(CMSIS_SRC) \
$(DEVICE_STDPERIPH_SRC)
2018-08-07 12:33:32 -07:00
COMMON_SRC := $(COMMON_SRC) $(COMMON_DEVICE_SRC)
ifeq ($(SIMULATOR_BUILD),yes)
TARGET_FLAGS := -DSIMULATOR_BUILD $(TARGET_FLAGS)
endif
SPEED_OPTIMISED_SRC := ""
SIZE_OPTIMISED_SRC := ""
ifneq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS)))
SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
common/encoding.c \
common/filter.c \
common/maths.c \
common/typeconversion.c \
drivers/accgyro/accgyro_fake.c \
drivers/accgyro/accgyro_mpu.c \
drivers/accgyro/accgyro_mpu3050.c \
drivers/accgyro/accgyro_mpu6050.c \
drivers/accgyro/accgyro_mpu6500.c \
drivers/accgyro/accgyro_spi_bmi160.c \
drivers/accgyro/accgyro_spi_icm20689.c \
drivers/accgyro/accgyro_spi_mpu6000.c \
drivers/accgyro/accgyro_spi_mpu6500.c \
drivers/accgyro/accgyro_spi_mpu9250.c \
drivers/accgyro_legacy/accgyro_adxl345.c \
drivers/accgyro_legacy/accgyro_bma280.c \
drivers/accgyro_legacy/accgyro_l3g4200d.c \
drivers/accgyro_legacy/accgyro_l3gd20.c \
drivers/accgyro_legacy/accgyro_lsm303dlhc.c \
drivers/accgyro_legacy/accgyro_mma845x.c \
drivers/adc.c \
drivers/buf_writer.c \
drivers/bus.c \
[H7] System and build files Basic system files - Initial system files - Additional RCC clock enables for testing - Coding style tidy (target/system_stm32h7xx.c) and enable MCO for testing - Clock generator changes for SPI support - Setup MPU for "D2 SRAM as write-through by MPU, call it DMA_RAM" - Drop USB clock enabling from driver/system_stm32h7xx.c - stm32h7_hal_conf.h for persistent object storage Basic build files STM32H7.mk changes - STM32H7.mk for USE_UART and USE_SERIAL_RX - Modify STM32H7.mk for inclusion of SPI driver - STM32H7.mk change for D2 SRAM as write-through by MPU, call it DMA_RAM - STM32H7.mk for DMA facility - STM32H7.mk for [TIMER] For "Initial cut without Dshot" - STM32H7.mk change for [LED_STRIP] Add LED_STRIP - STM32H7.mk for [ADC] Initial cut without internal sensors - STM32H7.mk for Enable I2C (HAL) - STM32H7.mk for "Enable HAL-based DShot (no burst yet)" - STM32H7.mk change for transponder - STM32H750 - Add platform support. - STM32H750 - Add H750 MCU ID. - STM32H743 - Add MCU ID. STM32H7.mk change for "Burst Dshot First working version" Fix boot loader request STM32H750 - Add PERSISTENT memory support. STM32H743 - Add PERSISTENT memory support. Use PERSISTENT memory for bootloader request. Using DTCM RAM did not work on H750. Change flash latency from 4WS to 2WS STM32H750 - Fix reset of RCC_CR to reset value. Note: The comment above the code didn't match code. STM32H750 - Remove duplicate startup code, see SystemClock_Config. STM32H7.mk changes for Port RTC backup register based persistent storage for H7 Make use of persistent object facility Force reboot after possible boot loader activity Enable CRS stm32h7xx_hal_conf.h for H7 - QuadSPI support stm32h7xx_hal_conf.h for STM32H7 - SDCard/SDIO using HAL Driver stm32h7xx_hal_conf.h : Fix systick to be 0x00 instead of ST's default 0x0F. This fixes the ability to use HAL_Delay() from an ISR, as required by the ST's USB Library. Specifically, systick handler must be a higher priority than the USB FS/HS Interrupt handler priorities. stm32h7xx_hal_conf.h for Add PID-Audio support source.mk for H7 - QuadSPI support drivers/system_stm32h7xx.c for H7 - QuadSPI support STM32H7.mk for H7 - QuadSPI support STM32H7.mk change for CDC-HID support common_pre.h updates - Scheduler parameters to same as F4 & F7 - Enable some important default features - STM32H7 - Enable ITCM RAM. Requires voltage scaling fix from commit 6e684c609310024141c43de484a5e78103140e3c STM32H750 - Disable caches before reboot. Prior to this when EEPROM_IN_RAM was used the persistent data section would have corruption immediately after a reboot, prior to even the Reset_Handler code having been executed. drivers/system_stm32h7xx.c Touch-up after 2019-02-02 rebase STM32H7 - Write protect ITCM ram. Remove local defs for RESET_xxx symbols STM32H750 - EXST firmware reboots to FLASH bootloader, rather than ROM bootloader. STM32H750 - Disable some MCO/clock testing code as the pins interfere with new targets. STM32H750 - Don't disable data caches after bootloader. Observed that disabling dcache after cold boot with BOOT pin high causes segfault. drivers/system_stm32h7xx.c for STM32H7 - SDCard/SDIO using HAL Driver drivers/system_stm32h7xx.c change for Move SDMMC clock init into SDIO driver drivers/system_stm32h7xx.c: Cleanup some Clock/MCO/GPIO initialisation code. drivers/system_stm32h7xx.c for Reset if systick is stuck. STM32H7 - Fix missing CPU voltage scaling. It appears this was the cause of other seemingly random issues: * Crash soon after enabling USB. * Flash write failures. * Random un-explainable crashes. Change RCC_HSE_BYPASS to RCC_HSE_ON Even Nucleo-H743 seems to work without setting HSE_BYPASS. STM32H7xx - Move memory section initialisation earlier into the init sequence. Allows startup-code/libs/etc to be moved into different memory regions. Don't touch vector table in EXST targets STM32H750_EXST - fix boot loop target/system_stm32h7xx.c for STM32H7 - SDCard/SDIO using HAL Driver target/system_stm32h7xx.c change for Fix SD card clock speed selection STM32H750_EXST - Reset MPU regions on boot. * Failure to reset regions will result in mem-fault if bootloader has configured a similar region. STM32H750 - Fix missing include of platform.h in system_stm32h7xx.c This caused the SDMMC peripheral clock to be un-configured (at reset state) when USE_SDCARD_SDIO was defined. Change MPU region number for DMA_RAM from 0 to 1 Avoid conflict with ITCM-RAM write protection. STM32H7xx - HSERDY slow/stuck workarounds. STM32H7xx - Fix region MPU number for SDIO. * It was overwriting the previous region causing LED strip and transponder issues. Target/system_stmh7xx.c for Reset if systick is stuck. startup/system_stm32h7xx.c change for non-caching DMA_RAM H750 - Use SIZE optimization by default due to limited flash space. STM32H7.mk for STM32H7 - SDCard/SDIO using HAL Driver STM32H7.mk updates - Decrease HSE_STARTUP_TIMEOUT to 1 second * default is 5 seconds, which is too long when HSE gets stuck. - Add PID-Audio support Temporary override LINKER_DIR
2019-05-04 07:07:45 -07:00
drivers/bus_quadspi.c \
drivers/bus_spi.c \
drivers/exti.c \
drivers/io.c \
drivers/pwm_output.c \
drivers/rcc.c \
drivers/serial.c \
drivers/serial_uart.c \
drivers/system.c \
drivers/timer.c \
fc/core.c \
fc/tasks.c \
fc/rc.c \
fc/rc_controls.c \
fc/runtime_config.c \
2019-05-05 04:23:18 -07:00
flight/gyroanalyse.c \
flight/imu.c \
flight/mixer.c \
flight/pid.c \
2019-05-05 04:23:18 -07:00
flight/rpm_filter.c \
rx/ibus.c \
rx/rx.c \
rx/rx_spi.c \
rx/crsf.c \
rx/sbus.c \
rx/sbus_channels.c \
rx/spektrum.c \
rx/sumd.c \
rx/xbus.c \
rx/fport.c \
scheduler/scheduler.c \
sensors/acceleration.c \
sensors/boardalignment.c \
sensors/gyro.c \
$(CMSIS_SRC) \
$(DEVICE_STDPERIPH_SRC) \
SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \
bus_bst_stm32f30x.c \
cli/cli.c \
cli/settings.c \
drivers/barometer/barometer_bmp085.c \
drivers/barometer/barometer_bmp280.c \
drivers/barometer/barometer_fake.c \
drivers/barometer/barometer_ms5611.c \
2017-12-27 05:54:53 -08:00
drivers/barometer/barometer_lps.c \
2018-05-18 03:37:28 -07:00
drivers/barometer/barometer_qmp6988.c \
drivers/bus_i2c_config.c \
drivers/bus_spi_config.c \
drivers/bus_spi_pinconfig.c \
drivers/compass/compass_ak8963.c \
drivers/compass/compass_ak8975.c \
drivers/compass/compass_fake.c \
drivers/compass/compass_hmc5883l.c \
2018-03-03 14:45:54 -08:00
drivers/compass/compass_qmc5883l.c \
drivers/compass/compass_lis3mdl.c \
drivers/display_ug2864hsweg01.c \
drivers/inverter.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_hal.c \
drivers/light_ws2811strip_stdperiph.c \
drivers/serial_escserial.c \
drivers/serial_pinconfig.c \
drivers/serial_tcp.c \
drivers/serial_uart_init.c \
drivers/serial_uart_pinconfig.c \
drivers/serial_usb_vcp.c \
drivers/transponder_ir_io_hal.c \
drivers/transponder_ir_io_stdperiph.c \
drivers/vtx_rtc6705_soft_spi.c \
drivers/vtx_rtc6705.c \
drivers/vtx_common.c \
fc/init.c \
fc/board_info.c \
config/config_eeprom.c \
config/feature.c \
config/config_streamer.c \
i2c_bst.c \
io/dashboard.c \
io/serial.c \
io/serial_4way.c \
io/serial_4way_avrootloader.c \
io/serial_4way_stk500v2.c \
io/transponder_ir.c \
io/usb_cdc_hid.c \
msp/msp_serial.c \
cms/cms.c \
cms/cms_menu_blackbox.c \
cms/cms_menu_builtin.c \
cms/cms_menu_failsafe.c \
2019-03-23 10:13:02 -07:00
cms/cms_menu_gps_rescue.c\
cms/cms_menu_imu.c \
cms/cms_menu_ledstrip.c \
cms/cms_menu_misc.c \
cms/cms_menu_osd.c \
cms/cms_menu_power.c \
cms/cms_menu_saveexit.c \
cms/cms_menu_vtx_rtc6705.c \
cms/cms_menu_vtx_smartaudio.c \
cms/cms_menu_vtx_tramp.c \
io/vtx_string.c \
io/vtx.c \
io/vtx_rtc6705.c \
io/vtx_smartaudio.c \
io/vtx_tramp.c \
2017-12-19 02:36:31 -08:00
io/vtx_control.c \
io/spektrum_vtx_control.c \
osd/osd.c \
osd/osd_elements.c \
2017-12-19 02:36:31 -08:00
pg/pg.h
2017-11-23 06:09:18 -08:00
# F4 and F7 optimizations
ifneq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \
drivers/bus_i2c_hal.c \
drivers/bus_spi_ll.c \
drivers/max7456.c \
drivers/pwm_output_dshot.c \
2019-03-03 02:33:14 -08:00
drivers/pwm_output_dshot_shared.c \
2017-11-23 06:09:18 -08:00
drivers/pwm_output_dshot_hal.c
endif #!F3
endif #!F1
# check if target.mk supplied
SRC := $(STARTUP_SRC) $(MCU_COMMON_SRC) $(TARGET_SRC) $(VARIANT_SRC)
# Files that should not be optimized, useful for debugging IMPRECISE cpu faults.
# Specify FULL PATH, e.g. "./lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver/Src/stm32f7xx_ll_sdmmc.c"
NOT_OPTIMISED_SRC := $(NOT_OPTIMISED_SRC) \
ifneq ($(DSP_LIB),)
INCLUDE_DIRS += $(DSP_LIB)/Include
SRC += $(DSP_LIB)/Source/BasicMathFunctions/arm_mult_f32.c
SRC += $(DSP_LIB)/Source/TransformFunctions/arm_rfft_fast_f32.c
SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_f32.c
SRC += $(DSP_LIB)/Source/TransformFunctions/arm_rfft_fast_init_f32.c
SRC += $(DSP_LIB)/Source/TransformFunctions/arm_cfft_radix8_f32.c
SRC += $(DSP_LIB)/Source/CommonTables/arm_common_tables.c
SRC += $(DSP_LIB)/Source/ComplexMathFunctions/arm_cmplx_mag_f32.c
SRC += $(DSP_LIB)/Source/StatisticsFunctions/arm_max_f32.c
SRC += $(wildcard $(DSP_LIB)/Source/*/*.S)
endif
ifneq ($(filter ONBOARDFLASH,$(FEATURES)),)
SRC += \
drivers/flash.c \
drivers/flash_m25p16.c \
2019-05-12 08:46:20 -07:00
drivers/flash_w25n01g.c \
drivers/flash_w25m.c \
io/flashfs.c \
pg/flash.c \
$(MSC_SRC)
endif
SRC += $(COMMON_SRC)
#excludes
SRC := $(filter-out $(MCU_EXCLUDES), $(SRC))
ifneq ($(filter SDCARD_SPI,$(FEATURES)),)
SRC += \
drivers/sdcard.c \
drivers/sdcard_spi.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \
$(MSC_SRC)
endif
ifneq ($(filter SDCARD_SDIO,$(FEATURES)),)
SRC += \
drivers/sdcard.c \
drivers/sdcard_sdio_baremetal.c \
drivers/sdcard_standard.c \
io/asyncfatfs/asyncfatfs.c \
io/asyncfatfs/fat_standard.c \
pg/sdio.c \
$(MSC_SRC)
endif
ifneq ($(filter VCP,$(FEATURES)),)
SRC += $(VCP_SRC)
endif
ifneq ($(filter MSC,$(FEATURES)),)
SRC += $(MSC_SRC)
endif
# end target specific make file checks
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src