diff --git a/Makefile b/Makefile index 3fdf458da4..baff3fae1a 100644 --- a/Makefile +++ b/Makefile @@ -58,6 +58,7 @@ FORKNAME = betaflight ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) PLATFORM_DIR := $(ROOT)/src/platform SRC_DIR := $(ROOT)/src/main +LIB_MAIN_DIR := $(ROOT)/lib/main OBJECT_DIR := $(ROOT)/obj/main BIN_DIR := $(ROOT)/obj CMSIS_DIR := $(ROOT)/lib/main/CMSIS @@ -109,7 +110,7 @@ include $(MAKE_SCRIPT_DIR)/$(OSFAMILY).mk include $(MAKE_SCRIPT_DIR)/tools.mk # Search path for sources -VPATH := $(SRC_DIR) +VPATH := $(SRC_DIR):$(LIB_MAIN_DIR):$(PLATFORM_DIR) FATFS_DIR = $(ROOT)/lib/main/FatFS FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') @@ -126,6 +127,7 @@ include $(MAKE_SCRIPT_DIR)/config.mk ifeq ($(CONFIG),) ifeq ($(TARGET),) TARGET := $(DEFAULT_TARGET) +SKIPCHECKS := yes endif endif @@ -138,7 +140,6 @@ CI_TARGETS := $(filter-out $(CI_EXCLUDED_TARGETS), $(BASE_TARGETS)) $(f TARGET_PLATFORM := $(notdir $(patsubst %/,%,$(subst target/$(TARGET)/,, $(dir $(wildcard $(PLATFORM_DIR)/*/target/$(TARGET)/target.mk))))) TARGET_PLATFORM_DIR := $(PLATFORM_DIR)/$(TARGET_PLATFORM) LINKER_DIR := $(TARGET_PLATFORM_DIR)/link -VPATH := $(VPATH):$(TARGET_PLATFORM_DIR):$(TARGET_PLATFORM_DIR)/startup:$(PLATFORM_DIR)/common include $(TARGET_PLATFORM_DIR)/target/$(TARGET)/target.mk @@ -196,8 +197,8 @@ ifneq ($(CONFIG),) TARGET_FLAGS := $(TARGET_FLAGS) -DUSE_CONFIG endif -SPEED_OPTIMISED_SRC := "" -SIZE_OPTIMISED_SRC := "" +SPEED_OPTIMISED_SRC := +SIZE_OPTIMISED_SRC := include $(TARGET_PLATFORM_DIR)/mk/$(TARGET_MCU_FAMILY).mk @@ -233,6 +234,12 @@ VPATH := $(VPATH):$(TARGET_DIR) include $(MAKE_SCRIPT_DIR)/source.mk +ifneq ($(SKIPCHECKS),yes) +ifneq ($(filter-out $(SRC),$(SPEED_OPTIMISED_SRC)),) +$(error Speed optimised sources not valid: $(strip $(filter-out $(SRC),$(SPEED_OPTIMISED_SRC)))) +endif +endif + ############################################################################### # Things that might need changing to use different tools # @@ -453,6 +460,11 @@ define compile_file $(CROSS_CC) -c -o $@ $(CFLAGS) $(2) $< endef +## `paths` is a list of paths that will be replaced for checking of speed, and size optimised sources +paths := $(SRC_DIR)/ $(LIB_MAIN_DIR)/ $(PLATFORM_DIR)/ +subst_paths_for = $(foreach path,$(paths),$(filter-out $(1),$(subst $(path),,$(1)))) +subst_paths = $(strip $(if $(call subst_paths_for,$(1)), $(call subst_paths_for,$(1)), $(1))) + ifeq ($(DEBUG),GDB) $(TARGET_OBJ_DIR)/%.o: %.c $(V1) mkdir -p $(dir $@) @@ -467,10 +479,10 @@ $(TARGET_OBJ_DIR)/%.o: %.c $(V1) $(if $(findstring $<,$(NOT_OPTIMISED_SRC)), \ $(call compile_file,not optimised,$(CC_NO_OPTIMISATION)) \ , \ - $(if $(findstring $(subst ./src/platform/,,$(subst ./src/main/,,$<)),$(SPEED_OPTIMISED_SRC)), \ + $(if $(findstring $(call subst_paths,$<),$(SPEED_OPTIMISED_SRC)), \ $(call compile_file,speed optimised,$(CC_SPEED_OPTIMISATION)) \ , \ - $(if $(findstring $(subst ./src/platform/,,$(subst ./src/main/,,$<)),$(SIZE_OPTIMISED_SRC)), \ + $(if $(findstring $(call subst_paths,$<),$(SIZE_OPTIMISED_SRC)), \ $(call compile_file,size optimised,$(CC_SIZE_OPTIMISATION)) \ , \ $(call compile_file,optimised,$(CC_DEFAULT_OPTIMISATION)) \ diff --git a/mk/source.mk b/mk/source.mk index 86b9110502..8129c737b7 100644 --- a/mk/source.mk +++ b/mk/source.mk @@ -275,6 +275,8 @@ COMMON_SRC = \ ifneq ($(SIMULATOR_BUILD),yes) COMMON_SRC += \ + drivers/bus_spi.c \ + drivers/serial_uart.c \ drivers/accgyro/accgyro_mpu3050.c \ drivers/accgyro/accgyro_mpu6050.c \ drivers/accgyro/accgyro_mpu6500.c \ @@ -293,7 +295,7 @@ COMMON_SRC += \ drivers/accgyro/accgyro_spi_mpu9250.c \ drivers/accgyro/accgyro_virtual.c \ drivers/accgyro/gyro_sync.c \ - $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ + BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ drivers/barometer/barometer_2smpb_02b.c \ drivers/barometer/barometer_bmp085.c \ drivers/barometer/barometer_bmp280.c \ @@ -322,13 +324,15 @@ ifneq ($(GYRO_DEFINE),) LEGACY_GYRO_DEFINES := USE_GYRO_L3GD20 ifneq ($(findstring $(GYRO_DEFINE),$(LEGACY_GYRO_DEFINES)),) -COMMON_SRC += \ +LEGACY_SRC := \ drivers/accgyro/legacy/accgyro_adxl345.c \ drivers/accgyro/legacy/accgyro_bma280.c \ drivers/accgyro/legacy/accgyro_l3g4200d.c \ drivers/accgyro/legacy/accgyro_lsm303dlhc.c \ drivers/accgyro/legacy/accgyro_mma845x.c +COMMON_SRC += $(LEGACY_SRC) +SPEED_OPTIMISED_SRC += $(LEGACY_SRC) endif endif @@ -376,6 +380,26 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(FATFS_DIR) VPATH := $(VPATH):$(FATFS_DIR) +# Gyro driver files that only contain initialization and configuration code - not runtime code +SIZE_OPTIMISED_SRC += \ + drivers/accgyro/accgyro_mpu6050.c \ + drivers/accgyro/accgyro_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu6000.c \ + drivers/accgyro/accgyro_spi_mpu6500.c \ + drivers/accgyro/accgyro_spi_mpu9250.c \ + drivers/accgyro/accgyro_spi_icm20689.c \ + drivers/accgyro/accgyro_spi_icm426xx.c \ + drivers/accgyro/accgyro_spi_lsm6dso_init.c + +SPEED_OPTIMISED_SRC += \ + drivers/bus_spi.c \ + drivers/serial_uart.c \ + drivers/accgyro/accgyro_mpu.c \ + drivers/accgyro/accgyro_mpu3050.c \ + drivers/accgyro/accgyro_spi_bmi160.c \ + drivers/accgyro/accgyro_spi_bmi270.c \ + drivers/accgyro/accgyro_spi_lsm6dso.c + endif COMMON_DEVICE_SRC = \ @@ -405,28 +429,11 @@ SPEED_OPTIMISED_SRC += \ common/stopwatch.c \ common/typeconversion.c \ common/vector.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu3050.c \ - drivers/accgyro/accgyro_spi_bmi160.c \ - drivers/accgyro/accgyro_spi_bmi270.c \ - drivers/accgyro/accgyro_spi_lsm6dso.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/buf_writer.c \ drivers/bus.c \ 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/timer.c \ fc/core.c \ fc/tasks.c \ fc/rc.c \ @@ -450,6 +457,7 @@ SPEED_OPTIMISED_SRC += \ rx/sumd.c \ rx/xbus.c \ rx/fport.c \ + rx/frsky_crc.c \ scheduler/scheduler.c \ sensors/acceleration.c \ sensors/boardalignment.c \ @@ -541,28 +549,6 @@ SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ io/vtx_msp.c \ cms/cms_menu_vtx_msp.c -# Gyro driver files that only contain initialization and configuration code - not runtime code -SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_spi_icm20689.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/accgyro/accgyro_spi_lsm6dso_init.c - - -# F4 and F7 optimizations -SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ - drivers/bus_i2c_hal.c \ - drivers/bus_spi_ll.c \ - rx/frsky_crc.c \ - drivers/max7456.c \ - drivers/pwm_output_dshot.c \ - drivers/pwm_output_dshot_shared.c \ - drivers/pwm_output_dshot_hal.c - SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ drivers/bus_i2c_hal_init.c @@ -590,10 +576,10 @@ SRC += $(VCP_SRC) # end target specific make file checks # Search path and source files for the Open Location Code library -OLC_DIR = $(ROOT)/lib/main/google/olc +OLC_DIR := google/olc ifneq ($(OLC_DIR),) -INCLUDE_DIRS += $(OLC_DIR) +INCLUDE_DIRS += $(LIB_MAIN_DIR)/$(OLC_DIR) SRC += $(OLC_DIR)/olc.c SIZE_OPTIMISED_SRC += $(OLC_DIR)/olc.c endif diff --git a/src/platform/APM32/mk/APM32F4.mk b/src/platform/APM32/mk/APM32F4.mk index 9792482a40..1c7d8c42a6 100644 --- a/src/platform/APM32/mk/APM32F4.mk +++ b/src/platform/APM32/mk/APM32F4.mk @@ -3,129 +3,126 @@ # #CMSIS -CMSIS_DIR := $(ROOT)/lib/main/APM32F4/Libraries/Device -STDPERIPH_DIR = $(ROOT)/lib/main/APM32F4/Libraries/APM32F4xx_DAL_Driver +CMSIS_DIR := $(LIB_MAIN_DIR)/APM32F4/Libraries/Device +STDPERIPH_DIR = $(LIB_MAIN_DIR)/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 + 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 +VPATH := $(VPATH):$(STDPERIPH_DIR)/Source #USB -USBCORE_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Core +USBCORE_DIR = APM32F4/Middlewares/APM32_USB_Library/Device/Core USBCORE_SRC = \ - usbd_core.c \ - usbd_dataXfer.c \ - usbd_stdReq.c + $(USBCORE_DIR)/Src/usbd_core.c \ + $(USBCORE_DIR)/Src/usbd_dataXfer.c \ + $(USBCORE_DIR)/Src/usbd_stdReq.c -USBCDC_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Class/CDC -USBCDC_SRC = usbd_cdc.c +USBCDC_DIR = APM32F4/Middlewares/APM32_USB_Library/Device/Class/CDC +USBCDC_SRC = \ + $(USBCDC_DIR)/Src/usbd_cdc.c -USBMSC_DIR = $(ROOT)/lib/main/APM32F4/Middlewares/APM32_USB_Library/Device/Class/MSC +USBMSC_DIR = APM32F4/Middlewares/APM32_USB_Library/Device/Class/MSC USBMSC_SRC = \ - usbd_msc.c \ - usbd_msc_bot.c \ - usbd_msc_scsi.c + $(USBMSC_DIR)/Src/usbd_msc.c \ + $(USBMSC_DIR)/Src/usbd_msc_bot.c \ + $(USBMSC_DIR)/Src/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) +DEVICE_STDPERIPH_SRC := \ + $(STDPERIPH_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) \ + $(USBMSC_SRC) #CMSIS -VPATH := $(VPATH):$(ROOT)/lib/main/APM32F4/Libraries/Device/Geehy/APM32F4xx +VPATH := $(VPATH):$(LIB_MAIN_DIR)/APM32F4/Libraries/Device/Geehy/APM32F4xx -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_PLATFORM_DIR)/startup \ - $(TARGET_PLATFORM_DIR) - -CMSIS_SRC := -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/Include \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ - $(CMSIS_DIR)/Geehy/APM32F4xx/Include \ - $(TARGET_PLATFORM_DIR)/usb/vcp \ - $(TARGET_PLATFORM_DIR)/usb/msc \ - $(TARGET_PLATFORM_DIR)/usb \ - $(ROOT)/lib/main/CMSIS/Core/Include \ - $(SRC_DIR)/msc +INCLUDE_DIRS += \ + $(TARGET_PLATFORM_DIR)/startup \ + $(TARGET_PLATFORM_DIR) \ + $(STDPERIPH_DIR)/Include \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/Inc \ + $(CMSIS_DIR)/Geehy/APM32F4xx/Include \ + $(TARGET_PLATFORM_DIR)/usb/vcp \ + $(TARGET_PLATFORM_DIR)/usb/msc \ + $(TARGET_PLATFORM_DIR)/usb \ + $(LIB_MAIN_DIR)/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 @@ -135,78 +132,76 @@ 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 = startup/startup_apm32f405xx.S +STARTUP_SRC = APM32/startup/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 = startup/startup_apm32f407xx.S +STARTUP_SRC = APM32/startup/startup_apm32f407xx.S MCU_FLASH_SIZE := 1024 else $(error TARGET_MCU [$(TARGET_MCU)] is not supported) endif MCU_COMMON_SRC = \ - stm32/system.c \ - startup/system_apm32f4xx.c \ - drivers/inverter.c \ - drivers/dshot_bitbang_decode.c \ - drivers/pwm_output_dshot_shared.c \ - bus_spi_apm32.c \ - bus_i2c_apm32.c \ - bus_i2c_apm32_init.c \ - camera_control_apm32.c \ - debug.c \ - dma_reqmap_mcu.c \ - dshot_bitbang.c \ - dshot_bitbang_ddl.c \ - eint_apm32.c \ - io_apm32.c \ - light_ws2811strip_apm32.c \ - persistent_apm32.c \ - pwm_output_apm32.c \ - pwm_output_dshot_apm32.c \ - rcm_apm32.c \ - serial_uart_apm32.c \ - timer_apm32.c \ - transponder_ir_io_apm32.c \ - timer_apm32f4xx.c \ - adc_apm32f4xx.c \ - dma_apm32f4xx.c \ - serial_uart_apm32f4xx.c \ - drivers/adc.c \ - drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ - drivers/bus_spi_config.c \ - drivers/bus_spi_pinconfig.c \ - drivers/serial_escserial.c \ - drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ - drivers/serial_uart_pinconfig.c \ - system_apm32f4xx.c + common/stm32/system.c \ + APM32/startup/system_apm32f4xx.c \ + drivers/inverter.c \ + drivers/dshot_bitbang_decode.c \ + drivers/pwm_output_dshot_shared.c \ + APM32/bus_spi_apm32.c \ + APM32/bus_i2c_apm32.c \ + APM32/bus_i2c_apm32_init.c \ + APM32/camera_control_apm32.c \ + APM32/debug.c \ + APM32/dma_reqmap_mcu.c \ + APM32/dshot_bitbang.c \ + APM32/dshot_bitbang_ddl.c \ + APM32/eint_apm32.c \ + APM32/io_apm32.c \ + APM32/light_ws2811strip_apm32.c \ + APM32/persistent_apm32.c \ + APM32/pwm_output_apm32.c \ + APM32/pwm_output_dshot_apm32.c \ + APM32/rcm_apm32.c \ + APM32/serial_uart_apm32.c \ + APM32/timer_apm32.c \ + APM32/transponder_ir_io_apm32.c \ + APM32/timer_apm32f4xx.c \ + APM32/adc_apm32f4xx.c \ + APM32/dma_apm32f4xx.c \ + APM32/serial_uart_apm32f4xx.c \ + drivers/adc.c \ + drivers/bus_i2c_config.c \ + drivers/bus_spi_config.c \ + drivers/bus_spi_pinconfig.c \ + drivers/serial_escserial.c \ + drivers/serial_pinconfig.c \ + drivers/serial_uart_pinconfig.c \ + APM32/system_apm32f4xx.c VCP_SRC = \ - usb/vcp/usbd_cdc_descriptor.c \ - usb/usbd_board_apm32f4.c \ - usb/vcp/usbd_cdc_vcp.c \ - usb/vcp/serial_usb_vcp.c \ - drivers/usb_io.c + APM32/usb/vcp/usbd_cdc_descriptor.c \ + APM32/usb/usbd_board_apm32f4.c \ + APM32/usb/vcp/usbd_cdc_vcp.c \ + APM32/usb/vcp/serial_usb_vcp.c \ + drivers/usb_io.c MSC_SRC = \ - drivers/usb_msc_common.c \ - usb/msc/usb_msc_apm32f4xx.c \ - usb/msc/usbd_memory.c \ - 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 + drivers/usb_msc_common.c \ + APM32/usb/msc/usb_msc_apm32f4xx.c \ + APM32/usb/msc/usbd_memory.c \ + 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 SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 -DUSE_FULL_DDL_DRIVER diff --git a/src/platform/AT32/mk/AT32F4.mk b/src/platform/AT32/mk/AT32F4.mk index 89305fe552..dda6847b9c 100644 --- a/src/platform/AT32/mk/AT32F4.mk +++ b/src/platform/AT32/mk/AT32F4.mk @@ -2,9 +2,9 @@ # 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 +CMSIS_DIR := $(LIB_MAIN_DIR)/AT32F43x/cmsis +STDPERIPH_DIR = $(LIB_MAIN_DIR)/AT32F43x/drivers +MIDDLEWARES_DIR = $(LIB_MAIN_DIR)/AT32F43x/middlewares STDPERIPH_SRC = \ at32f435_437_acc.c \ at32f435_437_adc.c \ @@ -45,9 +45,9 @@ STDPERIPH_SRC = \ usbd_class/msc/msc_class.c \ usbd_class/msc/msc_desc.c -STARTUP_SRC = startup/startup_at32f435_437.s +STARTUP_SRC = AT32/startup/startup_at32f435_437.s -VPATH := $(VPATH):$(ROOT)/lib/main/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/src:$(MIDDLEWARES_DIR):$(SRC_DIR)/startup/at32 +VPATH := $(VPATH):$(LIB_MAIN_DIR)/AT32F43x/cmsis/cm4/core_support:$(STDPERIPH_DIR)/src:$(MIDDLEWARES_DIR) VCP_SRC = \ usbd_class/cdc/cdc_class.c \ @@ -80,33 +80,33 @@ ARCH_FLAGS = -std=c99 -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi= DEVICE_FLAGS += -DUSE_ATBSP_DRIVER -DAT32F43x -DHSE_VALUE=$(HSE_VALUE) -DAT32 -DUSE_OTG_HOST_MODE MCU_COMMON_SRC = \ - stm32/system.c \ - startup/at32f435_437_clock.c \ - startup/system_at32f435_437.c \ - adc_at32f43x.c \ - bus_i2c_atbsp.c \ - bus_i2c_atbsp_init.c \ - bus_spi_at32bsp.c \ - camera_control_at32.c \ - debug.c \ - dma_at32f43x.c \ - dma_reqmap_mcu.c \ - dshot_bitbang.c \ - dshot_bitbang_stdperiph.c \ - exti_at32.c \ - io_at32.c \ - light_ws2811strip_at32f43x.c \ - persistent_at32bsp.c \ - pwm_output_at32bsp.c \ - pwm_output_dshot.c \ - rcc_at32.c \ - serial_uart_at32bsp.c \ - serial_uart_at32f43x.c \ - serial_usb_vcp_at32f4.c \ - system_at32f43x.c \ - timer_at32bsp.c \ - timer_at32f43x.c \ - usb_msc_at32f43x.c \ + common/stm32/system.c \ + AT32/startup/at32f435_437_clock.c \ + AT32/startup/system_at32f435_437.c \ + AT32/adc_at32f43x.c \ + AT32/bus_i2c_atbsp.c \ + AT32/bus_i2c_atbsp_init.c \ + AT32/bus_spi_at32bsp.c \ + AT32/camera_control_at32.c \ + AT32/debug.c \ + AT32/dma_at32f43x.c \ + AT32/dma_reqmap_mcu.c \ + AT32/dshot_bitbang.c \ + AT32/dshot_bitbang_stdperiph.c \ + AT32/exti_at32.c \ + AT32/io_at32.c \ + AT32/light_ws2811strip_at32f43x.c \ + AT32/persistent_at32bsp.c \ + AT32/pwm_output_at32bsp.c \ + AT32/pwm_output_dshot.c \ + AT32/rcc_at32.c \ + AT32/serial_uart_at32bsp.c \ + AT32/serial_uart_at32f43x.c \ + AT32/serial_usb_vcp_at32f4.c \ + AT32/system_at32f43x.c \ + AT32/timer_at32bsp.c \ + AT32/timer_at32f43x.c \ + AT32/usb_msc_at32f43x.c \ drivers/accgyro/accgyro_mpu.c \ drivers/dshot_bitbang_decode.c \ drivers/inverter.c \ @@ -116,12 +116,10 @@ MCU_COMMON_SRC = \ drivers/usb_msc_common.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ msc/usbd_storage.c \ msc/usbd_storage_emfat.c \ diff --git a/src/platform/PICO/mk/PICO.mk b/src/platform/PICO/mk/PICO.mk index 84acc3d098..699ee8f0fe 100644 --- a/src/platform/PICO/mk/PICO.mk +++ b/src/platform/PICO/mk/PICO.mk @@ -6,7 +6,7 @@ ifeq ($(DEBUG_HARDFAULTS),PICO) CFLAGS += -DDEBUG_HARDFAULTS endif -SDK_DIR = $(ROOT)/lib/main/pico-sdk +SDK_DIR = $(LIB_MAIN_DIR)/pico-sdk #CMSIS CMSIS_DIR := $(SDK_DIR)/rp2_common/cmsis/stub/CMSIS diff --git a/src/platform/SITL/dma_reqmap_mcu.h b/src/platform/SIMULATOR/dma_reqmap_mcu.h similarity index 100% rename from src/platform/SITL/dma_reqmap_mcu.h rename to src/platform/SIMULATOR/dma_reqmap_mcu.h diff --git a/src/platform/SITL/link/sitl.ld b/src/platform/SIMULATOR/link/sitl.ld similarity index 100% rename from src/platform/SITL/link/sitl.ld rename to src/platform/SIMULATOR/link/sitl.ld diff --git a/src/platform/SIMULATOR/mk/SITL.mk b/src/platform/SIMULATOR/mk/SITL.mk new file mode 100644 index 0000000000..6a2d8e8b9d --- /dev/null +++ b/src/platform/SIMULATOR/mk/SITL.mk @@ -0,0 +1,57 @@ + +INCLUDE_DIRS := \ + $(INCLUDE_DIRS) \ + $(TARGET_PLATFORM_DIR) \ + $(LIB_MAIN_DIR)/dyad + +MCU_COMMON_SRC := \ + $(LIB_MAIN_DIR)/dyad/dyad.c \ + SIMULATOR/sitl.c \ + SIMULATOR/udplink.c + +#Flags +ARCH_FLAGS = +DEVICE_FLAGS = +LD_SCRIPT = $(LINKER_DIR)/sitl.ld +STARTUP_SRC = + +MCU_FLASH_SIZE := 2048 + +ARM_SDK_PREFIX = + +MCU_EXCLUDES = \ + 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 diff --git a/src/platform/SITL/platform_mcu.h b/src/platform/SIMULATOR/platform_mcu.h similarity index 100% rename from src/platform/SITL/platform_mcu.h rename to src/platform/SIMULATOR/platform_mcu.h diff --git a/src/platform/SITL/sitl.c b/src/platform/SIMULATOR/sitl.c similarity index 100% rename from src/platform/SITL/sitl.c rename to src/platform/SIMULATOR/sitl.c diff --git a/src/platform/SITL/target/SITL/README.md b/src/platform/SIMULATOR/target/SITL/README.md similarity index 100% rename from src/platform/SITL/target/SITL/README.md rename to src/platform/SIMULATOR/target/SITL/README.md diff --git a/src/platform/SITL/target/SITL/target.h b/src/platform/SIMULATOR/target/SITL/target.h similarity index 100% rename from src/platform/SITL/target/SITL/target.h rename to src/platform/SIMULATOR/target/SITL/target.h diff --git a/src/platform/SITL/target/SITL/target.mk b/src/platform/SIMULATOR/target/SITL/target.mk similarity index 88% rename from src/platform/SITL/target/SITL/target.mk rename to src/platform/SIMULATOR/target/SITL/target.mk index 7429467dcb..97a4d2bd2d 100644 --- a/src/platform/SITL/target/SITL/target.mk +++ b/src/platform/SIMULATOR/target/SITL/target.mk @@ -1,4 +1,4 @@ -TARGET_MCU := SITL +TARGET_MCU := SIMULATOR TARGET_MCU_FAMILY := SITL SIMULATOR_BUILD = yes diff --git a/src/platform/SITL/timer_def.h b/src/platform/SIMULATOR/timer_def.h similarity index 100% rename from src/platform/SITL/timer_def.h rename to src/platform/SIMULATOR/timer_def.h diff --git a/src/platform/SITL/udplink.c b/src/platform/SIMULATOR/udplink.c similarity index 100% rename from src/platform/SITL/udplink.c rename to src/platform/SIMULATOR/udplink.c diff --git a/src/platform/SITL/udplink.h b/src/platform/SIMULATOR/udplink.h similarity index 100% rename from src/platform/SITL/udplink.h rename to src/platform/SIMULATOR/udplink.h diff --git a/src/platform/SITL/mk/SITL.mk b/src/platform/SITL/mk/SITL.mk deleted file mode 100644 index f9d585d1dd..0000000000 --- a/src/platform/SITL/mk/SITL.mk +++ /dev/null @@ -1,55 +0,0 @@ - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_PLATFORM_DIR) \ - $(ROOT)/lib/main/dyad - -MCU_COMMON_SRC := $(ROOT)/lib/main/dyad/dyad.c \ - sitl.c \ - udplink.c - -#Flags -ARCH_FLAGS = -DEVICE_FLAGS = -LD_SCRIPT = $(LINKER_DIR)/sitl.ld -STARTUP_SRC = - -MCU_FLASH_SIZE := 2048 - -ARM_SDK_PREFIX = - -MCU_EXCLUDES = \ - 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 diff --git a/src/platform/STM32/mk/STM32F4.mk b/src/platform/STM32/mk/STM32F4.mk index ed0274e80a..e9a37cb186 100644 --- a/src/platform/STM32/mk/STM32F4.mk +++ b/src/platform/STM32/mk/STM32F4.mk @@ -4,16 +4,16 @@ #CMSIS ifeq ($(PERIPH_DRIVER), HAL) -CMSIS_DIR := $(ROOT)/lib/main/STM32F4/Drivers/CMSIS -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4/Drivers/STM32F4xx_HAL_Driver +CMSIS_DIR := $(LIB_MAIN_DIR)/STM32F4/Drivers/CMSIS +STDPERIPH_DIR = $(LIB_MAIN_DIR)/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 +CMSIS_DIR := $(LIB_MAIN_DIR)/CMSIS +STDPERIPH_DIR = $(LIB_MAIN_DIR)/STM32F4/Drivers/STM32F4xx_StdPeriph_Driver STDPERIPH_SRC = \ misc.c \ stm32f4xx_adc.c \ @@ -48,12 +48,12 @@ endif ifeq ($(PERIPH_DRIVER), HAL) #USB -USBCORE_DIR = $(ROOT)/lib/main/STM32F4/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_DIR = $(LIB_MAIN_DIR)/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_DIR = $(LIB_MAIN_DIR)/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)) @@ -65,35 +65,37 @@ DEVICE_STDPERIPH_SRC := \ $(USBCORE_SRC) \ $(USBCDC_SRC) else -USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core +USBCORE_DIR = STM32_USB_Device_Library/Core USBCORE_SRC = \ - usbd_core.c \ - usbd_ioreq.c \ - usbd_req.c + $(USBCORE_DIR)/src/usbd_core.c \ + $(USBCORE_DIR)/src/usbd_ioreq.c \ + $(USBCORE_DIR)/src/usbd_req.c -USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver +USBOTG_DIR = STM32_USB_OTG_Driver USBOTG_SRC = \ - usb_core.c \ - usb_dcd.c \ - usb_dcd_int.c + $(USBOTG_DIR)/src/usb_core.c \ + $(USBOTG_DIR)/src/usb_dcd.c \ + $(USBOTG_DIR)/src/usb_dcd_int.c -USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc -USBCDC_SRC = usbd_cdc_core.c +USBCDC_DIR = STM32_USB_Device_Library/Class/cdc +USBCDC_SRC = \ + $(USBCDC_DIR)/src/usbd_cdc_core.c -USBMSC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/msc +USBMSC_DIR = STM32_USB_Device_Library/Class/msc USBMSC_SRC = \ - usbd_msc_bot.c \ - usbd_msc_core.c \ - usbd_msc_data.c \ - usbd_msc_scsi.c + $(USBMSC_DIR)/src/usbd_msc_bot.c \ + $(USBMSC_DIR)/src/usbd_msc_core.c \ + $(USBMSC_DIR)/src/usbd_msc_data.c \ + $(USBMSC_DIR)/src/usbd_msc_scsi.c -USBHID_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/hid -USBHID_SRC = usbd_hid_core.c +USBHID_DIR = STM32_USB_Device_Library/Class/hid +USBHID_SRC = \ + $(USBHID_DIR)/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 +USBWRAPPER_DIR = STM32_USB_Device_Library/Class/hid_cdc_wrapper +USBWRAPPER_SRC = \ + $(USBWRAPPER_DIR)/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) \ @@ -106,12 +108,7 @@ DEVICE_STDPERIPH_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 +VPATH := $(VPATH):$(CMSIS_DIR)/Core/Include:$(LIB_MAIN_DIR)/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx ifeq ($(PERIPH_DRIVER), HAL) CMSIS_SRC := @@ -120,8 +117,8 @@ INCLUDE_DIRS := \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ $(CMSIS_DIR)/Include \ $(CMSIS_DIR)/Device/ST/STM32F4xx/Include \ $(TARGET_PLATFORM_DIR)/vcp_hal @@ -135,14 +132,14 @@ INCLUDE_DIRS := \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/inc \ - $(USBOTG_DIR)/inc \ - $(USBCORE_DIR)/inc \ - $(USBCDC_DIR)/inc \ - $(USBHID_DIR)/inc \ - $(USBWRAPPER_DIR)/inc \ - $(USBMSC_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBOTG_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBHID_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBWRAPPER_DIR)/inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/inc \ $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx \ + $(LIB_MAIN_DIR)/STM32F4/Drivers/CMSIS/Device/ST/STM32F4xx \ $(TARGET_PLATFORM_DIR)/vcpf4 endif @@ -152,19 +149,19 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu ifeq ($(TARGET_MCU),STM32F411xE) DEVICE_FLAGS = -DSTM32F411xE -finline-limit=20 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld -STARTUP_SRC = startup/startup_stm32f411xe.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32f40xx.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32f446xx.s +STARTUP_SRC = STM32/startup/startup_stm32f446xx.s MCU_FLASH_SIZE := 512 else @@ -173,71 +170,70 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32 MCU_COMMON_SRC = \ - stm32/system.c \ + common/stm32/system.c \ drivers/accgyro/accgyro_mpu.c \ drivers/dshot_bitbang_decode.c \ drivers/inverter.c \ drivers/pwm_output_dshot_shared.c \ - pwm_output_dshot.c \ - adc_stm32f4xx.c \ - bus_i2c_stm32f4xx.c \ - bus_spi_stdperiph.c \ - debug.c \ - dma_reqmap_mcu.c \ - dma_stm32f4xx.c \ - dshot_bitbang.c \ - dshot_bitbang_stdperiph.c \ - exti.c \ - io_stm32.c \ - light_ws2811strip_stdperiph.c \ - persistent.c \ - pwm_output.c \ - rcc_stm32.c \ - sdio_f4xx.c \ - serial_uart_stdperiph.c \ - serial_uart_stm32f4xx.c \ - system_stm32f4xx.c \ - timer_stdperiph.c \ - timer_stm32f4xx.c \ - transponder_ir_io_stdperiph.c \ - usbd_msc_desc.c \ - camera_control_stm32.c \ + STM32/pwm_output_dshot.c \ + STM32/adc_stm32f4xx.c \ + STM32/bus_i2c_stm32f4xx.c \ + STM32/bus_spi_stdperiph.c \ + STM32/debug.c \ + STM32/dma_reqmap_mcu.c \ + STM32/dma_stm32f4xx.c \ + STM32/dshot_bitbang.c \ + STM32/dshot_bitbang_stdperiph.c \ + STM32/exti.c \ + STM32/io_stm32.c \ + STM32/light_ws2811strip_stdperiph.c \ + STM32/persistent.c \ + STM32/pwm_output.c \ + STM32/rcc_stm32.c \ + STM32/sdio_f4xx.c \ + STM32/serial_uart_stdperiph.c \ + STM32/serial_uart_stm32f4xx.c \ + STM32/system_stm32f4xx.c \ + STM32/timer_stdperiph.c \ + STM32/timer_stm32f4xx.c \ + STM32/transponder_ir_io_stdperiph.c \ + STM32/usbd_msc_desc.c \ + STM32/camera_control_stm32.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ - startup/system_stm32f4xx.c + STM32/startup/system_stm32f4xx.c SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c \ + STM32/exti.c ifeq ($(PERIPH_DRIVER), HAL) VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf.c \ - vcp_hal/usbd_cdc_interface.c \ - serial_usb_vcp.c \ + STM32/vcp_hal/usbd_desc.c \ + STM32/vcp_hal/usbd_conf.c \ + STM32/vcp_hal/usbd_cdc_interface.c \ + STM32/serial_usb_vcp.c \ drivers/usb_io.c else VCP_SRC = \ - vcpf4/stm32f4xx_it.c \ - vcpf4/usb_bsp.c \ - vcpf4/usbd_desc.c \ - vcpf4/usbd_usr.c \ - vcpf4/usbd_cdc_vcp.c \ - vcpf4/usb_cdc_hid.c \ - serial_usb_vcp.c \ + STM32/vcpf4/stm32f4xx_it.c \ + STM32/vcpf4/usb_bsp.c \ + STM32/vcpf4/usbd_desc.c \ + STM32/vcpf4/usbd_usr.c \ + STM32/vcpf4/usbd_cdc_vcp.c \ + STM32/vcpf4/usb_cdc_hid.c \ + STM32/serial_usb_vcp.c \ drivers/usb_io.c endif MSC_SRC = \ drivers/usb_msc_common.c \ - usb_msc_f4xx.c \ + STM32/usb_msc_f4xx.c \ msc/usbd_storage.c \ msc/usbd_storage_emfat.c \ msc/emfat.c \ @@ -245,5 +241,5 @@ MSC_SRC = \ msc/usbd_storage_sd_spi.c \ msc/usbd_storage_sdio.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/src/platform/STM32/mk/STM32F7.mk b/src/platform/STM32/mk/STM32F7.mk index 2084b5621a..9c29481815 100644 --- a/src/platform/STM32/mk/STM32F7.mk +++ b/src/platform/STM32/mk/STM32F7.mk @@ -7,10 +7,10 @@ CFLAGS += -DDEBUG_HARDFAULTS endif #CMSIS -CMSIS_DIR := $(ROOT)/lib/main/CMSIS +CMSIS_DIR := $(LIB_MAIN_DIR)/CMSIS #STDPERIPH -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7/Drivers/STM32F7xx_HAL_Driver +STDPERIPH_DIR = $(LIB_MAIN_DIR)/STM32F7/Drivers/STM32F7xx_HAL_Driver STDPERIPH_SRC = \ stm32f7xx_hal_adc.c \ stm32f7xx_hal_adc_ex.c \ @@ -51,49 +51,48 @@ STDPERIPH_SRC = \ stm32f7xx_ll_utils.c #USB -USBCORE_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_DIR = STM32F7/Middlewares/ST/STM32_USB_Device_Library/Core USBCORE_SRC = \ - usbd_core.c \ - usbd_ctlreq.c \ - usbd_ioreq.c + $(USBCORE_DIR)/Src/usbd_core.c \ + $(USBCORE_DIR)/Src/usbd_ctlreq.c \ + $(USBCORE_DIR)/Src/usbd_ioreq.c -USBCDC_DIR = $(ROOT)/lib/main/STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC -USBCDC_SRC = usbd_cdc.c +USBCDC_DIR = STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC +USBCDC_SRC = \ + $(USBCDC_DIR)/Src/usbd_cdc.c +USBHID_DIR = STM32F7/Middlewares/ST/STM32_USB_Device_Library/Class/HID +USBHID_SRC = \ + $(USBHID_DIR)/Src/usbd_hid.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_DIR = 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 + $(USBMSC_DIR)/Src/usbd_msc_bot.c \ + $(USBMSC_DIR)/Src/usbd_msc.c \ + $(USBMSC_DIR)/Src/usbd_msc_data.c \ + $(USBMSC_DIR)/Src/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) +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 +VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32F7xx:$(STDPERIPH_DIR)/Src CMSIS_SRC := INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBHID_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBHID_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \ + $(LIB_MAIN_DIR)/STM32F7/Drivers/CMSIS/Device/ST/STM32F7xx/Include \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags @@ -105,24 +104,24 @@ 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 = startup/startup_stm32f765xx.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32f745xx.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32f746xx.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32f722xx.s +STARTUP_SRC = STM32/startup/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. @@ -133,58 +132,56 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32 VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf_stm32f7xx.c \ - vcp_hal/usbd_cdc_hid.c \ - vcp_hal/usbd_cdc_interface.c \ - serial_usb_vcp.c \ + STM32/vcp_hal/usbd_desc.c \ + STM32/vcp_hal/usbd_conf_stm32f7xx.c \ + STM32/vcp_hal/usbd_cdc_hid.c \ + STM32/vcp_hal/usbd_cdc_interface.c \ + STM32/serial_usb_vcp.c \ drivers/usb_io.c MCU_COMMON_SRC = \ - stm32/system.c \ + common/stm32/system.c \ drivers/accgyro/accgyro_mpu.c \ drivers/bus_i2c_timing.c \ drivers/dshot_bitbang_decode.c \ drivers/pwm_output_dshot_shared.c \ - adc_stm32f7xx.c \ - audio_stm32f7xx.c \ - bus_i2c_hal_init.c \ - bus_i2c_hal.c \ - bus_spi_ll.c \ - debug.c \ - dma_reqmap_mcu.c \ - dma_stm32f7xx.c \ - dshot_bitbang_ll.c \ - dshot_bitbang.c \ - exti.c \ - io_stm32.c \ - light_ws2811strip_hal.c \ - persistent.c \ - pwm_output.c \ - pwm_output_dshot_hal.c \ - rcc_stm32.c \ - sdio_f7xx.c \ - serial_uart_hal.c \ - serial_uart_stm32f7xx.c \ - system_stm32f7xx.c \ - timer_hal.c \ - timer_stm32f7xx.c \ - transponder_ir_io_hal.c \ - camera_control_stm32.c \ + STM32/adc_stm32f7xx.c \ + STM32/audio_stm32f7xx.c \ + STM32/bus_i2c_hal_init.c \ + STM32/bus_i2c_hal.c \ + STM32/bus_spi_ll.c \ + STM32/debug.c \ + STM32/dma_reqmap_mcu.c \ + STM32/dma_stm32f7xx.c \ + STM32/dshot_bitbang_ll.c \ + STM32/dshot_bitbang.c \ + STM32/exti.c \ + STM32/io_stm32.c \ + STM32/light_ws2811strip_hal.c \ + STM32/persistent.c \ + STM32/pwm_output.c \ + STM32/pwm_output_dshot_hal.c \ + STM32/rcc_stm32.c \ + STM32/sdio_f7xx.c \ + STM32/serial_uart_hal.c \ + STM32/serial_uart_stm32f7xx.c \ + STM32/system_stm32f7xx.c \ + STM32/timer_hal.c \ + STM32/timer_stm32f7xx.c \ + STM32/transponder_ir_io_hal.c \ + STM32/camera_control_stm32.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ - startup/system_stm32f7xx.c + STM32/startup/system_stm32f7xx.c MSC_SRC = \ drivers/usb_msc_common.c \ - usb_msc_hal.c \ + STM32/usb_msc_hal.c \ msc/usbd_storage.c \ msc/usbd_storage_emfat.c \ msc/emfat.c \ @@ -193,7 +190,13 @@ MSC_SRC = \ msc/usbd_storage_sd_spi.c SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c \ + STM32/bus_i2c_hal.c \ + STM32/bus_spi_ll.c \ + drivers/max7456.c \ + drivers/pwm_output_dshot_shared.c \ + STM32/pwm_output_dshot_hal.c \ + STM32/exti.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7 diff --git a/src/platform/STM32/mk/STM32G4.mk b/src/platform/STM32/mk/STM32G4.mk index 923aca727a..4131430398 100644 --- a/src/platform/STM32/mk/STM32G4.mk +++ b/src/platform/STM32/mk/STM32G4.mk @@ -7,10 +7,10 @@ CFLAGS += -DDEBUG_HARDFAULTS endif #CMSIS -CMSIS_DIR := $(ROOT)/lib/main/CMSIS +CMSIS_DIR := $(LIB_MAIN_DIR)/CMSIS #STDPERIPH -STDPERIPH_DIR = $(ROOT)/lib/main/STM32G4/Drivers/STM32G4xx_HAL_Driver +STDPERIPH_DIR = $(LIB_MAIN_DIR)/STM32G4/Drivers/STM32G4xx_HAL_Driver STDPERIPH_SRC = \ stm32g4xx_hal_adc.c \ stm32g4xx_hal_adc_ex.c \ @@ -44,26 +44,26 @@ STDPERIPH_SRC = \ stm32g4xx_ll_usb.c #USB -USBCORE_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_DIR = STM32G4/Middlewares/ST/STM32_USB_Device_Library/Core USBCORE_SRC = \ - usbd_core.c \ - usbd_ctlreq.c \ - usbd_ioreq.c + $(USBCORE_DIR)/Src/usbd_core.c \ + $(USBCORE_DIR)/Src/usbd_ctlreq.c \ + $(USBCORE_DIR)/Src/usbd_ioreq.c -USBCDC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC -USBCDC_SRC = usbd_cdc.c +USBCDC_DIR = STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/CDC +USBCDC_SRC = \ + $(USBCDC_DIR)/Src/usbd_cdc.c -USBHID_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/HID -USBHID_SRC = usbd_hid.c +USBHID_DIR = STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/HID +USBHID_SRC = \ + $(USBHID_DIR)/Src/usbd_hid.c -USBMSC_DIR = $(ROOT)/lib/main/STM32G4/Middlewares/ST/STM32_USB_Device_Library/Class/MSC +USBMSC_DIR = 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 + $(USBMSC_DIR)/Src/usbd_msc_bot.c \ + $(USBMSC_DIR)/Src/usbd_msc.c \ + $(USBMSC_DIR)/Src/usbd_msc_data.c \ + $(USBMSC_DIR)/Src/usbd_msc_scsi.c DEVICE_STDPERIPH_SRC := \ $(STDPERIPH_SRC) \ @@ -73,20 +73,19 @@ DEVICE_STDPERIPH_SRC := \ $(USBMSC_SRC) #CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32G4xx -VPATH := $(VPATH):$(STDPERIPH_DIR)/Src +VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32G4xx:$(STDPERIPH_DIR)/Src CMSIS_SRC := INCLUDE_DIRS := \ $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBHID_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBHID_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \ + $(LIB_MAIN_DIR)/STM32G4/Drivers/CMSIS/Device/ST/STM32G4xx/Include \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags @@ -99,7 +98,7 @@ DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER -DUSE_DMA_RAM -DMAX_MPU_ ifeq ($(TARGET_MCU),STM32G474xx) DEVICE_FLAGS += -DSTM32G474xx LD_SCRIPT = $(LINKER_DIR)/stm32_flash_g474.ld -STARTUP_SRC = startup/startup_stm32g474xx.s +STARTUP_SRC = STM32/startup/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. @@ -110,59 +109,57 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DSTM32 VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf_stm32g4xx.c \ - vcp_hal/usbd_cdc_hid.c \ - vcp_hal/usbd_cdc_interface.c \ - serial_usb_vcp.c \ + STM32/vcp_hal/usbd_desc.c \ + STM32/vcp_hal/usbd_conf_stm32g4xx.c \ + STM32/vcp_hal/usbd_cdc_hid.c \ + STM32/vcp_hal/usbd_cdc_interface.c \ + STM32/serial_usb_vcp.c \ drivers/usb_io.c MCU_COMMON_SRC = \ - stm32/system.c \ + common/stm32/system.c \ drivers/accgyro/accgyro_mpu.c \ drivers/bus_i2c_timing.c \ drivers/dshot_bitbang_decode.c \ drivers/pwm_output_dshot_shared.c \ - adc_stm32g4xx.c \ - bus_i2c_hal_init.c \ - bus_i2c_hal.c \ - bus_spi_ll.c \ - debug.c \ - dma_reqmap_mcu.c \ - dma_stm32g4xx.c \ - dshot_bitbang_ll.c \ - dshot_bitbang.c \ - exti.c \ - io_stm32.c \ - light_ws2811strip_hal.c \ - memprot_hal.c \ - memprot_stm32g4xx.c \ - persistent.c \ - pwm_output.c \ - pwm_output_dshot_hal.c \ - rcc_stm32.c \ - serial_uart_hal.c \ - serial_uart_stm32g4xx.c \ - system_stm32g4xx.c \ - timer_hal.c \ - timer_stm32g4xx.c \ - transponder_ir_io_hal.c \ - camera_control_stm32.c \ + STM32/adc_stm32g4xx.c \ + STM32/bus_i2c_hal_init.c \ + STM32/bus_i2c_hal.c \ + STM32/bus_spi_ll.c \ + STM32/debug.c \ + STM32/dma_reqmap_mcu.c \ + STM32/dma_stm32g4xx.c \ + STM32/dshot_bitbang_ll.c \ + STM32/dshot_bitbang.c \ + STM32/exti.c \ + STM32/io_stm32.c \ + STM32/light_ws2811strip_hal.c \ + STM32/memprot_hal.c \ + STM32/memprot_stm32g4xx.c \ + STM32/persistent.c \ + STM32/pwm_output.c \ + STM32/pwm_output_dshot_hal.c \ + STM32/rcc_stm32.c \ + STM32/serial_uart_hal.c \ + STM32/serial_uart_stm32g4xx.c \ + STM32/system_stm32g4xx.c \ + STM32/timer_hal.c \ + STM32/timer_stm32g4xx.c \ + STM32/transponder_ir_io_hal.c \ + STM32/camera_control_stm32.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ - startup/system_stm32g4xx.c + STM32/startup/system_stm32g4xx.c # G4's MSC use the same driver layer file with F7 MSC_SRC = \ drivers/usb_msc_common.c \ - usb_msc_hal.c \ + STM32/usb_msc_hal.c \ msc/usbd_storage.c \ msc/usbd_storage_emfat.c \ msc/emfat.c \ @@ -171,7 +168,8 @@ MSC_SRC = \ msc/usbd_storage_sd_spi.c SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c \ + STM32/exti.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM4 diff --git a/src/platform/STM32/mk/STM32H5.mk b/src/platform/STM32/mk/STM32H5.mk index 11cdf5d64c..b6c1682c7b 100644 --- a/src/platform/STM32/mk/STM32H5.mk +++ b/src/platform/STM32/mk/STM32H5.mk @@ -7,10 +7,10 @@ CFLAGS += -DDEBUG_HARDFAULTS endif #CMSIS -CMSIS_DIR := $(ROOT)/lib/main/CMSIS +CMSIS_DIR := $(LIB_MAIN_DIR)/CMSIS #STDPERIPH -STDPERIPH_DIR = $(ROOT)/lib/main/STM32H5/Drivers/STM32H5xx_HAL_Driver +STDPERIPH_DIR = $(LIB_MAIN_DIR)/STM32H5/Drivers/STM32H5xx_HAL_Driver STDPERIPH_SRC = \ stm32h5xx_hal_adc.c \ stm32h5xx_hal_adc_ex.c \ @@ -69,7 +69,7 @@ STDPERIPH_SRC = \ 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_DIR = $(LIB_MAIN_DIR)/STM32H5/Middlewares/ST/usbx/Common #USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c)) #EXCLUDES = #USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC)) @@ -83,19 +83,18 @@ DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ $(USBMSC_SRC) #CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H5xx -VPATH := $(VPATH):$(STDPERIPH_DIR)/Src +VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H5xx:$(STDPERIPH_DIR)/Src CMSIS_SRC := INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBHID_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBHID_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32H5/Drivers/CMSIS/Device/ST/STM32H5xx/Include \ + $(LIB_MAIN_DIR)/STM32H5/Drivers/CMSIS/Device/ST/STM32H5xx/Include \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags @@ -110,7 +109,7 @@ DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER ifeq ($(TARGET_MCU),STM32H563xx) DEVICE_FLAGS += -DSTM32H563xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h563_2m.ld -STARTUP_SRC = startup/startup_stm32h563xx.s +STARTUP_SRC = STM32/startup/startup_stm32h563xx.s MCU_FLASH_SIZE := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -149,41 +148,39 @@ VCP_SRC = drivers/usb_io.c MCU_COMMON_SRC = \ - stm32/system.c \ + common/stm32/system.c \ drivers/bus_i2c_timing.c \ drivers/bus_quadspi.c \ drivers/dshot_bitbang_decode.c \ drivers/pwm_output_dshot_shared.c \ - bus_i2c_hal_init.c \ - bus_i2c_hal.c \ - bus_spi_ll.c \ - bus_quadspi_hal.c \ - debug.c \ - dma_reqmap_mcu.c \ - dshot_bitbang_ll.c \ - dshot_bitbang.c \ - exti.c \ - io_stm32.c \ - light_ws2811strip_hal.c \ - persistent.c \ - pwm_output.c \ - pwm_output_dshot_hal.c \ - rcc_stm32.c \ - serial_uart_hal.c \ - timer_hal.c \ - transponder_ir_io_hal.c \ - camera_control_stm32.c \ - system_stm32h5xx.c \ + STM32/bus_i2c_hal_init.c \ + STM32/bus_i2c_hal.c \ + STM32/bus_spi_ll.c \ + STM32/bus_quadspi_hal.c \ + STM32/debug.c \ + STM32/dma_reqmap_mcu.c \ + STM32/dshot_bitbang_ll.c \ + STM32/dshot_bitbang.c \ + STM32/exti.c \ + STM32/io_stm32.c \ + STM32/light_ws2811strip_hal.c \ + STM32/persistent.c \ + STM32/pwm_output.c \ + STM32/pwm_output_dshot_hal.c \ + STM32/rcc_stm32.c \ + STM32/serial_uart_hal.c \ + STM32/timer_hal.c \ + STM32/transponder_ir_io_hal.c \ + STM32/camera_control_stm32.c \ + STM32/system_stm32h5xx.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ - startup/system_stm32h5xx.c + STM32/startup/system_stm32h5xx.c # memprot_hal.c \ # memprot_stm32h5xx.c \ @@ -205,7 +202,8 @@ MSC_SRC = msc/usbd_storage_sdio.c SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c \ + STM32/exti.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7 diff --git a/src/platform/STM32/mk/STM32H7.mk b/src/platform/STM32/mk/STM32H7.mk index 0639cff249..5651cbd122 100644 --- a/src/platform/STM32/mk/STM32H7.mk +++ b/src/platform/STM32/mk/STM32H7.mk @@ -7,10 +7,10 @@ CFLAGS += -DDEBUG_HARDFAULTS endif #CMSIS -CMSIS_DIR := $(ROOT)/lib/main/CMSIS +CMSIS_DIR := $(LIB_MAIN_DIR)/CMSIS #STDPERIPH -STDPERIPH_DIR = $(ROOT)/lib/main/STM32H7/Drivers/STM32H7xx_HAL_Driver +STDPERIPH_DIR = $(LIB_MAIN_DIR)/STM32H7/Drivers/STM32H7xx_HAL_Driver STDPERIPH_SRC = \ stm32h7xx_hal_adc.c \ stm32h7xx_hal_adc_ex.c \ @@ -59,26 +59,26 @@ STDPERIPH_SRC = \ stm32h7xx_ll_usb.c #USB -USBCORE_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_DIR = STM32H7/Middlewares/ST/STM32_USB_Device_Library/Core USBCORE_SRC = \ - usbd_core.c \ - usbd_ctlreq.c \ - usbd_ioreq.c + $(USBCORE_DIR)/Src/usbd_core.c \ + $(USBCORE_DIR)/Src/usbd_ctlreq.c \ + $(USBCORE_DIR)/Src/usbd_ioreq.c -USBCDC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC -USBCDC_SRC = usbd_cdc.c +USBCDC_DIR = STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/CDC +USBCDC_SRC = \ + $(USBCDC_DIR)/Src/usbd_cdc.c -USBHID_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID -USBHID_SRC = usbd_hid.c +USBHID_DIR = STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/HID +USBHID_SRC = \ + $(USBHID_DIR)/Src/usbd_hid.c -USBMSC_DIR = $(ROOT)/lib/main/STM32H7/Middlewares/ST/STM32_USB_Device_Library/Class/MSC +USBMSC_DIR = 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 + $(USBMSC_DIR)/Src/usbd_msc_bot.c \ + $(USBMSC_DIR)/Src/usbd_msc.c \ + $(USBMSC_DIR)/Src/usbd_msc_data.c \ + $(USBMSC_DIR)/Src/usbd_msc_scsi.c DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ $(USBCORE_SRC) \ @@ -87,19 +87,18 @@ DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ $(USBMSC_SRC) #CMSIS -VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7xx -VPATH := $(VPATH):$(STDPERIPH_DIR)/Src +VPATH := $(VPATH):$(CMSIS_DIR)/Include:$(CMSIS_DIR)/Device/ST/STM32H7xx:$(STDPERIPH_DIR)/Src CMSIS_SRC := INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(TARGET_PLATFORM_DIR) \ $(TARGET_PLATFORM_DIR)/startup \ $(STDPERIPH_DIR)/Inc \ - $(USBCORE_DIR)/Inc \ - $(USBCDC_DIR)/Inc \ - $(USBHID_DIR)/Inc \ - $(USBMSC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCORE_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBCDC_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBHID_DIR)/Inc \ + $(LIB_MAIN_DIR)/$(USBMSC_DIR)/Inc \ $(CMSIS_DIR)/Core/Include \ - $(ROOT)/lib/main/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \ + $(LIB_MAIN_DIR)/STM32H7/Drivers/CMSIS/Device/ST/STM32H7xx/Include \ $(TARGET_PLATFORM_DIR)/vcp_hal #Flags @@ -117,7 +116,7 @@ DEVICE_FLAGS = -DUSE_HAL_DRIVER -DUSE_FULL_LL_DRIVER ifeq ($(TARGET_MCU),STM32H743xx) DEVICE_FLAGS += -DSTM32H743xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h743_2m.ld -STARTUP_SRC = startup/startup_stm32h743xx.s +STARTUP_SRC = STM32/startup/startup_stm32h743xx.s MCU_FLASH_SIZE := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -132,7 +131,7 @@ endif else ifeq ($(TARGET_MCU),STM32H7A3xxQ) DEVICE_FLAGS += -DSTM32H7A3xxQ DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld -STARTUP_SRC = startup/startup_stm32h7a3xx.s +STARTUP_SRC = STM32/startup/startup_stm32h7a3xx.s MCU_FLASH_SIZE := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -147,7 +146,7 @@ endif else ifeq ($(TARGET_MCU),STM32H7A3xx) DEVICE_FLAGS += -DSTM32H7A3xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h7a3_2m.ld -STARTUP_SRC = startup/startup_stm32h7a3xx.s +STARTUP_SRC = STM32/startup/startup_stm32h7a3xx.s MCU_FLASH_SIZE := 2048 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -162,7 +161,7 @@ endif else ifeq ($(TARGET_MCU),STM32H723xx) DEVICE_FLAGS += -DSTM32H723xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld -STARTUP_SRC = startup/startup_stm32h723xx.s +STARTUP_SRC = STM32/startup/startup_stm32h723xx.s DEFAULT_TARGET_FLASH := 1024 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -182,14 +181,14 @@ endif else ifeq ($(TARGET_MCU),STM32H725xx) DEVICE_FLAGS += -DSTM32H725xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld -STARTUP_SRC = startup/startup_stm32h723xx.s +STARTUP_SRC = STM32/startup/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 = startup/startup_stm32h730xx.s +STARTUP_SRC = STM32/startup/startup_stm32h730xx.s DEFAULT_TARGET_FLASH := 128 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 @@ -211,7 +210,7 @@ endif else ifeq ($(TARGET_MCU),STM32H750xx) DEVICE_FLAGS += -DSTM32H750xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_128k.ld -STARTUP_SRC = startup/startup_stm32h743xx.s +STARTUP_SRC = STM32/startup/startup_stm32h743xx.s DEFAULT_TARGET_FLASH := 128 ifeq ($(TARGET_FLASH),) @@ -256,61 +255,59 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 -DSTM32 VCP_SRC = \ - vcp_hal/usbd_desc.c \ - vcp_hal/usbd_conf_stm32h7xx.c \ - vcp_hal/usbd_cdc_hid.c \ - vcp_hal/usbd_cdc_interface.c \ - serial_usb_vcp.c \ + STM32/vcp_hal/usbd_desc.c \ + STM32/vcp_hal/usbd_conf_stm32h7xx.c \ + STM32/vcp_hal/usbd_cdc_hid.c \ + STM32/vcp_hal/usbd_cdc_interface.c \ + STM32/serial_usb_vcp.c \ drivers/usb_io.c MCU_COMMON_SRC = \ - stm32/system.c \ + common/stm32/system.c \ drivers/bus_i2c_timing.c \ drivers/bus_quadspi.c \ drivers/dshot_bitbang_decode.c \ drivers/pwm_output_dshot_shared.c \ - adc_stm32h7xx.c \ - audio_stm32h7xx.c \ - bus_i2c_hal_init.c \ - bus_i2c_hal.c \ - bus_spi_ll.c \ - bus_quadspi_hal.c \ - bus_octospi_stm32h7xx.c \ - debug.c \ - dma_reqmap_mcu.c \ - dma_stm32h7xx.c \ - dshot_bitbang_ll.c \ - dshot_bitbang.c \ - exti.c \ - io_stm32.c \ - light_ws2811strip_hal.c \ - memprot_hal.c \ - memprot_stm32h7xx.c \ - persistent.c \ - pwm_output.c \ - pwm_output_dshot_hal.c \ - rcc_stm32.c \ - sdio_h7xx.c \ - serial_uart_hal.c \ - serial_uart_stm32h7xx.c \ - system_stm32h7xx.c \ - timer_hal.c \ - timer_stm32h7xx.c \ - transponder_ir_io_hal.c \ - camera_control_stm32.c \ + STM32/adc_stm32h7xx.c \ + STM32/audio_stm32h7xx.c \ + STM32/bus_i2c_hal_init.c \ + STM32/bus_i2c_hal.c \ + STM32/bus_spi_ll.c \ + STM32/bus_quadspi_hal.c \ + STM32/bus_octospi_stm32h7xx.c \ + STM32/debug.c \ + STM32/dma_reqmap_mcu.c \ + STM32/dma_stm32h7xx.c \ + STM32/dshot_bitbang_ll.c \ + STM32/dshot_bitbang.c \ + STM32/exti.c \ + STM32/io_stm32.c \ + STM32/light_ws2811strip_hal.c \ + STM32/memprot_hal.c \ + STM32/memprot_stm32h7xx.c \ + STM32/persistent.c \ + STM32/pwm_output.c \ + STM32/pwm_output_dshot_hal.c \ + STM32/rcc_stm32.c \ + STM32/sdio_h7xx.c \ + STM32/serial_uart_hal.c \ + STM32/serial_uart_stm32h7xx.c \ + STM32/system_stm32h7xx.c \ + STM32/timer_hal.c \ + STM32/timer_stm32h7xx.c \ + STM32/transponder_ir_io_hal.c \ + STM32/camera_control_stm32.c \ drivers/adc.c \ drivers/bus_i2c_config.c \ - drivers/bus_spi.c \ drivers/bus_spi_config.c \ drivers/bus_spi_pinconfig.c \ drivers/serial_escserial.c \ drivers/serial_pinconfig.c \ - drivers/serial_uart.c \ drivers/serial_uart_pinconfig.c \ - startup/system_stm32h7xx.c + STM32/startup/system_stm32h7xx.c MSC_SRC = \ - usb_msc_hal.c \ + STM32/usb_msc_hal.c \ drivers/usb_msc_common.c \ msc/usbd_storage.c \ msc/usbd_storage_emfat.c \ @@ -320,7 +317,8 @@ MSC_SRC = \ msc/usbd_storage_sdio.c SPEED_OPTIMISED_SRC += \ - common/stm32/system.c + common/stm32/system.c \ + STM32/exti.c -DSP_LIB := $(ROOT)/lib/main/CMSIS/DSP +DSP_LIB := $(LIB_MAIN_DIR)/CMSIS/DSP DEVICE_FLAGS += -DARM_MATH_MATRIX_CHECK -DARM_MATH_ROUNDING -D__FPU_PRESENT=1 -DUNALIGNED_SUPPORT_DISABLE -DARM_MATH_CM7