diff --git a/Makefile b/Makefile index ac486e56e..eef3668e3 100644 --- a/Makefile +++ b/Makefile @@ -44,25 +44,36 @@ FLASH_SIZE ?= FORKNAME = betaflight -CC3D_TARGETS = CC3D CC3D_OPBL - -VALID_TARGETS = NAZE NAZE32PRO OLIMEXINO STM32F3DISCOVERY CHEBUZZF3 $(CC3D_TARGETS) CJMCU EUSTM32F103RC SPRACINGF3 PORT103R SPARKY ALIENFLIGHTF1 ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO IRCFUSIONF3 AFROMINI SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +CC3D_TARGETS = CC3D CC3D_OPBL +NAZE_TARGETS = ALIENFLIGHTF1 AFROMMINI +SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2 +SPRACINGF3_TARGETS = RMDO IRCFUSIONF3 +SERIAL_USB_TARGETS = SPRACINGF3 IRCFUSIONF3 # Valid targets for OP VCP support -VCP_VALID_TARGETS = $(CC3D_TARGETS) +VCP_VALID_TARGETS = BLUEJAYF4 $(CC3D_TARGETS) + +F405_TARGETS = REVO REVO_OPBL SPARKY2 ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON AQ32_V2 KKNGF4 +F405_TARGETS_16 = QUANTON +F411_TARGETS = REVONANO + +F1_TARGETS = NAZE OLIMEXINO $(CC3D_TARGETS) PORT103R ALIENFLIGHTF1 AFROMINI +F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +F4_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16) $(F411_TARGETS) +VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) # Valid targets for OP BootLoader support OPBL_VALID_TARGETS = CC3D_OPBL -64K_TARGETS = CJMCU -128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI -256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY - -F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +64K_TARGETS = CJMCU +128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI +256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY +512K_TARGETS = $(F411_TARGETS) +1024K_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16) # note that there is no hardfault debugging startup file assembly handler for other platforms ifeq ($(DEBUG_HARDFAULTS),F3) -CFLAGS += -DDEBUG_HARDFAULTS +CFLAGS += -DDEBUG_HARDFAULTS STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S else STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S @@ -76,6 +87,10 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS))) FLASH_SIZE = 128 else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS))) FLASH_SIZE = 256 +else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS))) +FLASH_SIZE = 512 +else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS))) +FLASH_SIZE = 1024 else $(error FLASH_SIZE not configured for target $(TARGET)) endif @@ -91,63 +106,58 @@ FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) # Working directories ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) -SRC_DIR = $(ROOT)/src/main -OBJECT_DIR = $(ROOT)/obj/main -BIN_DIR = $(ROOT)/obj -CMSIS_DIR = $(ROOT)/lib/main/CMSIS -INCLUDE_DIRS = $(SRC_DIR) -LINKER_DIR = $(ROOT)/src/main/target +SRC_DIR = $(ROOT)/src/main +OBJECT_DIR = $(ROOT)/obj/main +BIN_DIR = $(ROOT)/obj +CMSIS_DIR = $(ROOT)/lib/main/CMSIS +INCLUDE_DIRS = $(SRC_DIR) +LINKER_DIR = $(ROOT)/src/main/target # Search path for sources -VPATH := $(SRC_DIR):$(SRC_DIR)/startup -USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver +VPATH := $(SRC_DIR):$(SRC_DIR)/startup +USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) -FATFS_DIR = $(ROOT)/lib/main/FatFS -FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) +FATFS_DIR = $(ROOT)/lib/main/FatFS +FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) + +CSOURCES := $(shell find $(SRC_DIR) -name '*.c') ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -CSOURCES := $(shell find $(SRC_DIR) -name '*.c') - -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver - -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) - -EXCLUDES = stm32f30x_crc.c \ - stm32f30x_can.c - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) - -DEVICE_STDPERIPH_SRC = \ - $(STDPERIPH_SRC) +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f30x_crc.c \ + stm32f30x_can.c +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) +DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \ $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM1/CoreSupport \ - $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM1/CoreSupport \ + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x -ifneq ($(TARGET),$(filter $(TARGET),SPRACINGF3 IRCFUSIONF3)) +ifneq ($(TARGET),$(filter $(TARGET), $(SERIAL_USB_TARGETS))) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp -VPATH := $(VPATH):$(USBFS_DIR)/src +VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ - $(USBPERIPH_SRC) + $(USBPERIPH_SRC) endif -ifeq ($(TARGET),SPRACINGF3MINI) +ifeq ($(TARGET),$(filter $(TARGET), $(SDCARD_TARGETS))) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) \ + $(FATFS_DIR) \ -VPATH := $(VPATH):$(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) endif LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld @@ -160,33 +170,133 @@ ifeq ($(TARGET),CHEBUZZF3) TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY endif -ifeq ($(TARGET),$(filter $(TARGET),RMDO IRCFUSIONF3)) +ifeq ($(TARGET),$(filter $(TARGET),$(SPRACINGF3_TARGETS))) # RMDO and IRCFUSIONF3 are a VARIANT of SPRACINGF3 TARGET_FLAGS := $(TARGET_FLAGS) -DSPRACINGF3 endif -else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) +## End F3 targets +## +## Start F4 targets +else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) + +#STDPERIPH +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f4xx_crc.c \ + stm32f4xx_can.c \ + stm32f4xx_fmc.c \ + stm32f4xx_sai.c \ + stm32f4xx_cec.c \ + stm32f4xx_dsi.c \ + stm32f4xx_flash_ramfunc.c \ + stm32f4xx_fmpi2c.c \ + stm32f4xx_lptim.c \ + stm32f4xx_qspi.c \ + stm32f4xx_spdifrx.c \ + stm32f4xx_cryp.c \ + stm32f4xx_cryp_aes.c \ + stm32f4xx_hash_md5.c \ + stm32f4xx_cryp_des.c \ + stm32f4xx_rtc.c \ + stm32f4xx_hash.c \ + stm32f4xx_dbgmcu.c \ + stm32f4xx_cryp_tdes.c \ + stm32f4xx_hash_sha1.c -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver - -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) - -EXCLUDES = stm32f10x_crc.c \ - stm32f10x_cec.c \ - stm32f10x_can.c +ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) +EXCLUDES += stm32f4xx_fsmc.c +endif STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) +#USB +USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core +USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c)) +USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver +USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c)) +EXCLUDES = usb_bsp_template.c \ + usb_conf_template.c \ + usb_hcd_int.c \ + usb_hcd.c \ + usb_otg.c + +USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC)) +USBCDC_DIR = $(ROOT)/lib/main/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):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src + +DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ + $(USBOTG_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) + +#CMSIS +VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/inc \ + $(USBOTG_DIR)/inc \ + $(USBCORE_DIR)/inc \ + $(USBCDC_DIR)/inc \ + $(USBFS_DIR)/inc \ + $(CMSIS_DIR)/CM4/CoreSupport \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ + $(ROOT)/src/main/vcpf4 + +ifeq ($(TARGET),$(filter $(TARGET),$(SDCARD_TARGETS))) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) +endif + +#Flags +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion + +ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS))) +DEVICE_FLAGS = -DSTM32F411xE +DEVICE_FLAGS += -DHSE_VALUE=8000000 +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld +else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS_16))) +DEVICE_FLAGS = -DSTM32F40_41xxx +DEVICE_FLAGS += -DHSE_VALUE=16000000 +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld +else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS))) +DEVICE_FLAGS = -DSTM32F40_41xxx +DEVICE_FLAGS += -DHSE_VALUE=8000000 +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld +else +$(error Unknown MCU for F4 target) +endif + +TARGET_FLAGS = -D$(TARGET) + +## end F4 targets +## +## Start F1 targets +else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) + +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f10x_crc.c \ + stm32f10x_cec.c \ + stm32f10x_can.c + +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) + # Search path and source files for the CMSIS sources -VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x -CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) +VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM3/CoreSupport \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld @@ -199,14 +309,12 @@ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) else STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f10x_crc.c \ + stm32f10x_cec.c \ + stm32f10x_can.c -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) - -EXCLUDES = stm32f10x_crc.c \ - stm32f10x_cec.c \ - stm32f10x_can.c - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) # Search path and source files for the CMSIS sources VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x @@ -214,31 +322,33 @@ CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM3/CoreSupport \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) ifeq ($(TARGET),$(filter $(TARGET), $(VCP_VALID_TARGETS))) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \ - $(USBPERIPH_SRC) + $(USBPERIPH_SRC) endif LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld - ARCH_FLAGS = -mthumb -mcpu=cortex-m3 TARGET_FLAGS = -D$(TARGET) -pedantic DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X endif +## +## end F1/F3 target +## ifneq ($(FLASH_SIZE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) @@ -247,9 +357,9 @@ endif TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) -ifeq ($(TARGET),ALIENFLIGHTF1) -# ALIENFLIGHTF1 is a VARIANT of NAZE -TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENFLIGHT +ifeq ($(TARGET),$(filter $(TARGET), $(NAZE_TARGETS))) +# VARIANTS of NAZE +TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -D$(TARGET) TARGET_DIR = $(ROOT)/src/main/target/NAZE endif @@ -267,26 +377,21 @@ endif ifeq ($(OPBL),yes) ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),) -TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld +TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld .DEFAULT_GOAL := binary else $(error OPBL specified with a unsupported target) endif endif -ifeq ($(TARGET),AFROMINI) -# AFROMINI is a VARIANT of NAZE being recognized as rev4, but needs to use rev5 config -TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DAFROMINI -TARGET_DIR = $(ROOT)/src/main/target/NAZE -endif - INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_DIR) + $(TARGET_DIR) -VPATH := $(VPATH):$(TARGET_DIR) +VPATH := $(VPATH):$(TARGET_DIR) -COMMON_SRC = build_config.c \ +COMMON_SRC = \ + build_config.c \ debug.c \ version.c \ $(TARGET_SRC) \ @@ -311,7 +416,6 @@ COMMON_SRC = build_config.c \ drivers/sound_beeper.c \ drivers/system.c \ drivers/gyro_sync.c \ - drivers/dma.c \ drivers/buf_writer.c \ drivers/exti.c \ drivers/io.c \ @@ -374,180 +478,36 @@ VCP_SRC = \ drivers/serial_usb_vcp.c \ drivers/usb_io.c -NAZE_SRC = startup_stm32f10x_md_gcc.S \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/adc.c \ - drivers/adc_stm32f10x.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/barometer_bmp280.c \ - drivers/bus_spi.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.h \ - drivers/flash_m25p16.c \ - drivers/gpio_stm32f10x.c \ - drivers/inverter.c \ - drivers/light_led.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pwm_rx.c \ - drivers/serial_softserial.c \ - drivers/serial_uart.c \ - drivers/serial_uart_stm32f10x.c \ - drivers/system_stm32f10x.c \ - drivers/timer.c \ - drivers/timer_stm32f10x.c \ - io/flashfs.c \ - hardware_revision.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) +VCPF4_SRC = \ + vcpf4/stm32f4xx_it.c \ + vcpf4/usb_bsp.c \ + vcpf4/usbd_desc.c \ + vcpf4/usbd_usr.c \ + vcpf4/usbd_cdc_vcp.c \ + drivers/serial_usb_vcp.c -ALIENFLIGHTF1_SRC = $(NAZE_SRC) - -AFROMINI_SRC = $(NAZE_SRC) - -EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/adc.c \ - drivers/adc_stm32f10x.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/bus_spi.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.c \ - drivers/flash_m25p16.c \ - drivers/gpio_stm32f10x.c \ - drivers/inverter.c \ - drivers/light_led.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pwm_rx.c \ - drivers/serial_softserial.c \ - drivers/serial_uart.c \ - drivers/serial_uart_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - drivers/system_stm32f10x.c \ - drivers/timer.c \ - drivers/timer_stm32f10x.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -PORT103R_SRC = $(EUSTM32F103RC_SRC) - -OLIMEXINO_SRC = startup_stm32f10x_md_gcc.S \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/adc.c \ - drivers/adc_stm32f10x.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/bus_spi.c \ - drivers/compass_hmc5883l.c \ - drivers/gpio_stm32f10x.c \ - drivers/light_led.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pwm_rx.c \ - drivers/serial_softserial.c \ - drivers/serial_uart.c \ - drivers/serial_uart_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - drivers/system_stm32f10x.c \ - drivers/timer.c \ - drivers/timer_stm32f10x.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -CJMCU_SRC = \ +STM32F10x_COMMON_SRC = \ startup_stm32f10x_md_gcc.S \ - drivers/adc.c \ - drivers/adc_stm32f10x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/compass_hmc5883l.c \ - drivers/gpio_stm32f10x.c \ - drivers/light_led.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pwm_rx.c \ - drivers/serial_uart.c \ - drivers/serial_uart_stm32f10x.c \ - drivers/system_stm32f10x.c \ - drivers/timer.c \ - drivers/timer_stm32f10x.c \ - hardware_revision.c \ - flight/gtune.c \ - blackbox/blackbox.c \ - blackbox/blackbox_io.c \ - $(COMMON_SRC) - -CC3D_SRC = \ - startup_stm32f10x_md_gcc.S \ - drivers/accgyro_mpu.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/adc.c \ - drivers/adc_stm32f10x.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/bus_spi.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/compass_hmc5883l.c \ - drivers/display_ug2864hsweg01.c \ - drivers/flash_m25p16.c \ - drivers/gpio_stm32f10x.c \ - drivers/inverter.c \ - drivers/light_led.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/pwm_mapping.c \ - drivers/pwm_output.c \ - drivers/pwm_rx.c \ drivers/serial_softserial.c \ drivers/serial_uart.c \ drivers/serial_uart_stm32f10x.c \ - drivers/sonar_hcsr04.c \ drivers/system_stm32f10x.c \ + drivers/pwm_mapping.c \ + drivers/pwm_output.c \ + drivers/pwm_rx.c \ drivers/timer.c \ + drivers/dma.c \ drivers/timer_stm32f10x.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) + drivers/gpio_stm32f10x.c \ + drivers/adc.c \ + drivers/adc_stm32f10x.c \ + drivers/bus_spi.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/light_led.c \ + drivers/inverter.c - -STM32F30x_COMMON_SRC += \ +STM32F30x_COMMON_SRC = \ + startup_stm32f30x_md_gcc.S \ drivers/adc.c \ drivers/adc_stm32f30x.c \ drivers/bus_i2c_stm32f30x.c \ @@ -562,7 +522,133 @@ STM32F30x_COMMON_SRC += \ drivers/serial_uart_stm32f30x.c \ drivers/system_stm32f30x.c \ drivers/timer.c \ - drivers/timer_stm32f30x.c + drivers/timer_stm32f30x.c \ + drivers/dma.c + +STM32F4xx_COMMON_SRC = \ + startup_stm32f40xx.s \ + drivers/accgyro_mpu.c \ + drivers/adc.c \ + drivers/adc_stm32f4xx.c \ + drivers/adc.c \ + drivers/adc_stm32f4xx.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/bus_spi.c \ + drivers/gpio_stm32f4xx.c \ + drivers/inverter.c \ + drivers/light_led.c \ + drivers/pwm_mapping.c \ + drivers/pwm_output.c \ + drivers/pwm_rx.c \ + drivers/serial_softserial.c \ + drivers/serial_uart.c \ + drivers/serial_uart_stm32f4xx.c \ + drivers/sound_beeper.c \ + drivers/system_stm32f4xx.c \ + drivers/timer.c \ + drivers/timer_stm32f4xx.c \ + drivers/dma_stm32f4xx.c \ + drivers/flash_m25p16.c \ + io/flashfs.c + +NAZE_SRC = \ + $(STM32F10x_COMMON_SRC) \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.h \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + io/flashfs.c \ + hardware_revision.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) + +ALIENFLIGHTF1_SRC = $(NAZE_SRC) + +AFROMINI_SRC = $(NAZE_SRC) + +EUSTM32F103RC_SRC = \ + $(STM32F10x_COMMON_SRC) \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) + +PORT103R_SRC = $(EUSTM32F103RC_SRC) + +OLIMEXINO_SRC = \ + $(STM32F10x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) + +CJMCU_SRC = \ + $(STM32F10x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/compass_hmc5883l.c \ + hardware_revision.c \ + flight/gtune.c \ + blackbox/blackbox.c \ + blackbox/blackbox_io.c \ + $(COMMON_SRC) + +CC3D_SRC = \ + $(STM32F10x_COMMON_SRC) \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/display_ug2864hsweg01.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + io/flashfs.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCP_SRC) NAZE32PRO_SRC = \ $(STM32F30x_COMMON_SRC) \ @@ -807,6 +893,38 @@ SINGULARITY_SRC = \ $(COMMON_SRC) \ $(VCP_SRC) +ALIENFLIGHTF4_SRC = \ + $(STM32F4xx_COMMON_SRC) \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_spi_mpu9250.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8963.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f4xx.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCPF4_SRC) + +BLUEJAYF4_SRC = \ + $(STM32F4xx_COMMON_SRC) \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_ms5611.c \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c \ + $(HIGHEND_SRC) \ + $(COMMON_SRC) \ + $(VCPF4_SRC) + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src @@ -815,7 +933,7 @@ VPATH := $(VPATH):$(STDPERIPH_DIR)/src # # Tool names -CC = arm-none-eabi-gcc +CC = arm-none-eabi-gcc OBJCOPY = arm-none-eabi-objcopy SIZE = arm-none-eabi-size diff --git a/src/main/config/config.c b/src/main/config/config.c index 46fcd292a..b5025cd6f 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -74,7 +74,11 @@ #include "config/config_master.h" #define BRUSHED_MOTORS_PWM_RATE 16000 +#ifdef STM32F4 +#define BRUSHLESS_MOTORS_PWM_RATE 2000 +#else #define BRUSHLESS_MOTORS_PWM_RATE 400 +#endif void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, escAndServoConfig_t *escAndServoConfigToUse, pidProfile_t *pidProfileToUse); @@ -95,6 +99,15 @@ void useRcControlsConfig(modeActivationCondition_t *modeActivationConditions, es #ifdef STM32F10X_HD #define FLASH_PAGE_SIZE ((uint16_t)0x800) #endif + + #if defined(STM32F40_41xxx) + #define FLASH_PAGE_SIZE ((uint32_t)0x20000) + #endif + + #if defined (STM32F411xE) + #define FLASH_PAGE_SIZE ((uint32_t)0x20000) + #endif + #endif #if !defined(FLASH_SIZE) && !defined(FLASH_PAGE_COUNT) @@ -131,9 +144,10 @@ size_t custom_flash_memory_address = 0; #define CONFIG_START_FLASH_ADDRESS (custom_flash_memory_address) #else // use the last flash pages for storage +#ifndef CONFIG_START_FLASH_ADDRESS #define CONFIG_START_FLASH_ADDRESS (0x08000000 + (uint32_t)((FLASH_PAGE_SIZE * FLASH_PAGE_COUNT) - FLASH_TO_RESERVE_FOR_CONFIG)) #endif - +#endif master_t masterConfig; // master config struct with data independent from profiles profile_t *currentProfile; static uint32_t activeFeaturesLatch = 0; @@ -994,7 +1008,13 @@ void writeEEPROM(void) #endif for (wordOffset = 0; wordOffset < sizeof(master_t); wordOffset += 4) { if (wordOffset % FLASH_PAGE_SIZE == 0) { - status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset); +#if defined(STM32F40_41xxx) + status = FLASH_EraseSector(FLASH_Sector_8, VoltageRange_3); //0x08080000 to 0x080A0000 +#elif defined (STM32F411xE) + status = FLASH_EraseSector(FLASH_Sector_7, VoltageRange_3); //0x08060000 to 0x08080000 +#else + status = FLASH_ErasePage(CONFIG_START_FLASH_ADDRESS + wordOffset); +#endif if (status != FLASH_COMPLETE) { break; } diff --git a/src/main/startup/startup_stm32f40xx.s b/src/main/startup/startup_stm32f40xx.s new file mode 100644 index 000000000..fa98fff96 --- /dev/null +++ b/src/main/startup/startup_stm32f40xx.s @@ -0,0 +1,546 @@ +/** + ****************************************************************************** + * @file startup_stm32f40_41xxx.s + * @author MCD Application Team + * @version V1.6.1 + * @date 21-October-2015 + * @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO toolchain. + * Same as startup_stm32f40_41xxx.s and maintained for legacy purpose + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM324xG-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global irq_stack + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =0x2001FFFC // mj666 + ldr r1, =0xDEADBEEF // mj666 + ldr r2, [r0, #0] // mj666 + str r0, [r0, #0] // mj666 + cmp r2, r1 // mj666 + beq Reboot_Loader // mj666 + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/*FPU settings*/ + ldr r0, =0xE000ED88 /* Enable CP10,CP11 */ + ldr r1,[r0] + orr r1,r1,#(0xF << 20) + str r1,[r0] + +/* Call the clock system intitialization function.*/ + bl SystemInit + +/* Call the application's entry point.*/ + bl main + bx lr + +LoopForever: + b LoopForever + +Reboot_Loader: // mj666 + + // Reboot to ROM // mj666 + ldr r0, =0x1FFF0000 // mj666 + ldr sp,[r0, #0] // mj666 + ldr r0,[r0, #4] // mj666 + bx r0 // mj666 + +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .irqstack,"aw",%progbits + irq_stack: + .space 1024 + + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word irq_stack+1024 + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word CAN1_TX_IRQHandler /* CAN1 TX */ + .word CAN1_RX0_IRQHandler /* CAN1 RX0 */ + .word CAN1_RX1_IRQHandler /* CAN1 RX1 */ + .word CAN1_SCE_IRQHandler /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word USART3_IRQHandler /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word TIM8_BRK_TIM12_IRQHandler /* TIM8 Break and TIM12 */ + .word TIM8_UP_TIM13_IRQHandler /* TIM8 Update and TIM13 */ + .word TIM8_TRG_COM_TIM14_IRQHandler /* TIM8 Trigger and Commutation and TIM14 */ + .word TIM8_CC_IRQHandler /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word FSMC_IRQHandler /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word UART4_IRQHandler /* UART4 */ + .word UART5_IRQHandler /* UART5 */ + .word TIM6_DAC_IRQHandler /* TIM6 and DAC1&2 underrun errors */ + .word TIM7_IRQHandler /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word ETH_IRQHandler /* Ethernet */ + .word ETH_WKUP_IRQHandler /* Ethernet Wakeup through EXTI line */ + .word CAN2_TX_IRQHandler /* CAN2 TX */ + .word CAN2_RX0_IRQHandler /* CAN2 RX0 */ + .word CAN2_RX1_IRQHandler /* CAN2 RX1 */ + .word CAN2_SCE_IRQHandler /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word OTG_HS_EP1_OUT_IRQHandler /* USB OTG HS End Point 1 Out */ + .word OTG_HS_EP1_IN_IRQHandler /* USB OTG HS End Point 1 In */ + .word OTG_HS_WKUP_IRQHandler /* USB OTG HS Wakeup through EXTI */ + .word OTG_HS_IRQHandler /* USB OTG HS */ + .word DCMI_IRQHandler /* DCMI */ + .word CRYP_IRQHandler /* CRYP crypto */ + .word HASH_RNG_IRQHandler /* Hash and Rng */ + .word FPU_IRQHandler /* FPU */ + +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak CAN1_TX_IRQHandler + .thumb_set CAN1_TX_IRQHandler,Default_Handler + + .weak CAN1_RX0_IRQHandler + .thumb_set CAN1_RX0_IRQHandler,Default_Handler + + .weak CAN1_RX1_IRQHandler + .thumb_set CAN1_RX1_IRQHandler,Default_Handler + + .weak CAN1_SCE_IRQHandler + .thumb_set CAN1_SCE_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak USART3_IRQHandler + .thumb_set USART3_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak TIM8_BRK_TIM12_IRQHandler + .thumb_set TIM8_BRK_TIM12_IRQHandler,Default_Handler + + .weak TIM8_UP_TIM13_IRQHandler + .thumb_set TIM8_UP_TIM13_IRQHandler,Default_Handler + + .weak TIM8_TRG_COM_TIM14_IRQHandler + .thumb_set TIM8_TRG_COM_TIM14_IRQHandler,Default_Handler + + .weak TIM8_CC_IRQHandler + .thumb_set TIM8_CC_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak FSMC_IRQHandler + .thumb_set FSMC_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak UART4_IRQHandler + .thumb_set UART4_IRQHandler,Default_Handler + + .weak UART5_IRQHandler + .thumb_set UART5_IRQHandler,Default_Handler + + .weak TIM6_DAC_IRQHandler + .thumb_set TIM6_DAC_IRQHandler,Default_Handler + + .weak TIM7_IRQHandler + .thumb_set TIM7_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak ETH_IRQHandler + .thumb_set ETH_IRQHandler,Default_Handler + + .weak ETH_WKUP_IRQHandler + .thumb_set ETH_WKUP_IRQHandler,Default_Handler + + .weak CAN2_TX_IRQHandler + .thumb_set CAN2_TX_IRQHandler,Default_Handler + + .weak CAN2_RX0_IRQHandler + .thumb_set CAN2_RX0_IRQHandler,Default_Handler + + .weak CAN2_RX1_IRQHandler + .thumb_set CAN2_RX1_IRQHandler,Default_Handler + + .weak CAN2_SCE_IRQHandler + .thumb_set CAN2_SCE_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_OUT_IRQHandler + .thumb_set OTG_HS_EP1_OUT_IRQHandler,Default_Handler + + .weak OTG_HS_EP1_IN_IRQHandler + .thumb_set OTG_HS_EP1_IN_IRQHandler,Default_Handler + + .weak OTG_HS_WKUP_IRQHandler + .thumb_set OTG_HS_WKUP_IRQHandler,Default_Handler + + .weak OTG_HS_IRQHandler + .thumb_set OTG_HS_IRQHandler,Default_Handler + + .weak DCMI_IRQHandler + .thumb_set DCMI_IRQHandler,Default_Handler + + .weak CRYP_IRQHandler + .thumb_set CRYP_IRQHandler,Default_Handler + + .weak HASH_RNG_IRQHandler + .thumb_set HASH_RNG_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/ diff --git a/src/main/startup/startup_stm32f411xe.s b/src/main/startup/startup_stm32f411xe.s new file mode 100644 index 000000000..f8c460a54 --- /dev/null +++ b/src/main/startup/startup_stm32f411xe.s @@ -0,0 +1,473 @@ +/** + ****************************************************************************** + * @file startup_stm32f40_41xxx.s + * @author MCD Application Team + * @version V1.6.1 + * @date 21-October-2015 + * @brief STM32F40xxx/41xxx Devices vector table for Atollic TrueSTUDIO toolchain. + * Same as startup_stm32f40_41xxx.s and maintained for legacy purpose + * This module performs: + * - Set the initial SP + * - Set the initial PC == Reset_Handler, + * - Set the vector table entries with the exceptions ISR address + * - Configure the clock system and the external SRAM mounted on + * STM324xG-EVAL board to be used as data memory (optional, + * to be enabled by user) + * - Branches to main in the C library (which eventually + * calls main()). + * After Reset the Cortex-M4 processor is in Thread mode, + * priority is Privileged, and the Stack is set to Main. + ****************************************************************************** + * @attention + * + *

© COPYRIGHT 2015 STMicroelectronics

+ * + * Licensed under MCD-ST Liberty SW License Agreement V2, (the "License"); + * You may not use this file except in compliance with the License. + * You may obtain a copy of the License at: + * + * http://www.st.com/software_license_agreement_liberty_v2 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + * + ****************************************************************************** + */ + + .syntax unified + .cpu cortex-m4 + .fpu softvfp + .thumb + +.global g_pfnVectors +.global Default_Handler +.global irq_stack + +/* start address for the initialization values of the .data section. +defined in linker script */ +.word _sidata +/* start address for the .data section. defined in linker script */ +.word _sdata +/* end address for the .data section. defined in linker script */ +.word _edata +/* start address for the .bss section. defined in linker script */ +.word _sbss +/* end address for the .bss section. defined in linker script */ +.word _ebss +/* stack used for SystemInit_ExtMemCtl; always internal RAM used */ + +/** + * @brief This is the code that gets called when the processor first + * starts execution following a reset event. Only the absolutely + * necessary set is performed, after which the application + * supplied main() routine is called. + * @param None + * @retval : None +*/ + + .section .text.Reset_Handler + .weak Reset_Handler + .type Reset_Handler, %function +Reset_Handler: + ldr r0, =0x2001FFFC // mj666 + ldr r1, =0xDEADBEEF // mj666 + ldr r2, [r0, #0] // mj666 + str r0, [r0, #0] // mj666 + cmp r2, r1 // mj666 + beq Reboot_Loader // mj666 + +/* Copy the data segment initializers from flash to SRAM */ + movs r1, #0 + b LoopCopyDataInit + +CopyDataInit: + ldr r3, =_sidata + ldr r3, [r3, r1] + str r3, [r0, r1] + adds r1, r1, #4 + +LoopCopyDataInit: + ldr r0, =_sdata + ldr r3, =_edata + adds r2, r0, r1 + cmp r2, r3 + bcc CopyDataInit + ldr r2, =_sbss + b LoopFillZerobss +/* Zero fill the bss segment. */ +FillZerobss: + movs r3, #0 + str r3, [r2], #4 + +LoopFillZerobss: + ldr r3, = _ebss + cmp r2, r3 + bcc FillZerobss + +/*FPU settings*/ + ldr r0, =0xE000ED88 /* Enable CP10,CP11 */ + ldr r1,[r0] + orr r1,r1,#(0xF << 20) + str r1,[r0] + +/* Call the clock system intitialization function.*/ + bl SystemInit + +/* Call the application's entry point.*/ + bl main + bx lr + +LoopForever: + b LoopForever + +Reboot_Loader: // mj666 + + // Reboot to ROM // mj666 + ldr r0, =0x1FFF0000 // mj666 + ldr sp,[r0, #0] // mj666 + ldr r0,[r0, #4] // mj666 + bx r0 // mj666 +.size Reset_Handler, .-Reset_Handler + +/** + * @brief This is the code that gets called when the processor receives an + * unexpected interrupt. This simply enters an infinite loop, preserving + * the system state for examination by a debugger. + * @param None + * @retval None +*/ + .section .text.Default_Handler,"ax",%progbits +Default_Handler: +Infinite_Loop: + b Infinite_Loop + .size Default_Handler, .-Default_Handler +/****************************************************************************** +* +* The minimal vector table for a Cortex M3. Note that the proper constructs +* must be placed on this to ensure that it ends up at physical address +* 0x0000.0000. +* +*******************************************************************************/ + .section .irqstack,"aw",%progbits + irq_stack: + .space 1024 + + .section .isr_vector,"a",%progbits + .type g_pfnVectors, %object + .size g_pfnVectors, .-g_pfnVectors + + +g_pfnVectors: + .word irq_stack+1024 + .word Reset_Handler + .word NMI_Handler + .word HardFault_Handler + .word MemManage_Handler + .word BusFault_Handler + .word UsageFault_Handler + .word 0 + .word 0 + .word 0 + .word 0 + .word SVC_Handler + .word DebugMon_Handler + .word 0 + .word PendSV_Handler + .word SysTick_Handler + + /* External Interrupts */ + .word WWDG_IRQHandler /* Window WatchDog */ + .word PVD_IRQHandler /* PVD through EXTI Line detection */ + .word TAMP_STAMP_IRQHandler /* Tamper and TimeStamps through the EXTI line */ + .word RTC_WKUP_IRQHandler /* RTC Wakeup through the EXTI line */ + .word FLASH_IRQHandler /* FLASH */ + .word RCC_IRQHandler /* RCC */ + .word EXTI0_IRQHandler /* EXTI Line0 */ + .word EXTI1_IRQHandler /* EXTI Line1 */ + .word EXTI2_IRQHandler /* EXTI Line2 */ + .word EXTI3_IRQHandler /* EXTI Line3 */ + .word EXTI4_IRQHandler /* EXTI Line4 */ + .word DMA1_Stream0_IRQHandler /* DMA1 Stream 0 */ + .word DMA1_Stream1_IRQHandler /* DMA1 Stream 1 */ + .word DMA1_Stream2_IRQHandler /* DMA1 Stream 2 */ + .word DMA1_Stream3_IRQHandler /* DMA1 Stream 3 */ + .word DMA1_Stream4_IRQHandler /* DMA1 Stream 4 */ + .word DMA1_Stream5_IRQHandler /* DMA1 Stream 5 */ + .word DMA1_Stream6_IRQHandler /* DMA1 Stream 6 */ + .word ADC_IRQHandler /* ADC1, ADC2 and ADC3s */ + .word 0 /* CAN1 TX */ + .word 0 /* CAN1 RX0 */ + .word 0 /* CAN1 RX1 */ + .word 0 /* CAN1 SCE */ + .word EXTI9_5_IRQHandler /* External Line[9:5]s */ + .word TIM1_BRK_TIM9_IRQHandler /* TIM1 Break and TIM9 */ + .word TIM1_UP_TIM10_IRQHandler /* TIM1 Update and TIM10 */ + .word TIM1_TRG_COM_TIM11_IRQHandler /* TIM1 Trigger and Commutation and TIM11 */ + .word TIM1_CC_IRQHandler /* TIM1 Capture Compare */ + .word TIM2_IRQHandler /* TIM2 */ + .word TIM3_IRQHandler /* TIM3 */ + .word TIM4_IRQHandler /* TIM4 */ + .word I2C1_EV_IRQHandler /* I2C1 Event */ + .word I2C1_ER_IRQHandler /* I2C1 Error */ + .word I2C2_EV_IRQHandler /* I2C2 Event */ + .word I2C2_ER_IRQHandler /* I2C2 Error */ + .word SPI1_IRQHandler /* SPI1 */ + .word SPI2_IRQHandler /* SPI2 */ + .word USART1_IRQHandler /* USART1 */ + .word USART2_IRQHandler /* USART2 */ + .word 0 /* USART3 */ + .word EXTI15_10_IRQHandler /* External Line[15:10]s */ + .word RTC_Alarm_IRQHandler /* RTC Alarm (A and B) through EXTI Line */ + .word OTG_FS_WKUP_IRQHandler /* USB OTG FS Wakeup through EXTI line */ + .word 0 /* TIM8 Break and TIM12 */ + .word 0 /* TIM8 Update and TIM13 */ + .word 0 /* TIM8 Trigger and Commutation and TIM14 */ + .word 0 /* TIM8 Capture Compare */ + .word DMA1_Stream7_IRQHandler /* DMA1 Stream7 */ + .word 0 /* FSMC */ + .word SDIO_IRQHandler /* SDIO */ + .word TIM5_IRQHandler /* TIM5 */ + .word SPI3_IRQHandler /* SPI3 */ + .word 0 /* UART4 */ + .word 0 /* UART5 */ + .word 0 /* TIM6 and DAC1&2 underrun errors */ + .word 0 /* TIM7 */ + .word DMA2_Stream0_IRQHandler /* DMA2 Stream 0 */ + .word DMA2_Stream1_IRQHandler /* DMA2 Stream 1 */ + .word DMA2_Stream2_IRQHandler /* DMA2 Stream 2 */ + .word DMA2_Stream3_IRQHandler /* DMA2 Stream 3 */ + .word DMA2_Stream4_IRQHandler /* DMA2 Stream 4 */ + .word 0 /* Ethernet */ + .word 0 /* Ethernet Wakeup through EXTI line */ + .word 0 /* CAN2 TX */ + .word 0 /* CAN2 RX0 */ + .word 0 /* CAN2 RX1 */ + .word 0 /* CAN2 SCE */ + .word OTG_FS_IRQHandler /* USB OTG FS */ + .word DMA2_Stream5_IRQHandler /* DMA2 Stream 5 */ + .word DMA2_Stream6_IRQHandler /* DMA2 Stream 6 */ + .word DMA2_Stream7_IRQHandler /* DMA2 Stream 7 */ + .word USART6_IRQHandler /* USART6 */ + .word I2C3_EV_IRQHandler /* I2C3 event */ + .word I2C3_ER_IRQHandler /* I2C3 error */ + .word 0 /* USB OTG HS End Point 1 Out */ + .word 0 /* USB OTG HS End Point 1 In */ + .word 0 /* USB OTG HS Wakeup through EXTI */ + .word 0 /* USB OTG HS */ + .word 0 /* DCMI */ + .word 0 /* CRYP crypto */ + .word 0 /* Hash and Rng */ + .word FPU_IRQHandler /* FPU */ + .word 0 /* Reserved */ + .word 0 /* Reserved */ + .word SPI4_IRQHandler /* SPI4 */ + .word SPI5_IRQHandler /* SPI5 */ +/******************************************************************************* +* +* Provide weak aliases for each Exception handler to the Default_Handler. +* As they are weak aliases, any function with the same name will override +* this definition. +* +*******************************************************************************/ + .weak NMI_Handler + .thumb_set NMI_Handler,Default_Handler + + .weak HardFault_Handler + .thumb_set HardFault_Handler,Default_Handler + + .weak MemManage_Handler + .thumb_set MemManage_Handler,Default_Handler + + .weak BusFault_Handler + .thumb_set BusFault_Handler,Default_Handler + + .weak UsageFault_Handler + .thumb_set UsageFault_Handler,Default_Handler + + .weak SVC_Handler + .thumb_set SVC_Handler,Default_Handler + + .weak DebugMon_Handler + .thumb_set DebugMon_Handler,Default_Handler + + .weak PendSV_Handler + .thumb_set PendSV_Handler,Default_Handler + + .weak SysTick_Handler + .thumb_set SysTick_Handler,Default_Handler + + .weak WWDG_IRQHandler + .thumb_set WWDG_IRQHandler,Default_Handler + + .weak PVD_IRQHandler + .thumb_set PVD_IRQHandler,Default_Handler + + .weak TAMP_STAMP_IRQHandler + .thumb_set TAMP_STAMP_IRQHandler,Default_Handler + + .weak RTC_WKUP_IRQHandler + .thumb_set RTC_WKUP_IRQHandler,Default_Handler + + .weak FLASH_IRQHandler + .thumb_set FLASH_IRQHandler,Default_Handler + + .weak RCC_IRQHandler + .thumb_set RCC_IRQHandler,Default_Handler + + .weak EXTI0_IRQHandler + .thumb_set EXTI0_IRQHandler,Default_Handler + + .weak EXTI1_IRQHandler + .thumb_set EXTI1_IRQHandler,Default_Handler + + .weak EXTI2_IRQHandler + .thumb_set EXTI2_IRQHandler,Default_Handler + + .weak EXTI3_IRQHandler + .thumb_set EXTI3_IRQHandler,Default_Handler + + .weak EXTI4_IRQHandler + .thumb_set EXTI4_IRQHandler,Default_Handler + + .weak DMA1_Stream0_IRQHandler + .thumb_set DMA1_Stream0_IRQHandler,Default_Handler + + .weak DMA1_Stream1_IRQHandler + .thumb_set DMA1_Stream1_IRQHandler,Default_Handler + + .weak DMA1_Stream2_IRQHandler + .thumb_set DMA1_Stream2_IRQHandler,Default_Handler + + .weak DMA1_Stream3_IRQHandler + .thumb_set DMA1_Stream3_IRQHandler,Default_Handler + + .weak DMA1_Stream4_IRQHandler + .thumb_set DMA1_Stream4_IRQHandler,Default_Handler + + .weak DMA1_Stream5_IRQHandler + .thumb_set DMA1_Stream5_IRQHandler,Default_Handler + + .weak DMA1_Stream6_IRQHandler + .thumb_set DMA1_Stream6_IRQHandler,Default_Handler + + .weak ADC_IRQHandler + .thumb_set ADC_IRQHandler,Default_Handler + + .weak EXTI9_5_IRQHandler + .thumb_set EXTI9_5_IRQHandler,Default_Handler + + .weak TIM1_BRK_TIM9_IRQHandler + .thumb_set TIM1_BRK_TIM9_IRQHandler,Default_Handler + + .weak TIM1_UP_TIM10_IRQHandler + .thumb_set TIM1_UP_TIM10_IRQHandler,Default_Handler + + .weak TIM1_TRG_COM_TIM11_IRQHandler + .thumb_set TIM1_TRG_COM_TIM11_IRQHandler,Default_Handler + + .weak TIM1_CC_IRQHandler + .thumb_set TIM1_CC_IRQHandler,Default_Handler + + .weak TIM2_IRQHandler + .thumb_set TIM2_IRQHandler,Default_Handler + + .weak TIM3_IRQHandler + .thumb_set TIM3_IRQHandler,Default_Handler + + .weak TIM4_IRQHandler + .thumb_set TIM4_IRQHandler,Default_Handler + + .weak I2C1_EV_IRQHandler + .thumb_set I2C1_EV_IRQHandler,Default_Handler + + .weak I2C1_ER_IRQHandler + .thumb_set I2C1_ER_IRQHandler,Default_Handler + + .weak I2C2_EV_IRQHandler + .thumb_set I2C2_EV_IRQHandler,Default_Handler + + .weak I2C2_ER_IRQHandler + .thumb_set I2C2_ER_IRQHandler,Default_Handler + + .weak SPI1_IRQHandler + .thumb_set SPI1_IRQHandler,Default_Handler + + .weak SPI2_IRQHandler + .thumb_set SPI2_IRQHandler,Default_Handler + + .weak USART1_IRQHandler + .thumb_set USART1_IRQHandler,Default_Handler + + .weak USART2_IRQHandler + .thumb_set USART2_IRQHandler,Default_Handler + + .weak EXTI15_10_IRQHandler + .thumb_set EXTI15_10_IRQHandler,Default_Handler + + .weak RTC_Alarm_IRQHandler + .thumb_set RTC_Alarm_IRQHandler,Default_Handler + + .weak OTG_FS_WKUP_IRQHandler + .thumb_set OTG_FS_WKUP_IRQHandler,Default_Handler + + .weak DMA1_Stream7_IRQHandler + .thumb_set DMA1_Stream7_IRQHandler,Default_Handler + + .weak SDIO_IRQHandler + .thumb_set SDIO_IRQHandler,Default_Handler + + .weak TIM5_IRQHandler + .thumb_set TIM5_IRQHandler,Default_Handler + + .weak SPI3_IRQHandler + .thumb_set SPI3_IRQHandler,Default_Handler + + .weak DMA2_Stream0_IRQHandler + .thumb_set DMA2_Stream0_IRQHandler,Default_Handler + + .weak DMA2_Stream1_IRQHandler + .thumb_set DMA2_Stream1_IRQHandler,Default_Handler + + .weak DMA2_Stream2_IRQHandler + .thumb_set DMA2_Stream2_IRQHandler,Default_Handler + + .weak DMA2_Stream3_IRQHandler + .thumb_set DMA2_Stream3_IRQHandler,Default_Handler + + .weak DMA2_Stream4_IRQHandler + .thumb_set DMA2_Stream4_IRQHandler,Default_Handler + + .weak OTG_FS_IRQHandler + .thumb_set OTG_FS_IRQHandler,Default_Handler + + .weak DMA2_Stream5_IRQHandler + .thumb_set DMA2_Stream5_IRQHandler,Default_Handler + + .weak DMA2_Stream6_IRQHandler + .thumb_set DMA2_Stream6_IRQHandler,Default_Handler + + .weak DMA2_Stream7_IRQHandler + .thumb_set DMA2_Stream7_IRQHandler,Default_Handler + + .weak USART6_IRQHandler + .thumb_set USART6_IRQHandler,Default_Handler + + .weak I2C3_EV_IRQHandler + .thumb_set I2C3_EV_IRQHandler,Default_Handler + + .weak I2C3_ER_IRQHandler + .thumb_set I2C3_ER_IRQHandler,Default_Handler + + .weak FPU_IRQHandler + .thumb_set FPU_IRQHandler,Default_Handler + + .weak SPI4_IRQHandler + .thumb_set SPI4_IRQHandler,Default_Handler + + .weak SPI5_IRQHandler + .thumb_set SPI5_IRQHandler,Default_Handler + +/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/