mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-12 19:10:32 +03:00
Code re-organisation: src/platform/xxx for the MCU type (#13955)
This commit is contained in:
parent
7158ff7081
commit
b21cfe3282
311 changed files with 645 additions and 917 deletions
|
@ -1,199 +0,0 @@
|
|||
#
|
||||
# APM32F4 Make file include
|
||||
#
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/APM32F4/Libraries/Device
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/APM32F4/Libraries/APM32F4xx_DAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
apm32f4xx_dal_adc.c \
|
||||
apm32f4xx_dal_adc_ex.c \
|
||||
apm32f4xx_dal.c \
|
||||
apm32f4xx_dal_can.c \
|
||||
apm32f4xx_dal_comp.c \
|
||||
apm32f4xx_dal_cortex.c \
|
||||
apm32f4xx_dal_crc.c \
|
||||
apm32f4xx_dal_cryp.c \
|
||||
apm32f4xx_dal_cryp_ex.c \
|
||||
apm32f4xx_dal_dac.c \
|
||||
apm32f4xx_dal_dac_ex.c \
|
||||
apm32f4xx_dal_dci.c \
|
||||
apm32f4xx_dal_dci_ex.c \
|
||||
apm32f4xx_dal_dma.c \
|
||||
apm32f4xx_dal_dma_ex.c \
|
||||
apm32f4xx_dal_eint.c \
|
||||
apm32f4xx_dal_eth.c \
|
||||
apm32f4xx_dal_flash.c \
|
||||
apm32f4xx_dal_flash_ex.c \
|
||||
apm32f4xx_dal_flash_ramfunc.c \
|
||||
apm32f4xx_dal_gpio.c \
|
||||
apm32f4xx_dal_hash.c \
|
||||
apm32f4xx_dal_hash_ex.c \
|
||||
apm32f4xx_dal_hcd.c \
|
||||
apm32f4xx_dal_i2c.c \
|
||||
apm32f4xx_dal_i2c_ex.c \
|
||||
apm32f4xx_dal_i2s.c \
|
||||
apm32f4xx_dal_i2s_ex.c \
|
||||
apm32f4xx_dal_irda.c \
|
||||
apm32f4xx_dal_iwdt.c \
|
||||
apm32f4xx_dal_log.c \
|
||||
apm32f4xx_dal_mmc.c \
|
||||
apm32f4xx_dal_nand.c \
|
||||
apm32f4xx_dal_nor.c \
|
||||
apm32f4xx_dal_pccard.c \
|
||||
apm32f4xx_dal_pcd.c \
|
||||
apm32f4xx_dal_pcd_ex.c \
|
||||
apm32f4xx_dal_pmu.c \
|
||||
apm32f4xx_dal_pmu_ex.c \
|
||||
apm32f4xx_dal_qspi.c \
|
||||
apm32f4xx_dal_rcm.c \
|
||||
apm32f4xx_dal_rcm_ex.c \
|
||||
apm32f4xx_dal_rng.c \
|
||||
apm32f4xx_dal_rtc.c \
|
||||
apm32f4xx_dal_rtc_ex.c \
|
||||
apm32f4xx_dal_sd.c \
|
||||
apm32f4xx_dal_sdram.c \
|
||||
apm32f4xx_dal_smartcard.c \
|
||||
apm32f4xx_dal_smbus.c \
|
||||
apm32f4xx_dal_spi.c \
|
||||
apm32f4xx_dal_sram.c \
|
||||
apm32f4xx_dal_tmr.c \
|
||||
apm32f4xx_dal_tmr_ex.c \
|
||||
apm32f4xx_dal_uart.c \
|
||||
apm32f4xx_dal_usart.c \
|
||||
apm32f4xx_dal_wwdt.c \
|
||||
apm32f4xx_ddl_adc.c \
|
||||
apm32f4xx_ddl_comp.c \
|
||||
apm32f4xx_ddl_crc.c \
|
||||
apm32f4xx_ddl_dac.c \
|
||||
apm32f4xx_ddl_dma.c \
|
||||
apm32f4xx_ddl_dmc.c \
|
||||
apm32f4xx_ddl_eint.c \
|
||||
apm32f4xx_ddl_gpio.c \
|
||||
apm32f4xx_ddl_i2c.c \
|
||||
apm32f4xx_ddl_pmu.c \
|
||||
apm32f4xx_ddl_rcm.c \
|
||||
apm32f4xx_ddl_rng.c \
|
||||
apm32f4xx_ddl_rtc.c \
|
||||
apm32f4xx_ddl_sdmmc.c \
|
||||
apm32f4xx_ddl_smc.c \
|
||||
apm32f4xx_ddl_spi.c \
|
||||
apm32f4xx_ddl_tmr.c \
|
||||
apm32f4xx_ddl_usart.c \
|
||||
apm32f4xx_ddl_usb.c \
|
||||
apm32f4xx_ddl_utils.c
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Source
|
||||
|
||||
#USB
|
||||
USBCORE_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Core
|
||||
USBCORE_SRC = \
|
||||
usbd_core.c \
|
||||
usbd_dataXfer.c \
|
||||
usbd_stdReq.c
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Class/CDC
|
||||
USBCDC_SRC = usbd_cdc.c
|
||||
|
||||
USBMSC_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Class/MSC
|
||||
USBMSC_SRC = \
|
||||
usbd_msc.c \
|
||||
usbd_msc_bot.c \
|
||||
usbd_msc_scsi.c
|
||||
|
||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBMSC_DIR)/Src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(ROOT)/lib/main/APM32F4/Libraries/Device/Geehy/APM32F4xx
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/apm32 \
|
||||
$(SRC_DIR)/drivers/mcu/apm32
|
||||
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(STDPERIPH_DIR)/Include \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(USBMSC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Geehy/APM32F4xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/apm32/usb/vcp \
|
||||
$(SRC_DIR)/drivers/mcu/apm32/usb/msc \
|
||||
$(SRC_DIR)/drivers/mcu/apm32/usb \
|
||||
$(ROOT)/lib/main/CMSIS/Core/Include \
|
||||
$(SRC_DIR)/msc
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
|
||||
DEVICE_FLAGS = -DUSE_DAL_DRIVER -DHSE_VALUE=$(HSE_VALUE) -DAPM32
|
||||
|
||||
ifeq ($(TARGET_MCU),APM32F405xx)
|
||||
DEVICE_FLAGS += -DAPM32F405xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/apm32_flash_f405.ld
|
||||
STARTUP_SRC = apm32/startup_apm32f405xx.S
|
||||
MCU_FLASH_SIZE := 1024
|
||||
|
||||
else ifeq ($(TARGET_MCU),APM32F407xx)
|
||||
DEVICE_FLAGS += -DAPM32F407xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/apm32_flash_f407.ld
|
||||
STARTUP_SRC = apm32/startup_apm32f407xx.S
|
||||
MCU_FLASH_SIZE := 1024
|
||||
else
|
||||
$(error TARGET_MCU [$(TARGET_MCU] is not supported)
|
||||
endif
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
startup/apm32/system_apm32f4xx.c \
|
||||
drivers/inverter.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/apm32/bus_spi_apm32.c \
|
||||
drivers/mcu/apm32/bus_i2c_apm32.c \
|
||||
drivers/mcu/apm32/bus_i2c_apm32_init.c \
|
||||
drivers/mcu/apm32/camera_control.c \
|
||||
drivers/mcu/apm32/debug.c \
|
||||
drivers/mcu/apm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/apm32/dshot_bitbang.c \
|
||||
drivers/mcu/apm32/dshot_bitbang_ddl.c \
|
||||
drivers/mcu/apm32/eint_apm32.c \
|
||||
drivers/mcu/apm32/io_apm32.c \
|
||||
drivers/mcu/apm32/light_ws2811strip_apm32.c \
|
||||
drivers/mcu/apm32/persistent_apm32.c \
|
||||
drivers/mcu/apm32/pwm_output_apm32.c \
|
||||
drivers/mcu/apm32/pwm_output_dshot_apm32.c \
|
||||
drivers/mcu/apm32/rcm_apm32.c \
|
||||
drivers/mcu/apm32/serial_uart_apm32.c \
|
||||
drivers/mcu/apm32/timer_apm32.c \
|
||||
drivers/mcu/apm32/transponder_ir_io_apm32.c \
|
||||
drivers/mcu/apm32/timer_apm32f4xx.c \
|
||||
drivers/mcu/apm32/adc_apm32f4xx.c \
|
||||
drivers/mcu/apm32/dma_apm32f4xx.c \
|
||||
drivers/mcu/apm32/serial_uart_apm32f4xx.c \
|
||||
drivers/mcu/apm32/system_apm32f4xx.c
|
||||
|
||||
VCP_SRC = \
|
||||
drivers/mcu/apm32/usb/vcp/usbd_cdc_descriptor.c \
|
||||
drivers/mcu/apm32/usb/usbd_board_apm32f4.c \
|
||||
drivers/mcu/apm32/usb/vcp/usbd_cdc_vcp.c \
|
||||
drivers/mcu/apm32/usb/vcp/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MSC_SRC = \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/mcu/apm32/usb/msc/usb_msc_apm32f4xx.c \
|
||||
drivers/mcu/apm32/usb/msc/usbd_memory.c \
|
||||
drivers/mcu/apm32/usb/msc/usbd_msc_descriptor.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sd_spi.c \
|
||||
msc/usbd_storage_sdio.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 -DUSE_FULL_DDL_DRIVER
|
122
mk/mcu/AT32F4.mk
122
mk/mcu/AT32F4.mk
|
@ -1,122 +0,0 @@
|
|||
#
|
||||
# AT32F4 Make file include
|
||||
#
|
||||
|
||||
CMSIS_DIR := $(ROOT)/lib/main/AT32F43x/cmsis
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/AT32F43x/drivers
|
||||
MIDDLEWARES_DIR = $(ROOT)/lib/main/AT32F43x/middlewares
|
||||
STDPERIPH_SRC = \
|
||||
at32f435_437_acc.c \
|
||||
at32f435_437_adc.c \
|
||||
at32f435_437_can.c \
|
||||
at32f435_437_crc.c \
|
||||
at32f435_437_crm.c \
|
||||
at32f435_437_dac.c \
|
||||
at32f435_437_debug.c \
|
||||
at32f435_437_dma.c \
|
||||
at32f435_437_dvp.c \
|
||||
at32f435_437_edma.c \
|
||||
at32f435_437_emac.c \
|
||||
at32f435_437_ertc.c \
|
||||
at32f435_437_exint.c \
|
||||
at32f435_437_flash.c \
|
||||
at32f435_437_gpio.c \
|
||||
at32f435_437_i2c.c \
|
||||
at32f435_437_misc.c \
|
||||
at32f435_437_pwc.c \
|
||||
at32f435_437_qspi.c \
|
||||
at32f435_437_scfg.c \
|
||||
at32f435_437_sdio.c \
|
||||
at32f435_437_spi.c \
|
||||
at32f435_437_tmr.c \
|
||||
at32f435_437_usart.c \
|
||||
at32f435_437_usb.c \
|
||||
at32f435_437_wdt.c \
|
||||
at32f435_437_wwdt.c \
|
||||
at32f435_437_xmc.c \
|
||||
usb_drivers/src/usb_core.c \
|
||||
usb_drivers/src/usbd_core.c \
|
||||
usb_drivers/src/usbd_int.c \
|
||||
usb_drivers/src/usbd_sdr.c \
|
||||
usb_drivers/src/usbh_core.c \
|
||||
usb_drivers/src/usbh_ctrl.c \
|
||||
usb_drivers/src/usbh_int.c \
|
||||
usbd_class/msc/msc_bot_scsi.c \
|
||||
usbd_class/msc/msc_class.c \
|
||||
usbd_class/msc/msc_desc.c
|
||||
|
||||
STARTUP_SRC = at32/startup_at32f435_437.s
|
||||
|
||||
VPATH := $(VPATH):$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/src:$(MIDDLEWARES_DIR):$(SRC_DIR)/startup/at32
|
||||
|
||||
VCP_SRC = \
|
||||
usbd_class/cdc/cdc_class.c \
|
||||
usbd_class/cdc/cdc_desc.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
VCP_INCLUDES = \
|
||||
$(MIDDLEWARES_DIR)/usb_drivers/inc \
|
||||
$(MIDDLEWARES_DIR)/usbd_class/cdc
|
||||
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/at32 \
|
||||
$(SRC_DIR)/drivers \
|
||||
$(SRC_DIR)/drivers/mcu/at32 \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(CMSIS_DIR)/cm4/core_support \
|
||||
$(CMSIS_DIR)/cm4 \
|
||||
$(MIDDLEWARES_DIR)/i2c_application_library \
|
||||
$(MIDDLEWARES_DIR)/usbd_class/msc \
|
||||
$(VCP_INCLUDES)
|
||||
|
||||
ifeq ($(TARGET),AT32F435M)
|
||||
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xm.ld
|
||||
else
|
||||
LD_SCRIPT = $(LINKER_DIR)/at32_flash_f43xg.ld
|
||||
endif
|
||||
|
||||
ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
startup/at32/at32f435_437_clock.c \
|
||||
startup/at32/system_at32f435_437.c \
|
||||
drivers/mcu/at32/adc_at32f43x.c \
|
||||
drivers/mcu/at32/bus_i2c_atbsp.c \
|
||||
drivers/mcu/at32/bus_i2c_atbsp_init.c \
|
||||
drivers/mcu/at32/bus_spi_at32bsp.c \
|
||||
drivers/mcu/at32/camera_control.c \
|
||||
drivers/mcu/at32/debug.c \
|
||||
drivers/mcu/at32/dma_at32f43x.c \
|
||||
drivers/mcu/at32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/at32/dshot_bitbang.c \
|
||||
drivers/mcu/at32/dshot_bitbang_stdperiph.c \
|
||||
drivers/mcu/at32/exti_at32.c \
|
||||
drivers/mcu/at32/io_at32.c \
|
||||
drivers/mcu/at32/light_ws2811strip_at32f43x.c \
|
||||
drivers/mcu/at32/persistent_at32bsp.c \
|
||||
drivers/mcu/at32/pwm_output_at32bsp.c \
|
||||
drivers/mcu/at32/pwm_output_dshot.c \
|
||||
drivers/mcu/at32/rcc_at32.c \
|
||||
drivers/mcu/at32/serial_uart_at32bsp.c \
|
||||
drivers/mcu/at32/serial_uart_at32f43x.c \
|
||||
drivers/mcu/at32/serial_usb_vcp_at32f4.c \
|
||||
drivers/mcu/at32/system_at32f43x.c \
|
||||
drivers/mcu/at32/timer_at32bsp.c \
|
||||
drivers/mcu/at32/timer_at32f43x.c \
|
||||
drivers/mcu/at32/usb_msc_at32f43x.c \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/inverter.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
$(MIDDLEWARES_DIR)/i2c_application_library/i2c_application.c \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/usb_msc_common.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c
|
||||
|
||||
MCU_EXCLUDES =
|
|
@ -1,68 +0,0 @@
|
|||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(ROOT)/lib/main/dyad
|
||||
|
||||
MCU_COMMON_SRC := $(ROOT)/lib/main/dyad/dyad.c
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS =
|
||||
DEVICE_FLAGS =
|
||||
LD_SCRIPT = src/main/target/SITL/pg.ld
|
||||
STARTUP_SRC =
|
||||
|
||||
MCU_FLASH_SIZE := 2048
|
||||
|
||||
ARM_SDK_PREFIX =
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/adc.c \
|
||||
drivers/bus_i2c.c \
|
||||
drivers/bus_i2c_config.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/bus_spi_config.c \
|
||||
drivers/bus_spi_pinconfig.c \
|
||||
drivers/dma.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/timer.c \
|
||||
drivers/system.c \
|
||||
drivers/rcc.c \
|
||||
drivers/serial_escserial.c \
|
||||
drivers/serial_pinconfig.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/serial_uart_init.c \
|
||||
drivers/serial_uart_pinconfig.c \
|
||||
drivers/rx/rx_xn297.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
telemetry/crsf.c \
|
||||
telemetry/ghst.c \
|
||||
telemetry/srxl.c \
|
||||
io/displayport_oled.c
|
||||
|
||||
TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map
|
||||
|
||||
LD_FLAGS := \
|
||||
-lm \
|
||||
-lpthread \
|
||||
-lc \
|
||||
-lrt \
|
||||
$(ARCH_FLAGS) \
|
||||
$(LTO_FLAGS) \
|
||||
$(DEBUG_FLAGS) \
|
||||
-Wl,-gc-sections,-Map,$(TARGET_MAP) \
|
||||
-Wl,-L$(LINKER_DIR) \
|
||||
-Wl,--cref \
|
||||
-T$(LD_SCRIPT)
|
||||
|
||||
ifneq ($(filter SITL_STATIC,$(OPTIONS)),)
|
||||
LD_FLAGS += \
|
||||
-static \
|
||||
-static-libgcc
|
||||
endif
|
||||
|
||||
ifneq ($(DEBUG),GDB)
|
||||
OPTIMISE_DEFAULT := -Ofast
|
||||
OPTIMISE_SPEED := -Ofast
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED)
|
||||
endif
|
|
@ -1,232 +0,0 @@
|
|||
#
|
||||
# F4 Make file include
|
||||
#
|
||||
|
||||
#CMSIS
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_HAL_Driver
|
||||
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c))
|
||||
EXCLUDES =
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
|
||||
|
||||
else
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver
|
||||
STDPERIPH_SRC = \
|
||||
misc.c \
|
||||
stm32f4xx_adc.c \
|
||||
stm32f4xx_dac.c \
|
||||
stm32f4xx_dcmi.c \
|
||||
stm32f4xx_dfsdm.c \
|
||||
stm32f4xx_dma2d.c \
|
||||
stm32f4xx_dma.c \
|
||||
stm32f4xx_exti.c \
|
||||
stm32f4xx_flash.c \
|
||||
stm32f4xx_gpio.c \
|
||||
stm32f4xx_i2c.c \
|
||||
stm32f4xx_iwdg.c \
|
||||
stm32f4xx_ltdc.c \
|
||||
stm32f4xx_pwr.c \
|
||||
stm32f4xx_rcc.c \
|
||||
stm32f4xx_rng.c \
|
||||
stm32f4xx_rtc.c \
|
||||
stm32f4xx_sdio.c \
|
||||
stm32f4xx_spi.c \
|
||||
stm32f4xx_syscfg.c \
|
||||
stm32f4xx_tim.c \
|
||||
stm32f4xx_usart.c \
|
||||
stm32f4xx_wwdg.c
|
||||
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
|
||||
endif
|
||||
|
||||
ifneq ($(TARGET_MCU),$(filter $(TARGET_MCU),STM32F411xE STM32F446xx))
|
||||
STDPERIPH_SRC += stm32f4xx_fsmc.c
|
||||
endif
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
#USB
|
||||
USBCORE_DIR = $(ROOT)/lib/main/STM32F4/Middlewares/ST/STM32_USB_Device_Library/Core
|
||||
USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
|
||||
EXCLUDES = usbd_conf_template.c
|
||||
USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/STM32F4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
|
||||
USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c))
|
||||
EXCLUDES = usbd_cdc_if_template.c
|
||||
USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC))
|
||||
|
||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
$(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC)
|
||||
else
|
||||
USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core
|
||||
USBCORE_SRC = \
|
||||
usbd_core.c \
|
||||
usbd_ioreq.c \
|
||||
usbd_req.c
|
||||
|
||||
USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver
|
||||
USBOTG_SRC = \
|
||||
usb_core.c \
|
||||
usb_dcd.c \
|
||||
usb_dcd_int.c
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc
|
||||
USBCDC_SRC = usbd_cdc_core.c
|
||||
|
||||
USBMSC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/msc
|
||||
USBMSC_SRC = \
|
||||
usbd_msc_bot.c \
|
||||
usbd_msc_core.c \
|
||||
usbd_msc_data.c \
|
||||
usbd_msc_scsi.c
|
||||
|
||||
USBHID_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid
|
||||
USBHID_SRC = usbd_hid_core.c
|
||||
|
||||
USBWRAPPER_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid_cdc_wrapper
|
||||
USBWRAPPER_SRC = usbd_hid_cdc_wrapper.c
|
||||
|
||||
VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src:$(USBMSC_DIR)/src:$(USBHID_DIR)/src:$(USBWRAPPER_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
$(STDPERIPH_SRC) \
|
||||
$(USBOTG_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBWRAPPER_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx
|
||||
|
||||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/stm32 \
|
||||
$(SRC_DIR)/drivers/mcu/stm32
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Include \
|
||||
$(CMSIS_DIR)/Device/ST/STM32F4xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcp_hal
|
||||
else
|
||||
CMSIS_SRC := \
|
||||
stm32f4xx_gpio.c \
|
||||
stm32f4xx_rcc.c
|
||||
|
||||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(STDPERIPH_DIR)/inc \
|
||||
$(USBOTG_DIR)/inc \
|
||||
$(USBCORE_DIR)/inc \
|
||||
$(USBCDC_DIR)/inc \
|
||||
$(USBHID_DIR)/inc \
|
||||
$(USBWRAPPER_DIR)/inc \
|
||||
$(USBMSC_DIR)/inc \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcpf4
|
||||
endif
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
|
||||
ifeq ($(TARGET_MCU),STM32F411xE)
|
||||
DEVICE_FLAGS = -DSTM32F411xE -finline-limit=20
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f411xe.s
|
||||
MCU_FLASH_SIZE := 512
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32F405xx)
|
||||
DEVICE_FLAGS = -DSTM32F40_41xxx -DSTM32F405xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f40xx.s
|
||||
MCU_FLASH_SIZE := 1024
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32F446xx)
|
||||
DEVICE_FLAGS = -DSTM32F446xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f446.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f446xx.s
|
||||
MCU_FLASH_SIZE := 512
|
||||
|
||||
else
|
||||
$(error Unknown MCU for F4 target)
|
||||
endif
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/inverter.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/stm32/pwm_output_dshot.c \
|
||||
drivers/mcu/stm32/adc_stm32f4xx.c \
|
||||
drivers/mcu/stm32/bus_i2c_stm32f4xx.c \
|
||||
drivers/mcu/stm32/bus_spi_stdperiph.c \
|
||||
drivers/mcu/stm32/debug.c \
|
||||
drivers/mcu/stm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/stm32/dma_stm32f4xx.c \
|
||||
drivers/mcu/stm32/dshot_bitbang.c \
|
||||
drivers/mcu/stm32/dshot_bitbang_stdperiph.c \
|
||||
drivers/mcu/stm32/exti.c \
|
||||
drivers/mcu/stm32/io_stm32.c \
|
||||
drivers/mcu/stm32/light_ws2811strip_stdperiph.c \
|
||||
drivers/mcu/stm32/persistent.c \
|
||||
drivers/mcu/stm32/pwm_output.c \
|
||||
drivers/mcu/stm32/rcc_stm32.c \
|
||||
drivers/mcu/stm32/sdio_f4xx.c \
|
||||
drivers/mcu/stm32/serial_uart_stdperiph.c \
|
||||
drivers/mcu/stm32/serial_uart_stm32f4xx.c \
|
||||
drivers/mcu/stm32/system_stm32f4xx.c \
|
||||
drivers/mcu/stm32/timer_stdperiph.c \
|
||||
drivers/mcu/stm32/timer_stm32f4xx.c \
|
||||
drivers/mcu/stm32/transponder_ir_io_stdperiph.c \
|
||||
drivers/mcu/stm32/usbd_msc_desc.c \
|
||||
drivers/mcu/stm32/camera_control.c \
|
||||
startup/stm32/system_stm32f4xx.c
|
||||
|
||||
ifeq ($(PERIPH_DRIVER), HAL)
|
||||
VCP_SRC = \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_conf.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
else
|
||||
VCP_SRC = \
|
||||
drivers/mcu/stm32/vcpf4/stm32f4xx_it.c \
|
||||
drivers/mcu/stm32/vcpf4/usb_bsp.c \
|
||||
drivers/mcu/stm32/vcpf4/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcpf4/usbd_usr.c \
|
||||
drivers/mcu/stm32/vcpf4/usbd_cdc_vcp.c \
|
||||
drivers/mcu/stm32/vcpf4/usb_cdc_hid.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
endif
|
||||
|
||||
MSC_SRC = \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/mcu/stm32/usb_msc_f4xx.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sd_spi.c \
|
||||
msc/usbd_storage_sdio.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4
|
|
@ -1,189 +0,0 @@
|
|||
#
|
||||
# F7 Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),F7)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
stm32f7xx_hal_adc.c \
|
||||
stm32f7xx_hal_adc_ex.c \
|
||||
stm32f7xx_hal.c \
|
||||
stm32f7xx_hal_cortex.c \
|
||||
stm32f7xx_hal_dac.c \
|
||||
stm32f7xx_hal_dac_ex.c \
|
||||
stm32f7xx_hal_dma.c \
|
||||
stm32f7xx_hal_dma_ex.c \
|
||||
stm32f7xx_hal_exti.c \
|
||||
stm32f7xx_hal_flash.c \
|
||||
stm32f7xx_hal_flash_ex.c \
|
||||
stm32f7xx_hal_gpio.c \
|
||||
stm32f7xx_hal_i2c.c \
|
||||
stm32f7xx_hal_i2c_ex.c \
|
||||
stm32f7xx_hal_pcd.c \
|
||||
stm32f7xx_hal_pcd_ex.c \
|
||||
stm32f7xx_hal_pwr.c \
|
||||
stm32f7xx_hal_pwr_ex.c \
|
||||
stm32f7xx_hal_rcc.c \
|
||||
stm32f7xx_hal_rcc_ex.c \
|
||||
stm32f7xx_hal_rtc.c \
|
||||
stm32f7xx_hal_rtc_ex.c \
|
||||
stm32f7xx_hal_spi.c \
|
||||
stm32f7xx_hal_spi_ex.c \
|
||||
stm32f7xx_hal_tim.c \
|
||||
stm32f7xx_hal_tim_ex.c \
|
||||
stm32f7xx_hal_uart.c \
|
||||
stm32f7xx_hal_uart_ex.c \
|
||||
stm32f7xx_hal_usart.c \
|
||||
stm32f7xx_ll_dma2d.c \
|
||||
stm32f7xx_ll_dma.c \
|
||||
stm32f7xx_ll_gpio.c \
|
||||
stm32f7xx_ll_rcc.c \
|
||||
stm32f7xx_ll_spi.c \
|
||||
stm32f7xx_ll_tim.c \
|
||||
stm32f7xx_ll_usb.c \
|
||||
stm32f7xx_ll_utils.c
|
||||
|
||||
#USB
|
||||
USBCORE_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core
|
||||
USBCORE_SRC = \
|
||||
usbd_core.c \
|
||||
usbd_ctlreq.c \
|
||||
usbd_ioreq.c
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
|
||||
USBCDC_SRC = usbd_cdc.c
|
||||
|
||||
|
||||
USBHID_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID
|
||||
USBHID_SRC = usbd_hid.c
|
||||
|
||||
USBMSC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
|
||||
USBMSC_SRC = \
|
||||
usbd_msc_bot.c \
|
||||
usbd_msc.c \
|
||||
usbd_msc_data.c \
|
||||
usbd_msc_scsi.c
|
||||
|
||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
|
||||
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/stm32 \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(USBHID_DIR)/Inc \
|
||||
$(USBMSC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/stm32 \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
||||
ifeq ($(TARGET_MCU),STM32F765xx)
|
||||
DEVICE_FLAGS += -DSTM32F765xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f765.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f765xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
else ifeq ($(TARGET_MCU),STM32F745xx)
|
||||
DEVICE_FLAGS += -DSTM32F745xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f745xx.s
|
||||
MCU_FLASH_SIZE := 1024
|
||||
else ifeq ($(TARGET_MCU),STM32F746xx)
|
||||
DEVICE_FLAGS += -DSTM32F746xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f74x.ld
|
||||
STARTUP_SRC = stm32/startup_stm32f746xx.s
|
||||
MCU_FLASH_SIZE := 1024
|
||||
else ifeq ($(TARGET_MCU),STM32F722xx)
|
||||
DEVICE_FLAGS += -DSTM32F722xx
|
||||
ifndef LD_SCRIPT
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f722.ld
|
||||
endif
|
||||
STARTUP_SRC = stm32/startup_stm32f722xx.s
|
||||
MCU_FLASH_SIZE := 512
|
||||
# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets.
|
||||
# Performance is only slightly affected but around 50 kB of flash are saved.
|
||||
OPTIMISE_SPEED = -O2
|
||||
else
|
||||
$(error Unknown MCU for F7 target)
|
||||
endif
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32
|
||||
|
||||
VCP_SRC = \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_conf_stm32f7xx.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_hid.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/stm32/adc_stm32f7xx.c \
|
||||
drivers/mcu/stm32/audio_stm32f7xx.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal_init.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal.c \
|
||||
drivers/mcu/stm32/bus_spi_ll.c \
|
||||
drivers/mcu/stm32/debug.c \
|
||||
drivers/mcu/stm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/stm32/dma_stm32f7xx.c \
|
||||
drivers/mcu/stm32/dshot_bitbang_ll.c \
|
||||
drivers/mcu/stm32/dshot_bitbang.c \
|
||||
drivers/mcu/stm32/exti.c \
|
||||
drivers/mcu/stm32/io_stm32.c \
|
||||
drivers/mcu/stm32/light_ws2811strip_hal.c \
|
||||
drivers/mcu/stm32/persistent.c \
|
||||
drivers/mcu/stm32/pwm_output.c \
|
||||
drivers/mcu/stm32/pwm_output_dshot_hal.c \
|
||||
drivers/mcu/stm32/rcc_stm32.c \
|
||||
drivers/mcu/stm32/sdio_f7xx.c \
|
||||
drivers/mcu/stm32/serial_uart_hal.c \
|
||||
drivers/mcu/stm32/serial_uart_stm32f7xx.c \
|
||||
drivers/mcu/stm32/system_stm32f7xx.c \
|
||||
drivers/mcu/stm32/timer_hal.c \
|
||||
drivers/mcu/stm32/timer_stm32f7xx.c \
|
||||
drivers/mcu/stm32/transponder_ir_io_hal.c \
|
||||
drivers/mcu/stm32/camera_control.c \
|
||||
startup/stm32/system_stm32f7xx.c
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/bus_i2c.c
|
||||
|
||||
MSC_SRC = \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/mcu/stm32/usb_msc_hal.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sdio.c \
|
||||
msc/usbd_storage_sd_spi.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7
|
|
@ -1,167 +0,0 @@
|
|||
#
|
||||
# G4 Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),G4)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32G4/Drivers/STM32G4xx_HAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
stm32g4xx_hal_adc.c \
|
||||
stm32g4xx_hal_adc_ex.c \
|
||||
stm32g4xx_hal.c \
|
||||
stm32g4xx_hal_cordic.c \
|
||||
stm32g4xx_hal_cortex.c \
|
||||
stm32g4xx_hal_dma.c \
|
||||
stm32g4xx_hal_exti.c \
|
||||
stm32g4xx_hal_fdcan.c \
|
||||
stm32g4xx_hal_flash.c \
|
||||
stm32g4xx_hal_flash_ex.c \
|
||||
stm32g4xx_hal_fmac.c \
|
||||
stm32g4xx_hal_gpio.c \
|
||||
stm32g4xx_hal_i2c.c \
|
||||
stm32g4xx_hal_i2c_ex.c \
|
||||
stm32g4xx_hal_pcd.c \
|
||||
stm32g4xx_hal_pcd_ex.c \
|
||||
stm32g4xx_hal_pwr.c \
|
||||
stm32g4xx_hal_pwr_ex.c \
|
||||
stm32g4xx_hal_rcc.c \
|
||||
stm32g4xx_hal_rcc_ex.c \
|
||||
stm32g4xx_hal_rtc.c \
|
||||
stm32g4xx_hal_rtc_ex.c \
|
||||
stm32g4xx_hal_tim.c \
|
||||
stm32g4xx_hal_tim_ex.c \
|
||||
stm32g4xx_hal_uart.c \
|
||||
stm32g4xx_hal_uart_ex.c \
|
||||
stm32g4xx_ll_dma.c \
|
||||
stm32g4xx_ll_spi.c \
|
||||
stm32g4xx_ll_tim.c \
|
||||
stm32g4xx_ll_usb.c
|
||||
|
||||
#USB
|
||||
USBCORE_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Core
|
||||
USBCORE_SRC = \
|
||||
usbd_core.c \
|
||||
usbd_ctlreq.c \
|
||||
usbd_ioreq.c
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
|
||||
USBCDC_SRC = usbd_cdc.c
|
||||
|
||||
USBHID_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/HID
|
||||
USBHID_SRC = usbd_hid.c
|
||||
|
||||
USBMSC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
|
||||
USBMSC_SRC = \
|
||||
usbd_msc_bot.c \
|
||||
usbd_msc.c \
|
||||
usbd_msc_data.c \
|
||||
usbd_msc_scsi.c
|
||||
|
||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := \
|
||||
$(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32G4xx
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := \
|
||||
$(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/stm32 \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(USBHID_DIR)/Inc \
|
||||
$(USBMSC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(ROOT)/lib/main/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/stm32 \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant
|
||||
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DUSE_DMA_RAM -DMAX_MPU_REGIONS=16
|
||||
|
||||
# G47X_TARGETS includes G47{3,4}{RE,CE,CEU}
|
||||
|
||||
ifeq ($(TARGET_MCU),STM32G474xx)
|
||||
DEVICE_FLAGS += -DSTM32G474xx
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_g474.ld
|
||||
STARTUP_SRC = stm32/startup_stm32g474xx.s
|
||||
MCU_FLASH_SIZE = 512
|
||||
# Override the OPTIMISE_SPEED compiler setting to save flash space on these 512KB targets.
|
||||
# Performance is only slightly affected but around 50 kB of flash are saved.
|
||||
OPTIMISE_SPEED = -O2
|
||||
else
|
||||
$(error Unknown MCU for G4 target)
|
||||
endif
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32
|
||||
|
||||
VCP_SRC = \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_conf_stm32g4xx.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_hid.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/accgyro/accgyro_mpu.c \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/stm32/adc_stm32g4xx.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal_init.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal.c \
|
||||
drivers/mcu/stm32/bus_spi_ll.c \
|
||||
drivers/mcu/stm32/debug.c \
|
||||
drivers/mcu/stm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/stm32/dma_stm32g4xx.c \
|
||||
drivers/mcu/stm32/dshot_bitbang_ll.c \
|
||||
drivers/mcu/stm32/dshot_bitbang.c \
|
||||
drivers/mcu/stm32/exti.c \
|
||||
drivers/mcu/stm32/io_stm32.c \
|
||||
drivers/mcu/stm32/light_ws2811strip_hal.c \
|
||||
drivers/mcu/stm32/memprot_hal.c \
|
||||
drivers/mcu/stm32/memprot_stm32g4xx.c \
|
||||
drivers/mcu/stm32/persistent.c \
|
||||
drivers/mcu/stm32/pwm_output.c \
|
||||
drivers/mcu/stm32/pwm_output_dshot_hal.c \
|
||||
drivers/mcu/stm32/rcc_stm32.c \
|
||||
drivers/mcu/stm32/serial_uart_hal.c \
|
||||
drivers/mcu/stm32/serial_uart_stm32g4xx.c \
|
||||
drivers/mcu/stm32/system_stm32g4xx.c \
|
||||
drivers/mcu/stm32/timer_hal.c \
|
||||
drivers/mcu/stm32/timer_stm32g4xx.c \
|
||||
drivers/mcu/stm32/transponder_ir_io_hal.c \
|
||||
drivers/mcu/stm32/camera_control.c \
|
||||
startup/stm32/system_stm32g4xx.c
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/bus_i2c.c
|
||||
|
||||
# G4's MSC use the same driver layer file with F7
|
||||
MSC_SRC = \
|
||||
drivers/usb_msc_common.c \
|
||||
drivers/mcu/stm32/usb_msc_hal.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sdio.c \
|
||||
msc/usbd_storage_sd_spi.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4
|
|
@ -1,201 +0,0 @@
|
|||
#
|
||||
# H5 Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),H5)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32H5/Drivers/STM32H5xx_HAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
stm32h5xx_hal_adc.c \
|
||||
stm32h5xx_hal_adc_ex.c \
|
||||
stm32h5xx_hal.c \
|
||||
stm32h5xx_hal_cordic.c \
|
||||
stm32h5xx_hal_cortex.c \
|
||||
stm32h5xx_hal_dac.c \
|
||||
stm32h5xx_hal_dac_ex.c \
|
||||
stm32h5xx_hal_dcache.c \
|
||||
stm32h5xx_hal_dma.c \
|
||||
stm32h5xx_hal_dma_ex.c \
|
||||
stm32h5xx_hal_dts.c \
|
||||
stm32h5xx_hal_exti.c \
|
||||
stm32h5xx_hal_flash.c \
|
||||
stm32h5xx_hal_flash_ex.c \
|
||||
stm32h5xx_hal_fmac.c \
|
||||
stm32h5xx_hal_gpio.c \
|
||||
stm32h5xx_hal_gtzc.c \
|
||||
stm32h5xx_hal_i2c.c \
|
||||
stm32h5xx_hal_i2c_ex.c \
|
||||
stm32h5xx_hal_i3c.c \
|
||||
stm32h5xx_hal_icache.c \
|
||||
stm32h5xx_hal_otfdec.c \
|
||||
stm32h5xx_hal_pcd.c \
|
||||
stm32h5xx_hal_pcd_ex.c \
|
||||
stm32h5xx_hal_pka.c \
|
||||
stm32h5xx_hal_pssi.c \
|
||||
stm32h5xx_hal_pwr.c \
|
||||
stm32h5xx_hal_pwr_ex.c \
|
||||
stm32h5xx_hal_ramcfg.c \
|
||||
stm32h5xx_hal_rcc.c \
|
||||
stm32h5xx_hal_rcc_ex.c \
|
||||
stm32h5xx_hal_rng_ex.c \
|
||||
stm32h5xx_hal_rtc_ex.c \
|
||||
stm32h5xx_hal_sd.c \
|
||||
stm32h5xx_hal_smbus_ex.c \
|
||||
stm32h5xx_hal_spi_ex.c \
|
||||
stm32h5xx_hal_tim.c \
|
||||
stm32h5xx_hal_tim_ex.c \
|
||||
stm32h5xx_hal_uart.c \
|
||||
stm32h5xx_hal_uart_ex.c \
|
||||
stm32h5xx_hal_xspi.c \
|
||||
stm32h5xx_ll_cordic.c \
|
||||
stm32h5xx_ll_crs.c \
|
||||
stm32h5xx_ll_dlyb.c \
|
||||
stm32h5xx_ll_dma.c \
|
||||
stm32h5xx_ll_fmac.c \
|
||||
stm32h5xx_ll_i3c.c \
|
||||
stm32h5xx_ll_icache.c \
|
||||
stm32h5xx_ll_pka.c \
|
||||
stm32h5xx_ll_sdmmc.c \
|
||||
stm32h5xx_ll_spi.c \
|
||||
stm32h5xx_ll_tim.c \
|
||||
stm32h5xx_ll_ucpd.c \
|
||||
stm32h5xx_ll_usb.c \
|
||||
stm32h5xx_util_i3c.c
|
||||
|
||||
#USB ##TODO - need to work through the USB drivers, new directory: USBX
|
||||
#USBCORE_DIR = $(ROOT)/lib/main/STM32H5/Middlewares/ST/usbx/Common
|
||||
#USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c))
|
||||
#EXCLUDES =
|
||||
#USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC))
|
||||
|
||||
#VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H5xx
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/stm32 \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(USBHID_DIR)/Inc \
|
||||
$(USBMSC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(ROOT)/lib/main/STM32H5/Drivers/CMSIS/Device/ST/STM32H5xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/stm32 \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
||||
#
|
||||
# H563xx : 2M FLASH, 640KB SRAM
|
||||
#
|
||||
ifeq ($(TARGET_MCU),STM32H563xx)
|
||||
DEVICE_FLAGS += -DSTM32H563xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h563_2m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h563xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
# end H563xx
|
||||
|
||||
|
||||
ifneq ($(DEBUG),GDB)
|
||||
OPTIMISE_DEFAULT := -Os
|
||||
OPTIMISE_SPEED := -Os
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
|
||||
endif
|
||||
|
||||
else
|
||||
$(error Unknown MCU for STM32H5 target)
|
||||
endif
|
||||
|
||||
ifeq ($(LD_SCRIPT),)
|
||||
LD_SCRIPT = $(DEFAULT_LD_SCRIPT)
|
||||
endif
|
||||
|
||||
ifneq ($(FIRMWARE_SIZE),)
|
||||
DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 -DSTM32
|
||||
|
||||
VCP_SRC =
|
||||
#VCP_SRC = \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_conf_stm32h5xx.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_hid.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/bus_quadspi.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal_init.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal.c \
|
||||
drivers/mcu/stm32/bus_spi_ll.c \
|
||||
drivers/mcu/stm32/bus_quadspi_hal.c \
|
||||
drivers/mcu/stm32/debug.c \
|
||||
drivers/mcu/stm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/stm32/dshot_bitbang_ll.c \
|
||||
drivers/mcu/stm32/dshot_bitbang.c \
|
||||
drivers/mcu/stm32/exti.c \
|
||||
drivers/mcu/stm32/io_stm32.c \
|
||||
drivers/mcu/stm32/light_ws2811strip_hal.c \
|
||||
drivers/mcu/stm32/persistent.c \
|
||||
drivers/mcu/stm32/pwm_output.c \
|
||||
drivers/mcu/stm32/pwm_output_dshot_hal.c \
|
||||
drivers/mcu/stm32/rcc_stm32.c \
|
||||
drivers/mcu/stm32/serial_uart_hal.c \
|
||||
drivers/mcu/stm32/timer_hal.c \
|
||||
drivers/mcu/stm32/transponder_ir_io_hal.c \
|
||||
drivers/mcu/stm32/camera_control.c \
|
||||
drivers/mcu/stm32/system_stm32h5xx.c \
|
||||
startup/stm32/system_stm32h5xx.c
|
||||
|
||||
# drivers/mcu/stm32/memprot_hal.c \
|
||||
# drivers/mcu/stm32/memprot_stm32h5xx.c \
|
||||
# drivers/mcu/stm32/serial_uart_stm32h5xx.c \
|
||||
# drivers/mcu/stm32/sdio_h5xx.c \
|
||||
# drivers/mcu/stm32/timer_stm32h5xx.c \
|
||||
# drivers/mcu/stm32/adc_stm32h5xx.c \
|
||||
# drivers/mcu/stm32/dma_stm32h5xx.c \
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/bus_i2c.c
|
||||
|
||||
MSC_SRC =
|
||||
#MSC_SRC = \
|
||||
drivers/mcu/stm32/usb_msc_hal.c \
|
||||
drivers/usb_msc_common.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sd_spi.c \
|
||||
msc/usbd_storage_sdio.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7
|
|
@ -1,316 +0,0 @@
|
|||
#
|
||||
# H7 Make file include
|
||||
#
|
||||
|
||||
ifeq ($(DEBUG_HARDFAULTS),H7)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
endif
|
||||
|
||||
#CMSIS
|
||||
CMSIS_DIR := $(ROOT)/lib/main/CMSIS
|
||||
|
||||
#STDPERIPH
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver
|
||||
STDPERIPH_SRC = \
|
||||
stm32h7xx_hal_adc.c \
|
||||
stm32h7xx_hal_adc_ex.c \
|
||||
stm32h7xx_hal.c \
|
||||
stm32h7xx_hal_cordic.c \
|
||||
stm32h7xx_hal_cortex.c \
|
||||
stm32h7xx_hal_dac.c \
|
||||
stm32h7xx_hal_dac_ex.c \
|
||||
stm32h7xx_hal_dfsdm_ex.c \
|
||||
stm32h7xx_hal_dma.c \
|
||||
stm32h7xx_hal_dma_ex.c \
|
||||
stm32h7xx_hal_dts.c \
|
||||
stm32h7xx_hal_exti.c \
|
||||
stm32h7xx_hal_flash.c \
|
||||
stm32h7xx_hal_flash_ex.c \
|
||||
stm32h7xx_hal_fmac.c \
|
||||
stm32h7xx_hal_gfxmmu.c \
|
||||
stm32h7xx_hal_gpio.c \
|
||||
stm32h7xx_hal_i2c.c \
|
||||
stm32h7xx_hal_i2c_ex.c \
|
||||
stm32h7xx_hal_ospi.c \
|
||||
stm32h7xx_hal_otfdec.c \
|
||||
stm32h7xx_hal_pcd.c \
|
||||
stm32h7xx_hal_pcd_ex.c \
|
||||
stm32h7xx_hal_pssi.c \
|
||||
stm32h7xx_hal_pwr.c \
|
||||
stm32h7xx_hal_pwr_ex.c \
|
||||
stm32h7xx_hal_qspi.c \
|
||||
stm32h7xx_hal_rcc.c \
|
||||
stm32h7xx_hal_rcc_ex.c \
|
||||
stm32h7xx_hal_rng_ex.c \
|
||||
stm32h7xx_hal_rtc_ex.c \
|
||||
stm32h7xx_hal_sd.c \
|
||||
stm32h7xx_hal_spi_ex.c \
|
||||
stm32h7xx_hal_tim.c \
|
||||
stm32h7xx_hal_tim_ex.c \
|
||||
stm32h7xx_hal_uart.c \
|
||||
stm32h7xx_hal_uart_ex.c \
|
||||
stm32h7xx_ll_cordic.c \
|
||||
stm32h7xx_ll_crs.c \
|
||||
stm32h7xx_ll_dma.c \
|
||||
stm32h7xx_ll_fmac.c \
|
||||
stm32h7xx_ll_sdmmc.c \
|
||||
stm32h7xx_ll_spi.c \
|
||||
stm32h7xx_ll_tim.c \
|
||||
stm32h7xx_ll_usb.c
|
||||
|
||||
#USB
|
||||
USBCORE_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core
|
||||
USBCORE_SRC = \
|
||||
usbd_core.c \
|
||||
usbd_ctlreq.c \
|
||||
usbd_ioreq.c
|
||||
|
||||
USBCDC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC
|
||||
USBCDC_SRC = usbd_cdc.c
|
||||
|
||||
USBHID_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID
|
||||
USBHID_SRC = usbd_hid.c
|
||||
|
||||
USBMSC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC
|
||||
USBMSC_SRC = \
|
||||
usbd_msc_bot.c \
|
||||
usbd_msc.c \
|
||||
usbd_msc_data.c \
|
||||
usbd_msc_scsi.c
|
||||
|
||||
VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src:$(USBHID_DIR)/Src:$(USBMSC_DIR)/Src:$(STDPERIPH_DIR)/src
|
||||
|
||||
DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \
|
||||
$(USBCORE_SRC) \
|
||||
$(USBCDC_SRC) \
|
||||
$(USBHID_SRC) \
|
||||
$(USBMSC_SRC)
|
||||
|
||||
#CMSIS
|
||||
VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7xx
|
||||
VPATH := $(VPATH):$(STDPERIPH_DIR)/Src
|
||||
CMSIS_SRC :=
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(SRC_DIR)/startup/stm32 \
|
||||
$(STDPERIPH_DIR)/Inc \
|
||||
$(USBCORE_DIR)/Inc \
|
||||
$(USBCDC_DIR)/Inc \
|
||||
$(USBHID_DIR)/Inc \
|
||||
$(USBMSC_DIR)/Inc \
|
||||
$(CMSIS_DIR)/Core/Include \
|
||||
$(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \
|
||||
$(SRC_DIR)/drivers/mcu/stm32 \
|
||||
$(SRC_DIR)/drivers/mcu/stm32/vcp_hal
|
||||
|
||||
#Flags
|
||||
ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant
|
||||
|
||||
# Flags that are used in the STM32 libraries
|
||||
DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER
|
||||
|
||||
#
|
||||
# H743xI : 2M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xI also)
|
||||
# H743xG : 1M FLASH, 512KB AXI SRAM + 512KB D2 & D3 SRAM (H753xG also)
|
||||
# H7A3xI : 2M FLASH, 1MB AXI SRAM + 160KB AHB & SRD SRAM
|
||||
# H750xB : 128K FLASH, 1M RAM
|
||||
#
|
||||
ifeq ($(TARGET_MCU),STM32H743xx)
|
||||
DEVICE_FLAGS += -DSTM32H743xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h743xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
ifeq ($(RAM_BASED),yes)
|
||||
FIRMWARE_SIZE := 448
|
||||
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external storage device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h743.ld
|
||||
endif
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H7A3xxQ)
|
||||
DEVICE_FLAGS += -DSTM32H7A3xxQ
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h7a3xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
ifeq ($(RAM_BASED),yes)
|
||||
FIRMWARE_SIZE := 448
|
||||
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external storage device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
|
||||
endif
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H7A3xx)
|
||||
DEVICE_FLAGS += -DSTM32H7A3xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h7a3xx.s
|
||||
MCU_FLASH_SIZE := 2048
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
ifeq ($(RAM_BASED),yes)
|
||||
FIRMWARE_SIZE := 448
|
||||
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external storage device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_ram_based.ld
|
||||
endif
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H723xx)
|
||||
DEVICE_FLAGS += -DSTM32H723xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h723xx.s
|
||||
DEFAULT_TARGET_FLASH := 1024
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
ifeq ($(TARGET_FLASH),)
|
||||
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
|
||||
endif
|
||||
|
||||
ifeq ($(EXST),yes)
|
||||
FIRMWARE_SIZE := 1024
|
||||
# TARGET_FLASH now becomes the amount of MEMORY-MAPPED address space that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external flash device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h723_exst.ld
|
||||
LD_SCRIPTS = $(LINKER_DIR)/stm32_h723_common.ld $(LINKER_DIR)/stm32_h723_common_post.ld
|
||||
endif
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H725xx)
|
||||
DEVICE_FLAGS += -DSTM32H725xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h723xx.s
|
||||
MCU_FLASH_SIZE := 1024
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H730xx)
|
||||
DEVICE_FLAGS += -DSTM32H730xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h730_128m.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h730xx.s
|
||||
DEFAULT_TARGET_FLASH := 128
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
|
||||
|
||||
ifeq ($(TARGET_FLASH),)
|
||||
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
|
||||
endif
|
||||
|
||||
ifeq ($(EXST),yes)
|
||||
FIRMWARE_SIZE := 1024
|
||||
# TARGET_FLASH now becomes the amount of MEMORY-MAPPED address space that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external flash device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h730_exst.ld
|
||||
LD_SCRIPTS = $(LINKER_DIR)/stm32_h730_common.ld $(LINKER_DIR)/stm32_h730_common_post.ld
|
||||
endif
|
||||
|
||||
|
||||
else ifeq ($(TARGET_MCU),STM32H750xx)
|
||||
DEVICE_FLAGS += -DSTM32H750xx
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld
|
||||
STARTUP_SRC = stm32/startup_stm32h743xx.s
|
||||
DEFAULT_TARGET_FLASH := 128
|
||||
|
||||
ifeq ($(TARGET_FLASH),)
|
||||
MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH)
|
||||
endif
|
||||
|
||||
ifeq ($(EXST),yes)
|
||||
FIRMWARE_SIZE := 448
|
||||
# TARGET_FLASH now becomes the amount of RAM memory that is occupied by the firmware
|
||||
# and the maximum size of the data stored on the external storage device.
|
||||
MCU_FLASH_SIZE := FIRMWARE_SIZE
|
||||
DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h750_exst.ld
|
||||
endif
|
||||
|
||||
ifeq ($(EXST),yes)
|
||||
# Upper 8 regions are reserved for a boot loader in EXST environment
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=8
|
||||
else
|
||||
DEVICE_FLAGS += -DMAX_MPU_REGIONS=16
|
||||
endif
|
||||
|
||||
ifneq ($(DEBUG),GDB)
|
||||
OPTIMISE_DEFAULT := -Os
|
||||
OPTIMISE_SPEED := -Os
|
||||
OPTIMISE_SIZE := -Os
|
||||
|
||||
LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT)
|
||||
endif
|
||||
|
||||
else
|
||||
$(error Unknown MCU for H7 target)
|
||||
endif
|
||||
|
||||
ifeq ($(LD_SCRIPT),)
|
||||
LD_SCRIPT = $(DEFAULT_LD_SCRIPT)
|
||||
endif
|
||||
|
||||
ifneq ($(FIRMWARE_SIZE),)
|
||||
DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE)
|
||||
endif
|
||||
|
||||
DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 -DSTM32
|
||||
|
||||
VCP_SRC = \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_desc.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_conf_stm32h7xx.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_hid.c \
|
||||
drivers/mcu/stm32/vcp_hal/usbd_cdc_interface.c \
|
||||
drivers/mcu/stm32/serial_usb_vcp.c \
|
||||
drivers/usb_io.c
|
||||
|
||||
MCU_COMMON_SRC = \
|
||||
drivers/bus_i2c_timing.c \
|
||||
drivers/bus_quadspi.c \
|
||||
drivers/dshot_bitbang_decode.c \
|
||||
drivers/pwm_output_dshot_shared.c \
|
||||
drivers/mcu/stm32/adc_stm32h7xx.c \
|
||||
drivers/mcu/stm32/audio_stm32h7xx.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal_init.c \
|
||||
drivers/mcu/stm32/bus_i2c_hal.c \
|
||||
drivers/mcu/stm32/bus_spi_ll.c \
|
||||
drivers/mcu/stm32/bus_quadspi_hal.c \
|
||||
drivers/mcu/stm32/bus_octospi_stm32h7xx.c \
|
||||
drivers/mcu/stm32/debug.c \
|
||||
drivers/mcu/stm32/dma_reqmap_mcu.c \
|
||||
drivers/mcu/stm32/dma_stm32h7xx.c \
|
||||
drivers/mcu/stm32/dshot_bitbang_ll.c \
|
||||
drivers/mcu/stm32/dshot_bitbang.c \
|
||||
drivers/mcu/stm32/exti.c \
|
||||
drivers/mcu/stm32/io_stm32.c \
|
||||
drivers/mcu/stm32/light_ws2811strip_hal.c \
|
||||
drivers/mcu/stm32/memprot_hal.c \
|
||||
drivers/mcu/stm32/memprot_stm32h7xx.c \
|
||||
drivers/mcu/stm32/persistent.c \
|
||||
drivers/mcu/stm32/pwm_output.c \
|
||||
drivers/mcu/stm32/pwm_output_dshot_hal.c \
|
||||
drivers/mcu/stm32/rcc_stm32.c \
|
||||
drivers/mcu/stm32/sdio_h7xx.c \
|
||||
drivers/mcu/stm32/serial_uart_hal.c \
|
||||
drivers/mcu/stm32/serial_uart_stm32h7xx.c \
|
||||
drivers/mcu/stm32/system_stm32h7xx.c \
|
||||
drivers/mcu/stm32/timer_hal.c \
|
||||
drivers/mcu/stm32/timer_stm32h7xx.c \
|
||||
drivers/mcu/stm32/transponder_ir_io_hal.c \
|
||||
drivers/mcu/stm32/camera_control.c \
|
||||
startup/stm32/system_stm32h7xx.c
|
||||
|
||||
MCU_EXCLUDES = \
|
||||
drivers/bus_i2c.c
|
||||
|
||||
MSC_SRC = \
|
||||
drivers/mcu/stm32/usb_msc_hal.c \
|
||||
drivers/usb_msc_common.c \
|
||||
msc/usbd_storage.c \
|
||||
msc/usbd_storage_emfat.c \
|
||||
msc/emfat.c \
|
||||
msc/emfat_file.c \
|
||||
msc/usbd_storage_sd_spi.c \
|
||||
msc/usbd_storage_sdio.c
|
||||
|
||||
DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP
|
||||
DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7
|
|
@ -48,7 +48,6 @@ COMMON_SRC = \
|
|||
build/debug.c \
|
||||
build/debug_pin.c \
|
||||
build/version.c \
|
||||
$(TARGET_DIR_SRC) \
|
||||
main.c \
|
||||
$(PG_SRC) \
|
||||
common/bitarray.c \
|
||||
|
@ -98,6 +97,7 @@ COMMON_SRC = \
|
|||
drivers/bus_spi_config.c \
|
||||
drivers/bus_spi_pinconfig.c \
|
||||
drivers/buttons.c \
|
||||
drivers/camera_control.c \
|
||||
drivers/display.c \
|
||||
drivers/display_canvas.c \
|
||||
drivers/dma_common.c \
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue