diff --git a/Makefile b/Makefile
index 6bf45c36e..9b539cbd0 100755
--- a/Makefile
+++ b/Makefile
@@ -5,7 +5,7 @@
# this stuff is worth it, you can buy me a beer in return
###############################################################################
#
-# Makefile for building the cleanflight firmware.
+# Makefile for building the RACEFLIGHT firmware.
#
# Invoke this with 'make help' to see the list of supported targets.
#
@@ -15,16 +15,16 @@
#
# The target to build, see VALID_TARGETS below
-TARGET ?= NAZE
+TARGET ?= REVO
# Compile-time options
-OPTIONS ?=
+OPTIONS ?=
# compile for OpenPilot BootLoader support
-OPBL ?=no
+OPBL ?= no
# Debugger optons, must be empty or GDB
-DEBUG ?=
+DEBUG ?=
# Serial port/Device for flashing
SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found)
@@ -36,26 +36,27 @@ FLASH_SIZE ?=
# Things that need to be maintained as the source changes
#
-FORKNAME = raceflight
+FORKNAME = raceflight
-CC3D_TARGETS = CC3D CC3D_OPBL
-F1_TARGETS = NAZE OLIMEXINO CJMCU EUSTM32F103RC PORT103R ALIENWIIF1 AFROMINI
-F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENWIIF3 COLIBRI_RACE MOTOLAB RMDO LUX_RACE
-F4_TARGETS = REVO REVO_OPBL SPARKY2 SPARKY2_OPBL REVONANO REVONANO_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON KKNGF4
+CC3D_TARGETS = CC3D CC3D_OPBL
+F1_TARGETS = NAZE OLIMEXINO CJMCU EUSTM32F103RC PORT103R ALIENFLIGHTF1 AFROMINI
+F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE MOTOLAB RMDO LUX_RACE SPRACINGF3MINI ZCOREF3
+F4_TARGETS = REVO REVO_OPBL SPARKY2 SPARKY2_OPBL REVONANO REVONANO_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON QUANTON_OPBL AQ32_V2 KKNGF4
-F405_TARGETS = REVO REVO_OPBL SPARKY2 SPARKY2_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON KKNGF4
-F405_TARGETS_16 = QUANTON
-F411_TARGETS = REVONANO REVONANO_OPBL
+F405_TARGETS = REVO REVO_OPBL SPARKY2 SPARKY2_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE QUANTON AQ32_V2 KKNGF4
+F405_TARGETS_16 = QUANTON QUANTON_OPBL
+F411_TARGETS = REVONANO REVONANO_OPBL
+
+SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2
VALID_TARGETS = $(F1_TARGETS) $(CC3D_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
# Valid targets for OP BootLoader support
-OPBL_VALID_TARGETS = CC3D_OPBL REVO_OPBL REVONANO_OPBL SPARKY2_OPBL
+OPBL_VALID_TARGETS = CC3D_OPBL REVO_OPBL REVONANO_OPBL SPARKY2_OPBL QUANTON_OPBL
64K_TARGETS = CJMCU
-128K_TARGETS = ALIENWIIF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
-256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENWIIF3 COLIBRI_RACE MOTOLAB LUX_RACE $(F4_TARGETS)
-
+128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
+256K_TARGETS = EUSTM32F103RC PORT103R STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE MOTOLAB LUX_RACE SPRACINGF3MINI ZCOREF3 $(F4_TARGETS)
# Configure default flash sizes for the targets
ifeq ($(FLASH_SIZE),)
@@ -154,8 +155,17 @@ EXCLUDES = stm32f4xx_crc.c \
stm32f4xx_fmpi2c.c \
stm32f4xx_lptim.c \
stm32f4xx_qspi.c \
- stm32f4xx_spdifrx.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
+
ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS)))
EXCLUDES += stm32f4xx_fsmc.c
@@ -304,12 +314,18 @@ endif
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
-ifeq ($(TARGET),ALIENWIIF1)
-# ALIENWIIF1 is a VARIANT of NAZE
-TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENWII32
+ifeq ($(TARGET),ALIENFLIGHTF1)
+# ALIENFLIGHTF1 is a VARIANT of NAZE
+TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -DALIENFLIGHT
TARGET_DIR = $(ROOT)/src/main/target/NAZE
endif
+ifeq ($(TARGET),ZCOREF3)
+# ZCOREF3 is a VARIANT of SPRACINGF3
+TARGET_FLAGS := $(TARGET_FLAGS) -DSPRACINGF3 -DZCORE
+TARGET_DIR = $(ROOT)/src/main/target/SPRACINGF3
+endif
+
ifeq ($(TARGET),$(filter $(TARGET), $(CC3D_TARGETS)))
TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D
TARGET_DIR = $(ROOT)/src/main/target/CC3D
@@ -333,6 +349,12 @@ TARGET_DIR = $(ROOT)/src/main/target/SPARKY2
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
endif
+ifeq ($(TARGET),$(filter $(TARGET), QUANTON_OPBL))
+TARGET_FLAGS := $(TARGET_FLAGS) -DQUANTON
+TARGET_DIR = $(ROOT)/src/main/target/QUANTON
+TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
+endif
+
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
OPBL=yes
endif
@@ -342,7 +364,7 @@ ifeq ($(TARGET),$(filter $(TARGET),$(OPBL_VALID_TARGETS)))
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS)))
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_bl.ld
-else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS)))
+else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS) $(F405_TARGETS_16)))
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_bl.ld
else
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
@@ -364,7 +386,8 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
VPATH := $(VPATH):$(TARGET_DIR)
-COMMON_SRC = build_config.c \
+COMMON_SRC = \
+ build_config.c \
debug.c \
version.c \
$(TARGET_SRC) \
@@ -439,6 +462,44 @@ HIGHEND_SRC = \
blackbox/blackbox.c \
blackbox/blackbox_io.c
+STM32F10x_COMMON_SRC = \
+ startup_stm32f10x_md_gcc.S \
+ drivers/serial_softserial.c \
+ drivers/serial_uart.c \
+ drivers/serial_uart_stm32f10x.c \
+ drivers/system_stm32f10x.c \
+ drivers/pwm_mapping.c \
+ drivers/pwm_output.c \
+ drivers/pwm_rx.c \
+ drivers/timer.c \
+ drivers/timer_stm32f10x.c \
+ drivers/gpio_stm32f10x.c \
+ drivers/adc.c \
+ drivers/adc_stm32f10x.c \
+ drivers/bus_spi.c \
+ drivers/bus_i2c.c \
+ drivers/inverter.c
+
+STM32F30x_COMMON_SRC = \
+ startup_stm32f30x_md_gcc.S \
+ drivers/adc.c \
+ drivers/adc_stm32f30x.c \
+ drivers/bus_i2c_stm32f30x.c \
+ drivers/bus_spi.c \
+ drivers/gpio_stm32f30x.c \
+ drivers/light_led.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
+ drivers/pwm_mapping.c \
+ drivers/pwm_output.c \
+ drivers/pwm_rx.c \
+ drivers/serial_uart.c \
+ drivers/serial_uart_stm32f30x.c \
+ drivers/sound_beeper.c \
+ drivers/system_stm32f30x.c \
+ drivers/timer.c \
+ drivers/timer_stm32f30x.c
+
STM32F4xx_COMMON_SRC = \
startup_stm32f40xx.s \
drivers/accgyro_mpu.c \
@@ -474,7 +535,7 @@ VCP_SRC = \
vcp/usb_pwr.c \
drivers/serial_usb_vcp.c
-VCPF4_SRC = \
+VCPF4_SRC = \
vcpf4/stm32f4xx_it.c \
vcpf4/usb_bsp.c \
vcpf4/usbd_desc.c \
@@ -482,7 +543,8 @@ VCPF4_SRC = \
vcpf4/usbd_cdc_vcp.c \
drivers/serial_usb_vcp.c
-NAZE_SRC = startup_stm32f10x_md_gcc.S \
+NAZE_SRC = \
+ $(STM32F10x_COMMON_SRC) \
drivers/accgyro_adxl345.c \
drivers/accgyro_bma280.c \
drivers/accgyro_l3g4200d.c \
@@ -492,43 +554,29 @@ NAZE_SRC = startup_stm32f10x_md_gcc.S \
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.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/sound_beeper.c \
- drivers/system_stm32f10x.c \
- drivers/timer.c \
- drivers/timer_stm32f10x.c \
io/flashfs.c \
hardware_revision.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
-ALIENWIIF1_SRC = $(NAZE_SRC)
+ALIENFLIGHTF1_SRC = $(NAZE_SRC)
AFROMINI_SRC = $(NAZE_SRC)
-EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
+EUSTM32F103RC_SRC = \
+ $(STM32F10x_COMMON_SRC) \
drivers/accgyro_adxl345.c \
drivers/accgyro_bma280.c \
drivers/accgyro_l3g4200d.c \
@@ -538,64 +586,36 @@ EUSTM32F103RC_SRC = startup_stm32f10x_hd_gcc.S \
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.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/sound_beeper.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 \
+OLIMEXINO_SRC = \
+ $(STM32F10x_COMMON_SRC) \
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.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/sound_beeper.c \
- drivers/system_stm32f10x.c \
- drivers/timer.c \
- drivers/timer_stm32f10x.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
@@ -625,41 +645,27 @@ CJMCU_SRC = \
$(COMMON_SRC)
CC3D_SRC = \
- startup_stm32f10x_md_gcc.S \
+ $(STM32F10x_COMMON_SRC) \
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.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/sound_beeper.c \
- drivers/system_stm32f10x.c \
- drivers/timer.c \
- drivers/timer_stm32f10x.c \
io/flashfs.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)
-REVO_SRC = $(STM32F4xx_COMMON_SRC) \
+REVO_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
@@ -669,7 +675,8 @@ REVO_SRC = $(STM32F4xx_COMMON_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-KKNGF4_SRC = $(STM32F4xx_COMMON_SRC) \
+KKNGF4_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/light_ws2811strip.c \
@@ -678,7 +685,8 @@ KKNGF4_SRC = $(STM32F4xx_COMMON_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-REVONANO_SRC = $(STM32F4xx_COMMON_SRC) \
+REVONANO_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
@@ -686,17 +694,21 @@ REVONANO_SRC = $(STM32F4xx_COMMON_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-SPARKY2_SRC = $(STM32F4xx_COMMON_SRC) \
+SPARKY2_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_ms5611.c \
- drivers/compass_hmc5883l.c \
+ drivers/compass_ak8963.c \
drivers/light_ws2811strip.c \
drivers/light_ws2811strip_stm32f4xx.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-ALIENFLIGHTF4_SRC = $(STM32F4xx_COMMON_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 \
@@ -708,21 +720,33 @@ ALIENFLIGHTF4_SRC = $(STM32F4xx_COMMON_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-BLUEJAYF4_SRC = $(STM32F4xx_COMMON_SRC) \
+BLUEJAYF4_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_ms5611.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-QUANTON_SRC = $(STM32F4xx_COMMON_SRC) \
+QUANTON_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
+ drivers/accgyro_spi_mpu6000.c \
+ drivers/barometer_ms5611.c \
+ $(HIGHEND_SRC) \
+ $(COMMON_SRC) \
+ $(VCPF4_SRC)
+
+AQ32_V2_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
+ drivers/compass_hmc5883l.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-VRCORE_SRC = $(STM32F4xx_COMMON_SRC) \
+VRCORE_SRC = \
+ $(STM32F4xx_COMMON_SRC) \
drivers/accgyro_spi_mpu9250.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
@@ -732,26 +756,6 @@ VRCORE_SRC = $(STM32F4xx_COMMON_SRC) \
$(COMMON_SRC) \
$(VCPF4_SRC)
-STM32F30x_COMMON_SRC = \
- startup_stm32f30x_md_gcc.S \
- drivers/adc.c \
- drivers/adc_stm32f30x.c \
- drivers/bus_i2c_stm32f30x.c \
- drivers/bus_spi.c \
- drivers/gpio_stm32f30x.c \
- drivers/light_led.c \
- drivers/light_ws2811strip.c \
- drivers/light_ws2811strip_stm32f30x.c \
- drivers/pwm_mapping.c \
- drivers/pwm_output.c \
- drivers/pwm_rx.c \
- drivers/serial_uart.c \
- drivers/serial_uart_stm32f30x.c \
- drivers/sound_beeper.c \
- drivers/system_stm32f30x.c \
- drivers/timer.c \
- drivers/timer_stm32f30x.c
-
NAZE32PRO_SRC = \
$(STM32F30x_COMMON_SRC) \
$(HIGHEND_SRC) \
@@ -760,6 +764,8 @@ NAZE32PRO_SRC = \
STM32F3DISCOVERY_COMMON_SRC = \
$(STM32F30x_COMMON_SRC) \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/accgyro_l3gd20.c \
drivers/accgyro_l3gd20.c \
drivers/accgyro_lsm303dlhc.c \
@@ -790,7 +796,6 @@ COLIBRI_RACE_SRC = \
$(STM32F30x_COMMON_SRC) \
io/i2c_bst.c \
drivers/bus_bst_stm32f30x.c \
- drivers/display_ug2864hsweg01.c \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6500.c \
drivers/accgyro_spi_mpu6500.c \
@@ -798,6 +803,9 @@ COLIBRI_RACE_SRC = \
drivers/barometer_ms5611.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
+ drivers/display_ug2864hsweg01.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
@@ -807,7 +815,9 @@ LUX_RACE_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/display_ug2864hsweg01.c \
drivers/accgyro_mpu.c \
- drivers/accgyro_spi_mpu9250.c \
+ drivers/accgyro_mpu6500.c \
+ drivers/accgyro_spi_mpu6500.c \
+ drivers/accgyro_mpu6500.c \
drivers/barometer_ms5611.c \
drivers/compass_ak8975.c \
drivers/compass_hmc5883l.c \
@@ -827,13 +837,29 @@ SPARKY_SRC = \
drivers/barometer_ms5611.c \
drivers/barometer_bmp280.c \
drivers/compass_ak8975.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c \
+ drivers/sonar_hcsr04.c \
$(HIGHEND_SRC) \
$(COMMON_SRC) \
$(VCP_SRC)
-ALIENWIIF3_SRC = \
- $(SPARKY_SRC)
+ALIENFLIGHTF3_SRC = \
+ $(STM32F30x_COMMON_SRC) \
+ drivers/display_ug2864hsweg01.c \
+ drivers/accgyro_mpu.c \
+ drivers/accgyro_mpu6050.c \
+ drivers/accgyro_mpu6500.c \
+ drivers/accgyro_spi_mpu6500.c \
+ drivers/accgyro_spi_mpu9250.c \
+ drivers/compass_ak8963.c \
+ drivers/serial_usb_vcp.c \
+ drivers/sonar_hcsr04.c \
+ hardware_revision.c \
+ $(HIGHEND_SRC) \
+ $(COMMON_SRC) \
+ $(VCP_SRC)
RMDO_SRC = \
$(STM32F30x_COMMON_SRC) \
@@ -842,6 +868,8 @@ RMDO_SRC = \
drivers/barometer_bmp280.c \
drivers/display_ug2864hsweg01.h \
drivers/flash_m25p16.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_softserial.c \
drivers/sonar_hcsr04.c \
io/flashfs.c \
@@ -852,19 +880,25 @@ SPRACINGF3_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
drivers/accgyro_mpu6050.c \
+ drivers/accgyro_mpu6500.c \
drivers/barometer_ms5611.c \
drivers/compass_ak8975.c \
+ drivers/compass_ak8963.c \
drivers/barometer_bmp085.c \
drivers/barometer_bmp280.c \
drivers/compass_hmc5883l.c \
drivers/display_ug2864hsweg01.h \
drivers/flash_m25p16.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_softserial.c \
drivers/sonar_hcsr04.c \
io/flashfs.c \
$(HIGHEND_SRC) \
$(COMMON_SRC)
+ZCOREF3_SRC = $(SPRACINGF3_SRC)
+
IRCFUSIONF3_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
@@ -884,11 +918,13 @@ IRCFUSIONF3_SRC = \
MOTOLAB_SRC = \
$(STM32F30x_COMMON_SRC) \
drivers/accgyro_mpu.c \
- drivers/display_ug2864hsweg01.c \
drivers/accgyro_mpu6050.c \
drivers/accgyro_spi_mpu6000.c \
drivers/barometer_ms5611.c \
drivers/compass_hmc5883l.c \
+ drivers/display_ug2864hsweg01.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
drivers/serial_usb_vcp.c \
drivers/flash_m25p16.c \
io/flashfs.c \
@@ -896,6 +932,24 @@ MOTOLAB_SRC = \
$(COMMON_SRC) \
$(VCP_SRC)
+SPRACINGF3MINI_SRC = \
+ $(STM32F30x_COMMON_SRC) \
+ drivers/accgyro_mpu.c \
+ drivers/accgyro_mpu6500.c \
+ drivers/barometer_bmp280.c \
+ drivers/compass_ak8975.c \
+ drivers/compass_hmc5883l.c \
+ drivers/display_ug2864hsweg01.h \
+ drivers/flash_m25p16.c \
+ drivers/light_ws2811strip.c \
+ drivers/light_ws2811strip_stm32f30x.c \
+ drivers/serial_softserial.c \
+ drivers/serial_usb_vcp.c \
+ drivers/sonar_hcsr04.c \
+ $(HIGHEND_SRC) \
+ $(COMMON_SRC) \
+ $(VCP_SRC)
+
# Search path and source files for the ST stdperiph library
VPATH := $(VPATH):$(STDPERIPH_DIR)/src
@@ -904,7 +958,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
@@ -917,8 +971,8 @@ OPTIMIZE = -O0
LTO_FLAGS = $(OPTIMIZE)
else
ifeq ($(TARGET),$(filter $(TARGET),SPARKY2 SPARKY2_OPBL))
-OPTIMIZE = -O2
-else ifeq ($(TARGET),$(filter $(TARGET),REVO REVO_OPBL REVONANO REVONANO_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE KKNGF4))
+OPTIMIZE = -O0
+else ifeq ($(TARGET),$(filter $(TARGET),REVO REVO_OPBL REVONANO REVONANO_OPBL ALIENFLIGHTF4 BLUEJAYF4 VRCORE AQ32_V2))
OPTIMIZE = -O2
else
OPTIMIZE = -Os
@@ -985,6 +1039,7 @@ CC3D_OPBL_SRC = $(CC3D_SRC)
REVO_OPBL_SRC = $(REVO_SRC)
REVONANO_OPBL_SRC = $(REVONANO_SRC)
SPARKY2_OPBL_SRC = $(SPARKY2_SRC)
+QUANTON_OPBL_SRC = $(QUANTON_SRC)
TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(TARGET).bin
TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(TARGET).hex
@@ -1013,7 +1068,8 @@ $(TARGET_BIN): $(TARGET_ELF)
$(OBJCOPY) -O binary $< $@
$(TARGET_ELF): $(TARGET_OBJS)
- $(CC) -o $@ $^ $(LDFLAGS)
+ @echo LD $(notdir $@)
+ @$(CC) -o $@ $^ $(LDFLAGS)
$(SIZE) $(TARGET_ELF)
# Compile
diff --git a/src/main/config/config.c b/src/main/config/config.c
index ecc72d35a..666e860e9 100755
--- a/src/main/config/config.c
+++ b/src/main/config/config.c
@@ -665,12 +665,12 @@ static void resetConf(void)
featureSet(FEATURE_FAILSAFE);
#endif
- // alternative defaults settings for ALIENWIIF1 and ALIENWIIF3 targets
-#ifdef ALIENWII32
+ // alternative defaults settings for ALIENFLIGHTF1 and ALIENFLIGHTF3 targets
+#ifdef ALIENFLIGHT
featureSet(FEATURE_RX_SERIAL);
featureSet(FEATURE_MOTOR_STOP);
featureClear(FEATURE_ONESHOT125);
-#if defined(ALIENWIIF3) || defined(ALIENFLIGHTF4)
+#if defined(ALIENFLIGHTF3) || defined(ALIENFLIGHTF4)
masterConfig.serialConfig.portConfigs[1].functionMask = FUNCTION_MSP; //default config USART1 for MSP at 9600 for use with 1wire.
masterConfig.serialConfig.portConfigs[1].msp_baudrateIndex = BAUD_9600;
masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL;
diff --git a/src/main/drivers/accgyro_mpu6500.c b/src/main/drivers/accgyro_mpu6500.c
index ad0727557..d08fd9c1e 100644
--- a/src/main/drivers/accgyro_mpu6500.c
+++ b/src/main/drivers/accgyro_mpu6500.c
@@ -39,7 +39,7 @@ extern uint16_t acc_1G;
#define BIT_I2C_IF_DIS 0x10
-void resetGyro (void) {
+void mpu6500ResetGyro (void) {
// Device Reset
mpuConfiguration.write(MPU_RA_PWR_MGMT_1, MPU6500_BIT_RESET);
delay(100);
diff --git a/src/main/drivers/accgyro_mpu6500.h b/src/main/drivers/accgyro_mpu6500.h
index 67e482539..2569341a5 100644
--- a/src/main/drivers/accgyro_mpu6500.h
+++ b/src/main/drivers/accgyro_mpu6500.h
@@ -22,7 +22,7 @@
#pragma once
-void resetGyro(void);
+void mpu6500ResetGyro(void);
bool mpu6500AccDetect(acc_t *acc);
bool mpu6500GyroDetect(gyro_t *gyro);
diff --git a/src/main/drivers/accgyro_spi_mpu6500.c b/src/main/drivers/accgyro_spi_mpu6500.c
index 488c8f825..5859085f3 100755
--- a/src/main/drivers/accgyro_spi_mpu6500.c
+++ b/src/main/drivers/accgyro_spi_mpu6500.c
@@ -106,7 +106,7 @@ static void mpu6500SpiInit(void)
IOInit(mpuSpi6500CsPin, OWNER_SYSTEM, RESOURCE_SPI);
IOConfigGPIO(mpuSpi6500CsPin, SPI_IO_CS_CFG);
-#if defined(STM32F40_41xxx) || defined (STM32F411xE)
+#if defined(STM32F4)
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_SLOW_CLOCK);
#else
spiSetDivisor(MPU6500_SPI_INSTANCE, SPI_STANDARD_CLOCK);
@@ -123,7 +123,7 @@ bool mpu6500SpiDetect(void)
mpu6500ReadRegister(MPU_RA_WHO_AM_I, 1, &tmp);
- if (tmp == MPU6500_WHO_AM_I_CONST || tmp == MPU9250_WHO_AM_I_CONST) {
+ if (tmp == MPU6500_WHO_AM_I_CONST) {
return true;
}
diff --git a/src/main/drivers/pwm_mapping.c b/src/main/drivers/pwm_mapping.c
index 1ed0627a6..581968143 100755
--- a/src/main/drivers/pwm_mapping.c
+++ b/src/main/drivers/pwm_mapping.c
@@ -367,7 +367,7 @@ static const uint16_t airPWM[] = {
};
#endif
-#if defined(SPARKY) || defined(ALIENWIIF3)
+#if defined(SPARKY) || defined(ALIENFLIGHTF3)
static const uint16_t multiPPM[] = {
PWM11 | (MAP_TO_PPM_INPUT << 8), // PPM input
@@ -780,6 +780,68 @@ static const uint16_t airPWM[] = {
};
#endif
+#ifdef YOUPIF4
+static const uint16_t multiPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
+ 0xFFFF
+};
+static const uint16_t multiPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or servo #1 (swap to servo if needed)
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed)
+ PWM8 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6
+ 0xFFFF
+};
+
+static const uint16_t airPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM8 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM9 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM10 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM2 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM3 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM4 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
+ 0xFFFF
+};
+
+static const uint16_t airPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM7 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
+ PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM9 | (MAP_TO_SERVO_OUTPUT << 8), // servo #2
+ PWM10 | (MAP_TO_SERVO_OUTPUT << 8), // servo #3
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
+ 0xFFFF
+};
+#endif
+
+
#ifdef QUANTON
static const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
@@ -849,6 +911,91 @@ static const uint16_t airPWM[] = {
};
#endif
+#ifdef AQ32_V2
+static const uint16_t multiPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8
+ PWM17 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM18 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM19 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM20 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
+ 0xFFFF
+};
+
+static const uint16_t multiPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_PWM_INPUT << 8),
+ PWM7 | (MAP_TO_PWM_INPUT << 8),
+ PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM11 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM12 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM13 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM14 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM15 | (MAP_TO_MOTOR_OUTPUT << 8),
+ PWM16 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #8
+ PWM17 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM18 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM19 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM20 | (MAP_TO_SERVO_OUTPUT << 8), // servo #4
+ 0xFFFF
+};
+
+static const uint16_t airPPM[] = {
+ PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM17 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM18 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM19 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM20 | (MAP_TO_SERVO_OUTPUT << 8), // server #10
+ 0xFFFF
+};
+
+static const uint16_t airPWM[] = {
+ PWM1 | (MAP_TO_PWM_INPUT << 8), // input #1
+ PWM2 | (MAP_TO_PWM_INPUT << 8),
+ PWM3 | (MAP_TO_PWM_INPUT << 8),
+ PWM4 | (MAP_TO_PWM_INPUT << 8),
+ PWM5 | (MAP_TO_PWM_INPUT << 8),
+ PWM6 | (MAP_TO_PWM_INPUT << 8),
+ PWM7 | (MAP_TO_PWM_INPUT << 8),
+ PWM8 | (MAP_TO_PWM_INPUT << 8), // input #8
+ PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1
+ PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2
+ PWM11 | (MAP_TO_SERVO_OUTPUT << 8), // servo #1
+ PWM12 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM13 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM14 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM15 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM16 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM17 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM18 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM19 | (MAP_TO_SERVO_OUTPUT << 8),
+ PWM20 | (MAP_TO_SERVO_OUTPUT << 8), // server #10
+ 0xFFFF
+};
+#endif
+
#ifdef KKNGF4
static const uint16_t multiPPM[] = {
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
@@ -1056,7 +1203,6 @@ if (init->useBuzzerP6) {
const timerHardware_t *timerHardwarePtr = &timerHardware[timerIndex];
-
#ifdef OLIMEXINO_UNCUT_LED2_E_JUMPER
// PWM2 is connected to LED2 on the board and cannot be connected unless you cut LED2_E
if (timerIndex == PWM2)
@@ -1183,7 +1329,6 @@ if (init->useBuzzerP6) {
#endif
}
-
if (init->useChannelForwarding && !init->airplane) {
#if defined(NAZE) && defined(LED_STRIP_TIMER)
// if LED strip is active, PWM5-8 are unavailable, so map AUX1+AUX2 to PWM13+PWM14
@@ -1234,11 +1379,21 @@ if (init->useBuzzerP6) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM1);
}
#endif
+#ifdef AQ32_V2
+ if (init->useMultiShot || init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
+ ppmAvoidPWMTimerClash(timerHardwarePtr, TIM4);
+ }
+#endif
#ifdef VRCORE
if (init->useMultiShot || init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
ppmAvoidPWMTimerClash(timerHardwarePtr, TIM1);
}
#endif
+#ifdef YOUPIF4
+ if (init->useMultiShot || init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
+ ppmAvoidPWMTimerClash(timerHardwarePtr, TIM8);
+ }
+#endif
//#ifdef KKNGF4
// if (init->useMultiShot || init->useOneshot || isMotorBrushed(init->motorPwmRate)) {
// ppmAvoidPWMTimerClash(timerHardwarePtr, TIM8);
diff --git a/src/main/drivers/pwm_mapping.h b/src/main/drivers/pwm_mapping.h
index e36b0c5df..f48ff0426 100644
--- a/src/main/drivers/pwm_mapping.h
+++ b/src/main/drivers/pwm_mapping.h
@@ -137,7 +137,11 @@ enum {
PWM13,
PWM14,
PWM15,
- PWM16
+ PWM16,
+ PWM17,
+ PWM18,
+ PWM19,
+ PWM20
};
pwmOutputConfiguration_t *pwmGetOutputConfiguration(void);
diff --git a/src/main/drivers/timer.c b/src/main/drivers/timer.c
index ff240dcbb..dc9db6063 100755
--- a/src/main/drivers/timer.c
+++ b/src/main/drivers/timer.c
@@ -202,7 +202,7 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#endif
-#if defined(SPARKY) || defined(ALIENWIIF3)
+#if defined(SPARKY) || defined(ALIENFLIGHTF3)
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
//
// 6 x 3 pin headers
@@ -385,6 +385,29 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#endif
+#if defined(YOUPIF4)
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM8}, // PPM IN
+ { TIM12, GPIOB, Pin_14, TIM_Channel_1, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM12}, // S2_IN
+ { TIM12, GPIOB, Pin_15, TIM_Channel_2, TIM8_BRK_TIM12_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM12}, // S3_IN - GPIO_PartialRemap_TIM3
+ { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM8}, // S4_IN
+ { TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8}, // S5_IN
+
+ { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM3}, // S1_OUT
+ { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM3}, // S2_OUT
+ { TIM9, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM9_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM9}, // S3_OUT
+ { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM2}, // S4_OUT
+ { TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5}, // S5_OUT - GPIO_PartialRemap_TIM3
+ { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5}, // S6_OUT
+};
+
+#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9))
+
+#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM5 | RCC_APB1Periph_TIM12 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC)
+#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM8 | RCC_APB2Periph_TIM9)
+
+#endif
+
#ifdef QUANTON
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM1, GPIOA, Pin_10, TIM_Channel_3, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource10, GPIO_AF_TIM1 },
@@ -413,6 +436,39 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
#endif
+#ifdef AQ32_V2
+const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
+ { TIM4, GPIOD, Pin_12, TIM_Channel_1, TIM4_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource12, GPIO_AF_TIM4 },
+ { TIM4, GPIOD, Pin_13, TIM_Channel_2, TIM4_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource13, GPIO_AF_TIM4 },
+ { TIM4, GPIOD, Pin_14, TIM_Channel_3, TIM4_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM4 },
+ { TIM4, GPIOD, Pin_15, TIM_Channel_4, TIM4_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource14, GPIO_AF_TIM4 },
+ { TIM1, GPIOE, Pin_9, TIM_Channel_1, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM1 },
+ { TIM1, GPIOE, Pin_11, TIM_Channel_2, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource11, GPIO_AF_TIM1 },
+ { TIM1, GPIOE, Pin_12, TIM_Channel_3, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource12, GPIO_AF_TIM1 },
+ { TIM1, GPIOE, Pin_13, TIM_Channel_4, TIM1_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource13, GPIO_AF_TIM1 },
+
+ { TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8 },
+ { TIM8, GPIOC, Pin_8, TIM_Channel_3, TIM8_CC_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource8, GPIO_AF_TIM8 },
+ { TIM8, GPIOC, Pin_7, TIM_Channel_2, TIM8_CC_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource7, GPIO_AF_TIM8 },
+ { TIM8, GPIOC, Pin_6, TIM_Channel_1, TIM8_CC_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource6, GPIO_AF_TIM8 },
+ { TIM2, GPIOA, Pin_15, TIM_Channel_1, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource15, GPIO_AF_TIM2 },
+ { TIM2, GPIOB, Pin_3, TIM_Channel_2, TIM2_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM2 },
+ { TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource4, GPIO_AF_TIM3 },
+ { TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource5, GPIO_AF_TIM3 },
+
+ { TIM5, GPIOA, Pin_3, TIM_Channel_4, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource3, GPIO_AF_TIM5 },
+ { TIM5, GPIOA, Pin_2, TIM_Channel_3, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource2, GPIO_AF_TIM5 },
+ { TIM5, GPIOA, Pin_1, TIM_Channel_2, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource1, GPIO_AF_TIM5 },
+ { TIM5, GPIOA, Pin_0, TIM_Channel_1, TIM5_IRQn, 1, GPIO_Mode_AF, GPIO_PinSource0, GPIO_AF_TIM5 },
+};
+
+#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8))
+
+#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4| RCC_APB1Periph_TIM5 | RCC_AHB1Periph_GPIOA | RCC_AHB1Periph_GPIOB | RCC_AHB1Periph_GPIOC | RCC_AHB1Periph_GPIOD | RCC_AHB1Periph_GPIOE)
+#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM8)
+
+#endif
+
#if defined(KKNGF4)
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
{ TIM8, GPIOC, Pin_9, TIM_Channel_4, TIM8_CC_IRQn, 0, GPIO_Mode_AF, GPIO_PinSource9, GPIO_AF_TIM8}, // PPM_IN
diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c
index b5a99b675..329327448 100755
--- a/src/main/io/serial_msp.c
+++ b/src/main/io/serial_msp.c
@@ -81,7 +81,7 @@
#include "config/config_master.h"
#include "version.h"
-#ifdef NAZE
+#ifdef USE_HARDWARE_REVISION_DETECTION
#include "hardware_revision.h"
#endif
diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.c b/src/main/target/ALIENFLIGHTF3/hardware_revision.c
new file mode 100644
index 000000000..8ccb69143
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.c
@@ -0,0 +1,56 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#include
+#include
+#include
+
+#include "platform.h"
+
+#include "build_config.h"
+
+#include "drivers/system.h"
+#include "drivers/gpio.h"
+
+#include "hardware_revision.h"
+
+static const char * const hardwareRevisionNames[] = {
+ "Unknown",
+ "AlienFlight V1",
+ "AlienFlight V2"
+};
+
+uint8_t hardwareRevision = UNKNOWN;
+
+void detectHardwareRevision(void)
+{
+ gpio_config_t cfg = {HW_PIN, Mode_IPU, Speed_2MHz};
+ RCC_AHBPeriphClockCmd(HW_PERIPHERAL, ENABLE);
+ gpioInit(HW_GPIO, &cfg);
+
+ // Check hardware revision
+ delayMicroseconds(10); // allow configuration to settle
+ if (digitalIn(HW_GPIO, HW_PIN)) {
+ hardwareRevision = AFF3_REV_1;
+ } else {
+ hardwareRevision = AFF3_REV_2;
+ }
+}
+
+void updateHardwareRevision(void)
+{
+}
diff --git a/src/main/target/ALIENFLIGHTF3/hardware_revision.h b/src/main/target/ALIENFLIGHTF3/hardware_revision.h
new file mode 100644
index 000000000..f4c0e9095
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF3/hardware_revision.h
@@ -0,0 +1,27 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+typedef enum awf3HardwareRevision_t {
+ UNKNOWN = 0,
+ AFF3_REV_1, // MPU6050 / MPU9150 (I2C)
+ AFF3_REV_2 // MPU6500 / MPU9250 (SPI)
+} awf3HardwareRevision_e;
+
+extern uint8_t hardwareRevision;
+
+void updateHardwareRevision(void);
+void detectHardwareRevision(void);
diff --git a/src/main/target/ALIENWIIF3/system_stm32f30x.c b/src/main/target/ALIENFLIGHTF3/system_stm32f30x.c
similarity index 100%
rename from src/main/target/ALIENWIIF3/system_stm32f30x.c
rename to src/main/target/ALIENFLIGHTF3/system_stm32f30x.c
diff --git a/src/main/target/ALIENWIIF3/system_stm32f30x.h b/src/main/target/ALIENFLIGHTF3/system_stm32f30x.h
similarity index 100%
rename from src/main/target/ALIENWIIF3/system_stm32f30x.h
rename to src/main/target/ALIENFLIGHTF3/system_stm32f30x.h
diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h
new file mode 100644
index 000000000..1749fdcc4
--- /dev/null
+++ b/src/main/target/ALIENFLIGHTF3/target.h
@@ -0,0 +1,153 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+
+#define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3.
+
+#define USE_HARDWARE_REVISION_DETECTION
+#define HW_GPIO GPIOB
+#define HW_PIN Pin_2
+#define HW_PERIPHERAL RCC_AHBPeriph_GPIOB
+
+#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
+#define CONFIG_FEATURE_RX_SERIAL
+#define CONFIG_RX_SERIAL_PORT 2
+
+#define USBD_PRODUCT_STRING "AlienFlight F3"
+
+// LED's V1
+#define LED0 PB4 // LED - PB4
+#define LED1 PB5 // LED - PB5
+
+// LED's V2
+#define LED0_A PB8 // LED - PB8
+#define LED1_A PB9 // LED - PB9
+
+#define BEEPER PA5 // LED - PA5
+
+#define USABLE_TIMER_CHANNEL_COUNT 11
+
+//#define DEBUG_MPU_DATA_READY_INTERRUPT
+#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU data ready
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+#define USE_EXTI
+
+#define MPU6500_CS_PIN PA15
+#define MPU6500_SPI_INSTANCE SPI3
+#define MPU9250_CS_PIN PA15
+#define MPU9250_SPI_INSTANCE SPI3
+
+#define GYRO
+#define USE_GYRO_MPU6050
+#define USE_GYRO_SPI_MPU6500
+#define USE_GYRO_SPI_MPU9250
+
+#define GYRO_MPU6050_ALIGN CW270_DEG
+#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_MPU9250_ALIGN CW270_DEG
+
+#define ACC
+#define USE_ACC_MPU6050
+#define USE_ACC_SPI_MPU6500
+#define USE_ACC_SPI_MPU9250
+
+#define ACC_MPU6050_ALIGN CW270_DEG
+#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_MPU9250_ALIGN CW270_DEG
+
+// No baro support.
+//#define BARO
+//#define USE_BARO_MS5611
+
+#define MAG
+#define USE_MAG_AK8963
+#define MAG_AK8963_ALIGN CW0_DEG_FLIP
+
+#define USE_VCP
+#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
+#define USE_USART2 // Receiver - RX (PA3)
+#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
+#define SERIAL_PORT_COUNT 4
+
+#define UART1_TX_PIN GPIO_Pin_6 // PB6
+#define UART1_RX_PIN GPIO_Pin_7 // PB7
+#define UART1_GPIO GPIOB
+#define UART1_GPIO_AF GPIO_AF_7
+#define UART1_TX_PINSOURCE GPIO_PinSource6
+#define UART1_RX_PINSOURCE GPIO_PinSource7
+
+#define UART2_TX_PIN GPIO_Pin_2 // PA2
+#define UART2_RX_PIN GPIO_Pin_3 // PA3
+#define UART2_GPIO GPIOA
+#define UART2_GPIO_AF GPIO_AF_7
+#define UART2_TX_PINSOURCE GPIO_PinSource2
+#define UART2_RX_PINSOURCE GPIO_PinSource3
+
+#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
+#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
+#define UART3_GPIO_AF GPIO_AF_7
+#define UART3_GPIO GPIOB
+#define UART3_TX_PINSOURCE GPIO_PinSource10
+#define UART3_RX_PINSOURCE GPIO_PinSource11
+
+
+#define USE_I2C
+#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
+
+#define I2C2_SCL PA9
+#define I2C2_SDA PA10
+
+#define USE_SPI
+#define USE_SPI_DEVICE_3
+
+#define USE_ADC
+
+#define ADC_INSTANCE ADC2
+#define ADC_DMA_CHANNEL DMA2_Channel1
+#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
+
+//#define BOARD_HAS_VOLTAGE_DIVIDER
+
+#define VBAT_ADC_PIN PA4
+#define VBAT_ADC_CHANNEL ADC_Channel_1
+
+//#define BLACKBOX
+#define SERIAL_RX
+//#define GPS
+#define GTUNE
+//#define DISPLAY
+#define USE_SERVOS
+#define USE_CLI
+
+#define SPEKTRUM_BIND
+// USART2, PA3
+#define BIND_PORT GPIOA
+#define BIND_PIN Pin_3
+
+// alternative defaults for AlienFlight F3 target
+#define ALIENFLIGHT
+
+// Hardware bind plug at PB12 (Pin 25)
+#define HARDWARE_BIND_PLUG
+#define BINDPLUG_PORT GPIOB
+#define BINDPLUG_PIN Pin_12
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h
index 5e29b3c15..cf1b2c80b 100644
--- a/src/main/target/ALIENFLIGHTF4/target.h
+++ b/src/main/target/ALIENFLIGHTF4/target.h
@@ -19,86 +19,118 @@
#define TARGET_BOARD_IDENTIFIER "AFF4"
#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
-#define CONFIG_SERIALRX_PROVIDER 2
-#define CONFIG_BLACKBOX_DEVICE 1
+#define CONFIG_SERIALRX_PROVIDER SERIALRX_SPEKTRUM2048
+//#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
#define CONFIG_FEATURE_RX_SERIAL
-#define CONFIG_FEATURE_ONESHOT125
#define CONFIG_MSP_PORT 1
-//#define CONFIG_RX_SERIAL_PORT 2
+#define CONFIG_RX_SERIAL_PORT 2
-#define USBD_PRODUCT_STRING "AlienFlightF4"
+#define USBD_PRODUCT_STRING "AlienFlight F4"
-#define LED0 PC12
-#define LED1 PD2
+#define LED0 PC12
+#define LED1 PD2
-#define BEEPER PC13
+#define BEEPER PC13
-#define INVERTER PC15
-#define INVERTER_USART USART2
+#define INVERTER PC15
+#define INVERTER_USART USART2
-#define MPU9250_CS_PIN PA4
-#define MPU9250_SPI_INSTANCE SPI1
+// MPU interrupt
+//#define DEBUG_MPU_DATA_READY_INTERRUPT
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
+#define MPU_INT_EXTI PC14
+#define USE_EXTI
+
+#define MPU6500_CS_PIN PA4
+#define MPU6500_SPI_INSTANCE SPI1
+#define MPU9250_CS_PIN PA4
+#define MPU9250_SPI_INSTANCE SPI1
#define ACC
-#define USE_ACC_MPU9250
+#define USE_ACC_SPI_MPU6500
#define USE_ACC_SPI_MPU9250
-#define ACC_MPU9250_ALIGN CW270_DEG
+
+#define ACC_MPU6500_ALIGN CW270_DEG
+#define ACC_MPU9250_ALIGN CW270_DEG
#define GYRO
-#define USE_GYRO_MPU9250
+#define USE_GYRO_SPI_MPU6500
#define USE_GYRO_SPI_MPU9250
-#define GYRO_MPU9250_ALIGN CW270_DEG
+
+#define GYRO_MPU6500_ALIGN CW270_DEG
+#define GYRO_MPU9250_ALIGN CW270_DEG
#define MAG
#define USE_MAG_HMC5883
-//#define MAG_HMC5883_ALIGN CW180_DEG
#define USE_MAG_AK8963
-#define MAG_AK8963_ALIGN CW270_DEG
+
+#define MAG_HMC5883_ALIGN CW180_DEG
+#define MAG_AK8963_ALIGN CW270_DEG
#define BARO
#define USE_BARO_MS5611
#define USE_BARO_BMP280
-#define M25P16_CS_PIN PB12
-#define M25P16_SPI_INSTANCE SPI2
+#define USE_SDCARD
-#define USE_FLASHFS
-#define USE_FLASH_M25P16
+//#define SDCARD_DETECT_INVERTED
-#define USABLE_TIMER_CHANNEL_COUNT 13
+#define SDCARD_DETECT_PIN PB10
+#define SDCARD_DETECT_EXTI_LINE EXTI_Line10
+#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource10
+#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOB
+#define SDCARD_DETECT_EXTI_IRQn EXTI15_10_IRQn
-// MPU6500 interrupt
-//#define DEBUG_MPU_DATA_READY_INTERRUPT
-#define USE_MPU_DATA_READY_SIGNAL
-#define ENSURE_MPU_DATA_READY_IS_LOW
-#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready
-#define MPU_INT_EXTI PC14
-#define USE_EXTI
+#define SDCARD_SPI_INSTANCE SPI2
+#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN
+
+// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
+#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
+// Divide to under 25MHz for normal operation:
+#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
+
+#define SDCARD_DMA_CHANNEL_TX DMA1_Stream4
+#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF4
+#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1
+#define SDCARD_DMA_CHANNEL DMA_Channel_0
+
+// Performance logging for SD card operations:
+// #define AFATFS_USE_INTROSPECTIVE_LOGGING
+
+//#define M25P16_CS_PIN SPI2_NSS_PIN
+//#define M25P16_SPI_INSTANCE SPI2
+
+//#define USE_FLASHFS
+//#define USE_FLASH_M25P16
+
+#define USABLE_TIMER_CHANNEL_COUNT 13
#define USE_VCP
#define USE_USART1
-#define USART1_RX_PIN PA10
-#define USART1_TX_PIN PA9
+#define USART1_RX_PIN PA10
+#define USART1_TX_PIN PA9
#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
#define USE_USART2
-#define USART2_RX_PIN PA3
-#define USART2_TX_PIN PA2 //inverter
+#define USART2_RX_PIN PA3
+#define USART2_TX_PIN PA2 //inverter
-#define USE_USART3
-#define USART3_RX_PIN PB11
-#define USART3_TX_PIN PB10
+//#define USE_USART3
+//#define USART3_RX_PIN PB11
+//#define USART3_TX_PIN PB10
#define USE_USART4
-#define USART4_RX_PIN PC10
-#define USART4_TX_PIN PC11
+#define USART4_RX_PIN PC10
+#define USART4_TX_PIN PC11
//#define USE_USART5
-//#define USART5_RX_PIN PD2
-//#define USART5_TX_PIN PC12
+//#define USART5_RX_PIN PD2
+//#define USART5_TX_PIN PC12
-#define SERIAL_PORT_COUNT 5
+#define SERIAL_PORT_COUNT 4
//#define USE_ESCSERIAL
//#define ESCSERIAL_TIMER_TX_HARDWARE 0 // PWM 1
@@ -108,48 +140,48 @@
#define USE_SPI_DEVICE_1
#define USE_SPI_DEVICE_2
-#define SPI2_NSS_PIN PB12
-#define SPI2_SCK_PIN PB13
-#define SPI2_MISO_PIN PC2
-#define SPI2_MOSI_PIN PC3
+#define SPI2_NSS_PIN PB12
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PC2
+#define SPI2_MOSI_PIN PC3
#define USE_SPI_DEVICE_3
#define USE_I2C
-#define I2C_DEVICE (I2CDEV_1)
-//#define I2C_DEVICE_EXT (I2CDEV_2)
-#define I2C1_SCL PB6
-#define I2C1_SDA PB7
+#define I2C_DEVICE (I2CDEV_1)
+//#define I2C_DEVICE_EXT (I2CDEV_2)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
#define USE_ADC
//#define BOARD_HAS_VOLTAGE_DIVIDER
-#define VBAT_ADC_PIN PC0
-#define VBAT_ADC_CHANNEL ADC_Channel_1
+#define VBAT_ADC_PIN PC0
+#define VBAT_ADC_CHANNEL ADC_Channel_1
-#define CURRENT_METER_ADC_PIN PC1
-#define CURRENT_METER_ADC_CHANNEL ADC_Channel_0
+#define CURRENT_METER_ADC_PIN PC1
+#define CURRENT_METER_ADC_CHANNEL ADC_Channel_0
-#define RSSI_ADC_PIN PC4
-#define RSSI_ADC_CHANNEL ADC_Channel_4
+#define RSSI_ADC_PIN PC4
+#define RSSI_ADC_CHANNEL ADC_Channel_4
-#define EXTERNAL1_ADC_GPIO_PIN PC5
-#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
+#define EXTERNAL1_ADC_GPIO_PIN PC5
+#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5
// LED strip configuration using RC5 pin.
//#define LED_STRIP
-//#define LED_STRIP_TIMER TIM8
+//#define LED_STRIP_TIMER TIM8
//#define USE_LED_STRIP_ON_DMA1_CHANNEL3
-//#define WS2811_GPIO GPIOB
-//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
-//#define WS2811_GPIO_AF GPIO_AF_3
-//#define WS2811_PIN GPIO_Pin_15 // TIM8_CH3
-//#define WS2811_PIN_SOURCE GPIO_PinSource15
-//#define WS2811_TIMER TIM8
-//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM8
-//#define WS2811_DMA_CHANNEL DMA1_Channel3
-//#define WS2811_IRQ DMA1_Channel3_IRQn
+//#define WS2811_GPIO GPIOB
+//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOB
+//#define WS2811_GPIO_AF GPIO_AF_3
+//#define WS2811_PIN GPIO_Pin_15 // TIM8_CH3
+//#define WS2811_PIN_SOURCE GPIO_PinSource15
+//#define WS2811_TIMER TIM8
+//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM8
+//#define WS2811_DMA_CHANNEL DMA1_Channel3
+//#define WS2811_IRQ DMA1_Channel3_IRQn
#define BLACKBOX
//#define DISPLAY
@@ -162,27 +194,27 @@
#define SPEKTRUM_BIND
// USART2, PA3
-#define BIND_PORT GPIOA
-#define BIND_PIN Pin_3
+#define BIND_PORT GPIOA
+#define BIND_PIN Pin_3
-// alternative defaults for AlienWii32 F4 target
-#define ALIENWII32
+// alternative defaults for AlienFlight F4 target
+#define ALIENFLIGHT
// Hardware bind plug at PB2 (Pin 28)
#define HARDWARE_BIND_PLUG
-#define BINDPLUG_PORT GPIOB
-#define BINDPLUG_PIN Pin_2
+#define BINDPLUG_PORT GPIOB
+#define BINDPLUG_PIN Pin_2
#define USE_SERIAL_1WIRE
#define ESC_COUNT 8
-#define S1W_TX_GPIO GPIOA
-#define S1W_TX_PIN GPIO_Pin_9
-#define S1W_RX_GPIO GPIOA
-#define S1W_RX_PIN GPIO_Pin_10
+#define S1W_TX_GPIO GPIOA
+#define S1W_TX_PIN GPIO_Pin_9
+#define S1W_RX_GPIO GPIOA
+#define S1W_RX_PIN GPIO_Pin_10
#define USE_QUATERNION
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD (BIT(2))
diff --git a/src/main/target/ALIENWIIF3/target.h b/src/main/target/ALIENWIIF3/target.h
deleted file mode 100644
index dac56560d..000000000
--- a/src/main/target/ALIENWIIF3/target.h
+++ /dev/null
@@ -1,122 +0,0 @@
-/*
- * This file is part of Cleanflight.
- *
- * Cleanflight is free software: you can redistribute it and/or modify
- * it under the terms of the GNU General Public License as published by
- * the Free Software Foundation, either version 3 of the License, or
- * (at your option) any later version.
- *
- * Cleanflight is distributed in the hope that it will be useful,
- * but WITHOUT ANY WARRANTY; without even the implied warranty of
- * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
- * GNU General Public License for more details.
- *
- * You should have received a copy of the GNU General Public License
- * along with Cleanflight. If not, see .
- */
-
-#pragma once
-
-#define TARGET_BOARD_IDENTIFIER "AWF3" // AlienWii32 F3.
-
-#define USBD_PRODUCT_STRING "AlienWii32 F3"
-
-#define LED0 PB4 // Blue LEDs - PB4
-#define LED1 PB5 // Green LEDs - PB5
-#define BEEPER PA5 // White LEDs - PA5
-
-#define USABLE_TIMER_CHANNEL_COUNT 11
-
-// Using MPU6050 for the moment.
-#define GYRO
-#define USE_GYRO_MPU6050
-
-#define GYRO_MPU6050_ALIGN CW270_DEG
-
-#define ACC
-#define USE_ACC_MPU6050
-
-#define ACC_MPU6050_ALIGN CW270_DEG
-
-// No baro support.
-//#define BARO
-//#define USE_BARO_MS5611
-
-// No mag support for now (option to use MPU9150 in the future).
-//#define MAG
-//#define USE_MAG_AK8975
-
-#define MAG_AK8975_ALIGN CW0_DEG_FLIP
-
-#define USE_VCP
-#define USE_USART1 // Not connected - TX (PB6) RX PB7 (AF7)
-#define USE_USART2 // Receiver - RX (PA3)
-#define USE_USART3 // Not connected - 10/RX (PB11) 11/TX (PB10)
-#define SERIAL_PORT_COUNT 4
-
-#define UART1_TX_PIN GPIO_Pin_6 // PB6
-#define UART1_RX_PIN GPIO_Pin_7 // PB7
-#define UART1_GPIO GPIOB
-#define UART1_GPIO_AF GPIO_AF_7
-#define UART1_TX_PINSOURCE GPIO_PinSource6
-#define UART1_RX_PINSOURCE GPIO_PinSource7
-
-#define UART2_TX_PIN GPIO_Pin_2 // PA2
-#define UART2_RX_PIN GPIO_Pin_3 // PA3
-#define UART2_GPIO GPIOA
-#define UART2_GPIO_AF GPIO_AF_7
-#define UART2_TX_PINSOURCE GPIO_PinSource2
-#define UART2_RX_PINSOURCE GPIO_PinSource3
-
-#define UART3_TX_PIN GPIO_Pin_10 // PB10 (AF7)
-#define UART3_RX_PIN GPIO_Pin_11 // PB11 (AF7)
-#define UART3_GPIO_AF GPIO_AF_7
-#define UART3_GPIO GPIOB
-#define UART3_TX_PINSOURCE GPIO_PinSource10
-#define UART3_RX_PINSOURCE GPIO_PinSource11
-
-
-#define USE_I2C
-#define I2C_DEVICE (I2CDEV_2) // SDA (PA10/AF4), SCL (PA9/AF4)
-
-#define I2C2_SCL PA9
-#define I2C2_SDA PA10
-
-#define USE_ADC
-
-#define ADC_INSTANCE ADC2
-#define ADC_DMA_CHANNEL DMA2_Channel1
-#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA2
-
-//#define BOARD_HAS_VOLTAGE_DIVIDER
-
-#define VBAT_ADC_PIN PA4
-#define VBAT_ADC_CHANNEL ADC_Channel_1
-
-//#define BLACKBOX
-#define SERIAL_RX
-//#define GPS
-#define GTUNE
-//#define DISPLAY
-#define USE_SERVOS
-#define USE_CLI
-
-#define SPEKTRUM_BIND
-// USART2, PA3
-#define BIND_PORT GPIOA
-#define BIND_PIN Pin_3
-
-// alternative defaults for AlienWii32 F3 target
-#define ALIENWII32
-#define HARDWARE_BIND_PLUG
-
-// Hardware bind plug at PB12 (Pin 25)
-#define BINDPLUG_PORT GPIOB
-#define BINDPLUG_PIN Pin_12
-
-// IO - assuming 303 in 64pin package, TODO
-#define TARGET_IO_PORTA 0xffff
-#define TARGET_IO_PORTB 0xffff
-#define TARGET_IO_PORTC 0xffff
-#define TARGET_IO_PORTD (BIT(2))
-#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
\ No newline at end of file
diff --git a/src/main/target/AQ32_V2/system_stm32f4xx.c b/src/main/target/AQ32_V2/system_stm32f4xx.c
new file mode 100644
index 000000000..142fae8b6
--- /dev/null
+++ b/src/main/target/AQ32_V2/system_stm32f4xx.c
@@ -0,0 +1,1227 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.c
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device Peripheral Access Layer System Source File.
+ * This file contains the system clock configuration for STM32F4xx devices.
+ *
+ * 1. This file provides two functions and one global variable to be called from
+ * user application:
+ * - SystemInit(): Setups the system clock (System clock source, PLL Multiplier
+ * and Divider factors, AHB/APBx prescalers and Flash settings),
+ * depending on the configuration made in the clock xls tool.
+ * This function is called at startup just after reset and
+ * before branch to main program. This call is made inside
+ * the "startup_stm32f4xx.s" file.
+ *
+ * - SystemCoreClock variable: Contains the core clock (HCLK), it can be used
+ * by the user application to setup the SysTick
+ * timer or configure other parameters.
+ *
+ * - SystemCoreClockUpdate(): Updates the variable SystemCoreClock and must
+ * be called whenever the core clock is changed
+ * during program execution.
+ *
+ * 2. After each device reset the HSI (16 MHz) is used as system clock source.
+ * Then SystemInit() function is called, in "startup_stm32f4xx.s" file, to
+ * configure the system clock before to branch to main program.
+ *
+ * 3. If the system clock source selected by user fails to startup, the SystemInit()
+ * function will do nothing and HSI still used as system clock source. User can
+ * add some code to deal with this issue inside the SetSysClock() function.
+ *
+ * 4. The default value of HSE crystal is set to 25MHz, refer to "HSE_VALUE" define
+ * in "stm32f4xx.h" file. When HSE is used as system clock source, directly or
+ * through PLL, and you are using different crystal you have to adapt the HSE
+ * value to your own configuration.
+ *
+ * 5. This file configures the system clock as follows:
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F40xxx/41xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 168000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 10
+ *-----------------------------------------------------------------------------
+ * PLL_N | 420
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F42xxx/43xxx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F401xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 84000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 25000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 25
+ *-----------------------------------------------------------------------------
+ * PLL_N | 336
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 2
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F411xx/STM32F410xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSI)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 100000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * HSI Frequency(Hz) | 16000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 16
+ *-----------------------------------------------------------------------------
+ * PLL_N | 400
+ *-----------------------------------------------------------------------------
+ * PLL_P | 4
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 3
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ *=============================================================================
+ * Supported STM32F446xx devices
+ *-----------------------------------------------------------------------------
+ * System Clock source | PLL (HSE)
+ *-----------------------------------------------------------------------------
+ * SYSCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * HCLK(Hz) | 180000000
+ *-----------------------------------------------------------------------------
+ * AHB Prescaler | 1
+ *-----------------------------------------------------------------------------
+ * APB1 Prescaler | 4
+ *-----------------------------------------------------------------------------
+ * APB2 Prescaler | 2
+ *-----------------------------------------------------------------------------
+ * HSE Frequency(Hz) | 8000000
+ *-----------------------------------------------------------------------------
+ * PLL_M | 8
+ *-----------------------------------------------------------------------------
+ * PLL_N | 360
+ *-----------------------------------------------------------------------------
+ * PLL_P | 2
+ *-----------------------------------------------------------------------------
+ * PLL_Q | 7
+ *-----------------------------------------------------------------------------
+ * PLL_R | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_M | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_N | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_P | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_Q | NA
+ *-----------------------------------------------------------------------------
+ * PLLI2S_R | NA
+ *-----------------------------------------------------------------------------
+ * I2S input clock | NA
+ *-----------------------------------------------------------------------------
+ * VDD(V) | 3.3
+ *-----------------------------------------------------------------------------
+ * Main regulator output voltage | Scale1 mode
+ *-----------------------------------------------------------------------------
+ * Flash Latency(WS) | 5
+ *-----------------------------------------------------------------------------
+ * Prefetch Buffer | ON
+ *-----------------------------------------------------------------------------
+ * Instruction cache | ON
+ *-----------------------------------------------------------------------------
+ * Data cache | ON
+ *-----------------------------------------------------------------------------
+ * Require 48MHz for USB OTG FS, | Disabled
+ * SDIO and RNG clock |
+ *-----------------------------------------------------------------------------
+ *=============================================================================
+ ******************************************************************************
+ * @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.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Includes
+ * @{
+ */
+
+#include "stm32f4xx.h"
+
+uint32_t hse_value = HSE_VALUE;
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_TypesDefinitions
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Defines
+ * @{
+ */
+
+/************************* Miscellaneous Configuration ************************/
+/*!< Uncomment the following line if you need to use external SRAM or SDRAM mounted
+ on STM324xG_EVAL/STM324x7I_EVAL/STM324x9I_EVAL boards as data memory */
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSRAM */
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+/* #define DATA_IN_ExtSDRAM */
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+/*!< Uncomment the following line if you need to clock the STM32F410xx/STM32F411xE by HSE Bypass
+ through STLINK MCO pin of STM32F103 microcontroller. The frequency cannot be changed
+ and is fixed at 8 MHz.
+ Hardware configuration needed for Nucleo Board:
+ – SB54, SB55 OFF
+ – R35 removed
+ – SB16, SB50 ON */
+/* #define USE_HSE_BYPASS */
+
+#if defined(USE_HSE_BYPASS)
+#define HSE_BYPASS_INPUT_FREQUENCY 8000000
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F410xx || STM32F411xE */
+
+/*!< Uncomment the following line if you need to relocate your vector Table in
+ Internal SRAM. */
+/* #define VECT_TAB_SRAM */
+#define VECT_TAB_OFFSET 0x00 /*!< Vector Table base offset field.
+ This value must be a multiple of 0x200. */
+/******************************************************************************/
+
+/************************* PLL Parameters *************************************/
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N */
+ #define PLL_M 8
+#elif defined (STM32F446xx)
+ #define PLL_M 8
+#elif defined (STM32F410xx) || defined (STM32F411xE)
+ #if defined(USE_HSE_BYPASS)
+ #define PLL_M 8
+ #else /* !USE_HSE_BYPASS */
+ #define PLL_M 8
+ #endif /* USE_HSE_BYPASS */
+#else
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+
+/* USB OTG FS, SDIO and RNG Clock = PLL_VCO / PLLQ */
+#define PLL_Q 7
+
+#if defined(STM32F446xx)
+/* PLL division factor for I2S, SAI, SYSTEM and SPDIF: Clock = PLL_VCO / PLLR */
+#define PLL_R 7
+#endif /* STM32F446xx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+#define PLL_N 360
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined (STM32F40_41xxx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 2
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+#define PLL_N 336
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+#define PLL_N 400
+/* SYSCLK = PLL_VCO / PLL_P */
+#define PLL_P 4
+#endif /* STM32F410xx || STM32F411xE */
+
+/******************************************************************************/
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Variables
+ * @{
+ */
+
+#if defined(STM32F40_41xxx)
+ uint32_t SystemCoreClock = 168000000;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ uint32_t SystemCoreClock = 180000000;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ uint32_t SystemCoreClock = 84000000;
+#endif /* STM32F401xx */
+
+#if defined(STM32F410xx) || defined(STM32F411xE)
+ uint32_t SystemCoreClock = 100000000;
+#endif /* STM32F410xx || STM32F401xE */
+
+__I uint8_t AHBPrescTable[16] = {0, 0, 0, 0, 0, 0, 0, 0, 1, 2, 3, 4, 6, 7, 8, 9};
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_FunctionPrototypes
+ * @{
+ */
+
+void SetSysClock(void);
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+static void SystemInit_ExtMemCtl(void);
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Private_Functions
+ * @{
+ */
+
+/**
+ * @brief Setup the microcontroller system
+ * Initialize the Embedded Flash Interface, the PLL and update the
+ * SystemFrequency variable.
+ * @param None
+ * @retval None
+ */
+void SystemInit(void)
+{
+ /* FPU settings ------------------------------------------------------------*/
+ #if (__FPU_PRESENT == 1) && (__FPU_USED == 1)
+ SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); /* set CP10 and CP11 Full Access */
+ #endif
+ /* Reset the RCC clock configuration to the default reset state ------------*/
+ /* Set HSION bit */
+ RCC->CR |= (uint32_t)0x00000001;
+
+ /* Reset CFGR register */
+ RCC->CFGR = 0x00000000;
+
+ /* Reset HSEON, CSSON and PLLON bits */
+ RCC->CR &= (uint32_t)0xFEF6FFFF;
+
+ /* Reset PLLCFGR register */
+ RCC->PLLCFGR = 0x24003010;
+
+ /* Reset HSEBYP bit */
+ RCC->CR &= (uint32_t)0xFFFBFFFF;
+
+ /* Disable all interrupts */
+ RCC->CIR = 0x00000000;
+
+#if defined(DATA_IN_ExtSRAM) || defined(DATA_IN_ExtSDRAM)
+ SystemInit_ExtMemCtl();
+#endif /* DATA_IN_ExtSRAM || DATA_IN_ExtSDRAM */
+
+ /* Configure the System clock source, PLL Multiplier and Divider factors,
+ AHB/APBx prescalers and Flash settings ----------------------------------*/
+ SetSysClock();
+
+ /* Configure the Vector Table location add offset address ------------------*/
+#ifdef VECT_TAB_SRAM
+ SCB->VTOR = SRAM_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal SRAM */
+#else
+ SCB->VTOR = FLASH_BASE | VECT_TAB_OFFSET; /* Vector Table Relocation in Internal FLASH */
+#endif
+}
+
+/**
+ * @brief Update SystemCoreClock variable according to Clock Register Values.
+ * The SystemCoreClock variable contains the core clock (HCLK), it can
+ * be used by the user application to setup the SysTick timer or configure
+ * other parameters.
+ *
+ * @note Each time the core clock (HCLK) changes, this function must be called
+ * to update SystemCoreClock variable value. Otherwise, any configuration
+ * based on this variable will be incorrect.
+ *
+ * @note - The system frequency computed by this function is not the real
+ * frequency in the chip. It is calculated based on the predefined
+ * constant and the selected clock source:
+ *
+ * - If SYSCLK source is HSI, SystemCoreClock will contain the HSI_VALUE(*)
+ *
+ * - If SYSCLK source is HSE, SystemCoreClock will contain the HSE_VALUE(**)
+ *
+ * - If SYSCLK source is PLL, SystemCoreClock will contain the HSE_VALUE(**)
+ * or HSI_VALUE(*) multiplied/divided by the PLL factors.
+ *
+ * (*) HSI_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 16 MHz) but the real value may vary depending on the variations
+ * in voltage and temperature.
+ *
+ * (**) HSE_VALUE is a constant defined in stm32f4xx.h file (default value
+ * 25 MHz), user has to ensure that HSE_VALUE is same as the real
+ * frequency of the crystal used. Otherwise, this function may
+ * have wrong result.
+ *
+ * - The result of this function could be not correct when using fractional
+ * value for HSE crystal.
+ *
+ * @param None
+ * @retval None
+ */
+void SystemCoreClockUpdate(void)
+{
+ uint32_t tmp = 0, pllvco = 0, pllp = 2, pllsource = 0, pllm = 2;
+#if defined(STM32F446xx)
+ uint32_t pllr = 2;
+#endif /* STM32F446xx */
+ /* Get SYSCLK source -------------------------------------------------------*/
+ tmp = RCC->CFGR & RCC_CFGR_SWS;
+
+ switch (tmp)
+ {
+ case 0x00: /* HSI used as system clock source */
+ SystemCoreClock = HSI_VALUE;
+ break;
+ case 0x04: /* HSE used as system clock source */
+ SystemCoreClock = HSE_VALUE;
+ break;
+ case 0x08: /* PLL P used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_P
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_BYPASS_INPUT_FREQUENCY / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#else
+ if (pllsource == 0)
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F446xx || STM32F469_479xx */
+ pllp = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLP) >>16) + 1 ) *2;
+ SystemCoreClock = pllvco/pllp;
+ break;
+#if defined(STM32F446xx)
+ case 0x0C: /* PLL R used as system clock source */
+ /* PLL_VCO = (HSE_VALUE or HSI_VALUE / PLL_M) * PLL_N
+ SYSCLK = PLL_VCO / PLL_R
+ */
+ pllsource = (RCC->PLLCFGR & RCC_PLLCFGR_PLLSRC) >> 22;
+ pllm = RCC->PLLCFGR & RCC_PLLCFGR_PLLM;
+ if (pllsource != 0)
+ {
+ /* HSE used as PLL clock source */
+ pllvco = (HSE_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+ else
+ {
+ /* HSI used as PLL clock source */
+ pllvco = (HSI_VALUE / pllm) * ((RCC->PLLCFGR & RCC_PLLCFGR_PLLN) >> 6);
+ }
+
+ pllr = (((RCC->PLLCFGR & RCC_PLLCFGR_PLLR) >>28) + 1 ) *2;
+ SystemCoreClock = pllvco/pllr;
+ break;
+#endif /* STM32F446xx */
+ default:
+ SystemCoreClock = HSI_VALUE;
+ break;
+ }
+ /* Compute HCLK frequency --------------------------------------------------*/
+ /* Get HCLK prescaler */
+ tmp = AHBPrescTable[((RCC->CFGR & RCC_CFGR_HPRE) >> 4)];
+ /* HCLK frequency */
+ SystemCoreClock >>= tmp;
+}
+
+/**
+ * @brief Configures the System clock source, PLL Multiplier and Divider factors,
+ * AHB/APBx prescalers and Flash settings
+ * @Note This function should be called only once the RCC clock configuration
+ * is reset to the default reset state (done in SystemInit() function).
+ * @param None
+ * @retval None
+ */
+void SetSysClock(void)
+{
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F446xx)|| defined(STM32F469_479xx)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV2;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV4;
+#endif /* STM32F40_41xxx || STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F401xx)
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+#endif /* STM32F401xx */
+
+#if defined(STM32F40_41xxx) || defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F401xx) || defined(STM32F469_479xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+#endif /* STM32F40_41xxx || STM32F401xx || STM32F427_437x || STM32F429_439xx || STM32F469_479xx */
+
+#if defined(STM32F446xx)
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24) | (PLL_R << 28);
+#endif /* STM32F446xx */
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Enable the Over-drive to extend the clock frequency to 180 Mhz */
+ PWR->CR |= PWR_CR_ODEN;
+ while((PWR->CSR & PWR_CSR_ODRDY) == 0)
+ {
+ }
+ PWR->CR |= PWR_CR_ODSWEN;
+ while((PWR->CSR & PWR_CSR_ODSWRDY) == 0)
+ {
+ }
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F427_437x || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_5WS;
+#endif /* STM32F40_41xxx */
+
+#if defined(STM32F401xx)
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+#endif /* STM32F401xx */
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#elif defined(STM32F410xx) || defined(STM32F411xE)
+#if defined(USE_HSE_BYPASS)
+/******************************************************************************/
+/* PLL (clocked by HSE) used as System clock source */
+/******************************************************************************/
+ __IO uint32_t StartUpCounter = 0, HSEStatus = 0;
+
+ /* Enable HSE and HSE BYPASS */
+ RCC->CR |= ((uint32_t)RCC_CR_HSEON | RCC_CR_HSEBYP);
+
+ /* Wait till HSE is ready and if Time out is reached exit */
+ do
+ {
+ HSEStatus = RCC->CR & RCC_CR_HSERDY;
+ StartUpCounter++;
+ } while((HSEStatus == 0) && (StartUpCounter != HSE_STARTUP_TIMEOUT));
+
+ if ((RCC->CR & RCC_CR_HSERDY) != RESET)
+ {
+ HSEStatus = (uint32_t)0x01;
+ }
+ else
+ {
+ HSEStatus = (uint32_t)0x00;
+ }
+
+ if (HSEStatus == (uint32_t)0x01)
+ {
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) |
+ (RCC_PLLCFGR_PLLSRC_HSE) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+ }
+ else
+ { /* If HSE fails to start-up, the application will have wrong clock
+ configuration. User can add here some code to deal with this error */
+ }
+#else /* HSI will be used as PLL clock source */
+ /* Select regulator voltage output Scale 1 mode */
+ RCC->APB1ENR |= RCC_APB1ENR_PWREN;
+ PWR->CR |= PWR_CR_VOS;
+
+ /* HCLK = SYSCLK / 1*/
+ RCC->CFGR |= RCC_CFGR_HPRE_DIV1;
+
+ /* PCLK2 = HCLK / 2*/
+ RCC->CFGR |= RCC_CFGR_PPRE2_DIV1;
+
+ /* PCLK1 = HCLK / 4*/
+ RCC->CFGR |= RCC_CFGR_PPRE1_DIV2;
+
+ /* Configure the main PLL */
+ RCC->PLLCFGR = PLL_M | (PLL_N << 6) | (((PLL_P >> 1) -1) << 16) | (PLL_Q << 24);
+
+ /* Enable the main PLL */
+ RCC->CR |= RCC_CR_PLLON;
+
+ /* Wait till the main PLL is ready */
+ while((RCC->CR & RCC_CR_PLLRDY) == 0)
+ {
+ }
+
+ /* Configure Flash prefetch, Instruction cache, Data cache and wait state */
+ FLASH->ACR = FLASH_ACR_PRFTEN | FLASH_ACR_ICEN |FLASH_ACR_DCEN |FLASH_ACR_LATENCY_2WS;
+
+ /* Select the main PLL as system clock source */
+ RCC->CFGR &= (uint32_t)((uint32_t)~(RCC_CFGR_SW));
+ RCC->CFGR |= RCC_CFGR_SW_PLL;
+
+ /* Wait till the main PLL is used as system clock source */
+ while ((RCC->CFGR & (uint32_t)RCC_CFGR_SWS ) != RCC_CFGR_SWS_PLL);
+ {
+ }
+#endif /* USE_HSE_BYPASS */
+#endif /* STM32F40_41xxx || STM32F427_437xx || STM32F429_439xx || STM32F401xx || STM32F469_479xx */
+}
+
+/**
+ * @brief Setup the external memory controller. Called in startup_stm32f4xx.s
+ * before jump to __main
+ * @param None
+ * @retval None
+ */
+#ifdef DATA_IN_ExtSRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SRAM mounted on STM324xG_EVAL/STM324x7I boards
+ * This SRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+/*-- GPIOs Configuration -----------------------------------------------------*/
+/*
+ +-------------------+--------------------+------------------+--------------+
+ + SRAM pins assignment +
+ +-------------------+--------------------+------------------+--------------+
+ | PD0 <-> FMC_D2 | PE0 <-> FMC_NBL0 | PF0 <-> FMC_A0 | PG0 <-> FMC_A10 |
+ | PD1 <-> FMC_D3 | PE1 <-> FMC_NBL1 | PF1 <-> FMC_A1 | PG1 <-> FMC_A11 |
+ | PD4 <-> FMC_NOE | PE3 <-> FMC_A19 | PF2 <-> FMC_A2 | PG2 <-> FMC_A12 |
+ | PD5 <-> FMC_NWE | PE4 <-> FMC_A20 | PF3 <-> FMC_A3 | PG3 <-> FMC_A13 |
+ | PD8 <-> FMC_D13 | PE7 <-> FMC_D4 | PF4 <-> FMC_A4 | PG4 <-> FMC_A14 |
+ | PD9 <-> FMC_D14 | PE8 <-> FMC_D5 | PF5 <-> FMC_A5 | PG5 <-> FMC_A15 |
+ | PD10 <-> FMC_D15 | PE9 <-> FMC_D6 | PF12 <-> FMC_A6 | PG9 <-> FMC_NE2 |
+ | PD11 <-> FMC_A16 | PE10 <-> FMC_D7 | PF13 <-> FMC_A7 |-----------------+
+ | PD12 <-> FMC_A17 | PE11 <-> FMC_D8 | PF14 <-> FMC_A8 |
+ | PD13 <-> FMC_A18 | PE12 <-> FMC_D9 | PF15 <-> FMC_A9 |
+ | PD14 <-> FMC_D0 | PE13 <-> FMC_D10 |-----------------+
+ | PD15 <-> FMC_D1 | PE14 <-> FMC_D11 |
+ | | PE15 <-> FMC_D12 |
+ +------------------+------------------+
+*/
+ /* Enable GPIOD, GPIOE, GPIOF and GPIOG interface clock */
+ RCC->AHB1ENR |= 0x00000078;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x00cc00cc;
+ GPIOD->AFR[1] = 0xcccccccc;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xaaaa0a0a;
+ /* Configure PDx pins speed to 100 MHz */
+ GPIOD->OSPEEDR = 0xffff0f0f;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xcccccccc;
+ GPIOE->AFR[1] = 0xcccccccc;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xaaaaaaaa;
+ /* Configure PEx pins speed to 100 MHz */
+ GPIOE->OSPEEDR = 0xffffffff;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0x00cccccc;
+ GPIOF->AFR[1] = 0xcccc0000;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xaa000aaa;
+ /* Configure PFx pins speed to 100 MHz */
+ GPIOF->OSPEEDR = 0xff000fff;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0x00cccccc;
+ GPIOG->AFR[1] = 0x000000c0;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0x00080aaa;
+ /* Configure PGx pins speed to 100 MHz */
+ GPIOG->OSPEEDR = 0x000c0fff;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC/FSMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+#if defined(STM32F427_437xx) || defined(STM32F429_439xx) || defined(STM32F446xx) || defined(STM32F469_479xx)
+ /* Configure and enable Bank1_SRAM2 */
+ FMC_Bank1->BTCR[2] = 0x00001011;
+ FMC_Bank1->BTCR[3] = 0x00000201;
+ FMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F427_437xx || STM32F429_439xx || STM32F446xx || STM32F469_479xx */
+
+#if defined(STM32F40_41xxx)
+ /* Configure and enable Bank1_SRAM2 */
+ FSMC_Bank1->BTCR[2] = 0x00001011;
+ FSMC_Bank1->BTCR[3] = 0x00000201;
+ FSMC_Bank1E->BWTR[2] = 0x0fffffff;
+#endif /* STM32F40_41xxx */
+
+/*
+ Bank1_SRAM2 is configured as follow:
+ In case of FSMC configuration
+ NORSRAMTimingStructure.FSMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FSMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FSMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FSMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FSMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FSMC_DataLatency = 0;
+ NORSRAMTimingStructure.FSMC_AccessMode = FMC_AccessMode_A;
+
+ FSMC_NORSRAMInitStructure.FSMC_Bank = FSMC_Bank1_NORSRAM2;
+ FSMC_NORSRAMInitStructure.FSMC_DataAddressMux = FSMC_DataAddressMux_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryType = FSMC_MemoryType_SRAM;
+ FSMC_NORSRAMInitStructure.FSMC_MemoryDataWidth = FSMC_MemoryDataWidth_16b;
+ FSMC_NORSRAMInitStructure.FSMC_BurstAccessMode = FSMC_BurstAccessMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_AsynchronousWait = FSMC_AsynchronousWait_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalPolarity = FSMC_WaitSignalPolarity_Low;
+ FSMC_NORSRAMInitStructure.FSMC_WrapMode = FSMC_WrapMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignalActive = FSMC_WaitSignalActive_BeforeWaitState;
+ FSMC_NORSRAMInitStructure.FSMC_WriteOperation = FSMC_WriteOperation_Enable;
+ FSMC_NORSRAMInitStructure.FSMC_WaitSignal = FSMC_WaitSignal_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ExtendedMode = FSMC_ExtendedMode_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_WriteBurst = FSMC_WriteBurst_Disable;
+ FSMC_NORSRAMInitStructure.FSMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FSMC_NORSRAMInitStructure.FSMC_WriteTimingStruct = &NORSRAMTimingStructure;
+
+ In case of FMC configuration
+ NORSRAMTimingStructure.FMC_AddressSetupTime = 1;
+ NORSRAMTimingStructure.FMC_AddressHoldTime = 0;
+ NORSRAMTimingStructure.FMC_DataSetupTime = 2;
+ NORSRAMTimingStructure.FMC_BusTurnAroundDuration = 0;
+ NORSRAMTimingStructure.FMC_CLKDivision = 0;
+ NORSRAMTimingStructure.FMC_DataLatency = 0;
+ NORSRAMTimingStructure.FMC_AccessMode = FMC_AccessMode_A;
+
+ FMC_NORSRAMInitStructure.FMC_Bank = FMC_Bank1_NORSRAM2;
+ FMC_NORSRAMInitStructure.FMC_DataAddressMux = FMC_DataAddressMux_Disable;
+ FMC_NORSRAMInitStructure.FMC_MemoryType = FMC_MemoryType_SRAM;
+ FMC_NORSRAMInitStructure.FMC_MemoryDataWidth = FMC_MemoryDataWidth_16b;
+ FMC_NORSRAMInitStructure.FMC_BurstAccessMode = FMC_BurstAccessMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_AsynchronousWait = FMC_AsynchronousWait_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalPolarity = FMC_WaitSignalPolarity_Low;
+ FMC_NORSRAMInitStructure.FMC_WrapMode = FMC_WrapMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignalActive = FMC_WaitSignalActive_BeforeWaitState;
+ FMC_NORSRAMInitStructure.FMC_WriteOperation = FMC_WriteOperation_Enable;
+ FMC_NORSRAMInitStructure.FMC_WaitSignal = FMC_WaitSignal_Disable;
+ FMC_NORSRAMInitStructure.FMC_ExtendedMode = FMC_ExtendedMode_Disable;
+ FMC_NORSRAMInitStructure.FMC_WriteBurst = FMC_WriteBurst_Disable;
+ FMC_NORSRAMInitStructure.FMC_ContinousClock = FMC_CClock_SyncOnly;
+ FMC_NORSRAMInitStructure.FMC_ReadWriteTimingStruct = &NORSRAMTimingStructure;
+ FMC_NORSRAMInitStructure.FMC_WriteTimingStruct = &NORSRAMTimingStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSRAM */
+
+#ifdef DATA_IN_ExtSDRAM
+/**
+ * @brief Setup the external memory controller.
+ * Called in startup_stm32f4xx.s before jump to main.
+ * This function configures the external SDRAM mounted on STM324x9I_EVAL board
+ * This SDRAM will be used as program data memory (including heap and stack).
+ * @param None
+ * @retval None
+ */
+void SystemInit_ExtMemCtl(void)
+{
+ register uint32_t tmpreg = 0, timeout = 0xFFFF;
+ register uint32_t index;
+
+ /* Enable GPIOC, GPIOD, GPIOE, GPIOF, GPIOG, GPIOH and GPIOI interface
+ clock */
+ RCC->AHB1ENR |= 0x000001FC;
+
+ /* Connect PCx pins to FMC Alternate function */
+ GPIOC->AFR[0] = 0x0000000c;
+ GPIOC->AFR[1] = 0x00007700;
+ /* Configure PCx pins in Alternate function mode */
+ GPIOC->MODER = 0x00a00002;
+ /* Configure PCx pins speed to 50 MHz */
+ GPIOC->OSPEEDR = 0x00a00002;
+ /* Configure PCx pins Output type to push-pull */
+ GPIOC->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PCx pins */
+ GPIOC->PUPDR = 0x00500000;
+
+ /* Connect PDx pins to FMC Alternate function */
+ GPIOD->AFR[0] = 0x000000CC;
+ GPIOD->AFR[1] = 0xCC000CCC;
+ /* Configure PDx pins in Alternate function mode */
+ GPIOD->MODER = 0xA02A000A;
+ /* Configure PDx pins speed to 50 MHz */
+ GPIOD->OSPEEDR = 0xA02A000A;
+ /* Configure PDx pins Output type to push-pull */
+ GPIOD->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PDx pins */
+ GPIOD->PUPDR = 0x00000000;
+
+ /* Connect PEx pins to FMC Alternate function */
+ GPIOE->AFR[0] = 0xC00000CC;
+ GPIOE->AFR[1] = 0xCCCCCCCC;
+ /* Configure PEx pins in Alternate function mode */
+ GPIOE->MODER = 0xAAAA800A;
+ /* Configure PEx pins speed to 50 MHz */
+ GPIOE->OSPEEDR = 0xAAAA800A;
+ /* Configure PEx pins Output type to push-pull */
+ GPIOE->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PEx pins */
+ GPIOE->PUPDR = 0x00000000;
+
+ /* Connect PFx pins to FMC Alternate function */
+ GPIOF->AFR[0] = 0xcccccccc;
+ GPIOF->AFR[1] = 0xcccccccc;
+ /* Configure PFx pins in Alternate function mode */
+ GPIOF->MODER = 0xAA800AAA;
+ /* Configure PFx pins speed to 50 MHz */
+ GPIOF->OSPEEDR = 0xAA800AAA;
+ /* Configure PFx pins Output type to push-pull */
+ GPIOF->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PFx pins */
+ GPIOF->PUPDR = 0x00000000;
+
+ /* Connect PGx pins to FMC Alternate function */
+ GPIOG->AFR[0] = 0xcccccccc;
+ GPIOG->AFR[1] = 0xcccccccc;
+ /* Configure PGx pins in Alternate function mode */
+ GPIOG->MODER = 0xaaaaaaaa;
+ /* Configure PGx pins speed to 50 MHz */
+ GPIOG->OSPEEDR = 0xaaaaaaaa;
+ /* Configure PGx pins Output type to push-pull */
+ GPIOG->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PGx pins */
+ GPIOG->PUPDR = 0x00000000;
+
+ /* Connect PHx pins to FMC Alternate function */
+ GPIOH->AFR[0] = 0x00C0CC00;
+ GPIOH->AFR[1] = 0xCCCCCCCC;
+ /* Configure PHx pins in Alternate function mode */
+ GPIOH->MODER = 0xAAAA08A0;
+ /* Configure PHx pins speed to 50 MHz */
+ GPIOH->OSPEEDR = 0xAAAA08A0;
+ /* Configure PHx pins Output type to push-pull */
+ GPIOH->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PHx pins */
+ GPIOH->PUPDR = 0x00000000;
+
+ /* Connect PIx pins to FMC Alternate function */
+ GPIOI->AFR[0] = 0xCCCCCCCC;
+ GPIOI->AFR[1] = 0x00000CC0;
+ /* Configure PIx pins in Alternate function mode */
+ GPIOI->MODER = 0x0028AAAA;
+ /* Configure PIx pins speed to 50 MHz */
+ GPIOI->OSPEEDR = 0x0028AAAA;
+ /* Configure PIx pins Output type to push-pull */
+ GPIOI->OTYPER = 0x00000000;
+ /* No pull-up, pull-down for PIx pins */
+ GPIOI->PUPDR = 0x00000000;
+
+/*-- FMC Configuration ------------------------------------------------------*/
+ /* Enable the FMC interface clock */
+ RCC->AHB3ENR |= 0x00000001;
+
+ /* Configure and enable SDRAM bank1 */
+ FMC_Bank5_6->SDCR[0] = 0x000039D0;
+ FMC_Bank5_6->SDTR[0] = 0x01115351;
+
+ /* SDRAM initialization sequence */
+ /* Clock enable command */
+ FMC_Bank5_6->SDCMR = 0x00000011;
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Delay */
+ for (index = 0; index<1000; index++);
+
+ /* PALL command */
+ FMC_Bank5_6->SDCMR = 0x00000012;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Auto refresh command */
+ FMC_Bank5_6->SDCMR = 0x00000073;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* MRD register program */
+ FMC_Bank5_6->SDCMR = 0x00046014;
+ timeout = 0xFFFF;
+ while((tmpreg != 0) & (timeout-- > 0))
+ {
+ tmpreg = FMC_Bank5_6->SDSR & 0x00000020;
+ }
+
+ /* Set refresh count */
+ tmpreg = FMC_Bank5_6->SDRTR;
+ FMC_Bank5_6->SDRTR = (tmpreg | (0x0000027C<<1));
+
+ /* Disable write protection */
+ tmpreg = FMC_Bank5_6->SDCR[0];
+ FMC_Bank5_6->SDCR[0] = (tmpreg & 0xFFFFFDFF);
+
+/*
+ Bank1_SDRAM is configured as follow:
+
+ FMC_SDRAMTimingInitStructure.FMC_LoadToActiveDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_ExitSelfRefreshDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_SelfRefreshTime = 4;
+ FMC_SDRAMTimingInitStructure.FMC_RowCycleDelay = 6;
+ FMC_SDRAMTimingInitStructure.FMC_WriteRecoveryTime = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RPDelay = 2;
+ FMC_SDRAMTimingInitStructure.FMC_RCDDelay = 2;
+
+ FMC_SDRAMInitStructure.FMC_Bank = SDRAM_BANK;
+ FMC_SDRAMInitStructure.FMC_ColumnBitsNumber = FMC_ColumnBits_Number_8b;
+ FMC_SDRAMInitStructure.FMC_RowBitsNumber = FMC_RowBits_Number_11b;
+ FMC_SDRAMInitStructure.FMC_SDMemoryDataWidth = FMC_SDMemory_Width_16b;
+ FMC_SDRAMInitStructure.FMC_InternalBankNumber = FMC_InternalBank_Number_4;
+ FMC_SDRAMInitStructure.FMC_CASLatency = FMC_CAS_Latency_3;
+ FMC_SDRAMInitStructure.FMC_WriteProtection = FMC_Write_Protection_Disable;
+ FMC_SDRAMInitStructure.FMC_SDClockPeriod = FMC_SDClock_Period_2;
+ FMC_SDRAMInitStructure.FMC_ReadBurst = FMC_Read_Burst_disable;
+ FMC_SDRAMInitStructure.FMC_ReadPipeDelay = FMC_ReadPipe_Delay_1;
+ FMC_SDRAMInitStructure.FMC_SDRAMTimingStruct = &FMC_SDRAMTimingInitStructure;
+*/
+
+}
+#endif /* DATA_IN_ExtSDRAM */
+
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/AQ32_V2/system_stm32f4xx.h b/src/main/target/AQ32_V2/system_stm32f4xx.h
new file mode 100644
index 000000000..5e30ef818
--- /dev/null
+++ b/src/main/target/AQ32_V2/system_stm32f4xx.h
@@ -0,0 +1,105 @@
+/**
+ ******************************************************************************
+ * @file system_stm32f4xx.h
+ * @author MCD Application Team
+ * @version V1.6.1
+ * @date 21-October-2015
+ * @brief CMSIS Cortex-M4 Device System Source File for STM32F4xx devices.
+ ******************************************************************************
+ * @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.
+ *
+ ******************************************************************************
+ */
+
+/** @addtogroup CMSIS
+ * @{
+ */
+
+/** @addtogroup stm32f4xx_system
+ * @{
+ */
+
+/**
+ * @brief Define to prevent recursive inclusion
+ */
+#ifndef __SYSTEM_STM32F4XX_H
+#define __SYSTEM_STM32F4XX_H
+
+#ifdef __cplusplus
+ extern "C" {
+#endif
+
+/** @addtogroup STM32F4xx_System_Includes
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+
+/** @addtogroup STM32F4xx_System_Exported_types
+ * @{
+ */
+
+extern uint32_t SystemCoreClock; /*!< System Clock Frequency (Core Clock) */
+
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Constants
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Macros
+ * @{
+ */
+
+/**
+ * @}
+ */
+
+/** @addtogroup STM32F4xx_System_Exported_Functions
+ * @{
+ */
+
+extern void SystemInit(void);
+extern void SystemCoreClockUpdate(void);
+/**
+ * @}
+ */
+
+#ifdef __cplusplus
+}
+#endif
+
+#endif /*__SYSTEM_STM32F4XX_H */
+
+/**
+ * @}
+ */
+
+/**
+ * @}
+ */
+/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/target/AQ32_V2/target.h b/src/main/target/AQ32_V2/target.h
new file mode 100644
index 000000000..70efdf6dd
--- /dev/null
+++ b/src/main/target/AQ32_V2/target.h
@@ -0,0 +1,204 @@
+/*
+ * This file is part of Cleanflight.
+ *
+ * Cleanflight is free software: you can redistribute it and/or modify
+ * it under the terms of the GNU General Public License as published by
+ * the Free Software Foundation, either version 3 of the License, or
+ * (at your option) any later version.
+ *
+ * Cleanflight is distributed in the hope that it will be useful,
+ * but WITHOUT ANY WARRANTY; without even the implied warranty of
+ * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
+ * GNU General Public License for more details.
+ *
+ * You should have received a copy of the GNU General Public License
+ * along with Cleanflight. If not, see .
+ */
+
+#pragma once
+#define TARGET_BOARD_IDENTIFIER "AQ32"
+
+#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8)
+#define CONFIG_SERIALRX_PROVIDER SERIALRX_SBUS
+//#define CONFIG_BLACKBOX_DEVICE BLACKBOX_DEVICE_SDCARD
+#define CONFIG_FEATURE_RX_SERIAL
+#define CONFIG_RX_SERIAL_PORT 2
+#define CONFIG_FEATURE_ONESHOT125
+#define CONFIG_MSP_PORT 1
+
+#define USBD_PRODUCT_STRING "AeroQuad32 V2"
+
+#define LED0 PE5
+#define LED0_INVERTED
+#define LED1 PE6
+#define LED1_INVERTED
+#define LED2 PD7 // LED2 external with transistor driver
+
+#define BEEPER PE0 // LED1 external with transistor driver
+
+#define INVERTER PB12
+#define INVERTER_USART USART3
+
+#define MPU6000_CS_PIN PB8
+#define MPU6000_SPI_INSTANCE SPI3
+
+#define ACC
+#define USE_ACC_MPU6000
+#define USE_ACC_SPI_MPU6000
+//#define ACC_MPU6000_ALIGN CW0_DEG
+
+#define GYRO
+#define USE_GYRO_MPU6000
+#define USE_GYRO_SPI_MPU6000
+//#define GYRO_MPU6000_ALIGN CW0_DEG
+
+#define MAG
+#define USE_MAG_HMC5883
+#define MAG_HMC5883_ALIGN CW90_DEG
+
+#define BARO
+#define USE_BARO_MS5611
+#define MS5611_ADDR 0x76
+
+#define USE_SDCARD
+
+//#define SDCARD_DETECT_INVERTED
+
+#define SDCARD_DETECT_PIN PC1
+//#define SDCARD_DETECT_EXTI_LINE EXTI_Line1
+//#define SDCARD_DETECT_EXTI_PIN_SOURCE EXTI_PinSource1
+//#define SDCARD_DETECT_EXTI_PORT_SOURCE EXTI_PortSourceGPIOC
+//#define SDCARD_DETECT_EXTI_IRQn EXTI2_IRQn
+
+#define SDCARD_SPI_INSTANCE SPI1
+#define SDCARD_SPI_CS_PIN PE10
+
+// SPI2 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init:
+#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz
+// Divide to under 25MHz for normal operation:
+#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz
+
+#define SDCARD_DMA_CHANNEL_TX DMA2_Stream5
+#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5
+#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA2
+#define SDCARD_DMA_CHANNEL DMA_Channel_3
+
+// Performance logging for SD card operations:
+// #define AFATFS_USE_INTROSPECTIVE_LOGGING
+
+#define USABLE_TIMER_CHANNEL_COUNT 20
+
+#define USE_EXTI
+#define EXTI_CALLBACK_HANDLER_COUNT 2 // MPU data ready
+// MPU6000 interrupt
+#define USE_MPU_DATA_READY_SIGNAL
+#define ENSURE_MPU_DATA_READY_IS_LOW
+#define MPU_INT_EXTI PE4
+// HMC5883 interrupt
+#define USE_MAG_DATA_READY_SIGNAL
+#define ENSURE_MAG_DATA_READY_IS_HIGH
+
+#define USE_VCP
+
+#define USE_USART1
+#define USART1_RX_PIN PA10
+#define USART1_TX_PIN PA9
+#define USART1_AHB1_PERIPHERALS RCC_AHB1Periph_DMA2
+
+#define USE_USART2
+#define USART2_RX_PIN PD6
+#define USART2_TX_PIN PD5
+
+#define USE_USART3
+#define USART3_RX_PIN PD9 //inverter
+#define USART3_TX_PIN PD8 //inverter
+
+#define SERIAL_PORT_COUNT 4
+
+#define USE_SPI
+
+#define USE_SPI_DEVICE_1
+#define SPI1_NSS_PIN PE10
+#define SPI1_SCK_PIN PA5
+#define SPI1_MISO_PIN PA6
+#define SPI1_MOSI_PIN PA7
+
+#define USE_SPI_DEVICE_2
+#define SPI2_NSS_PIN PA3
+#define SPI2_SCK_PIN PB13
+#define SPI2_MISO_PIN PB14
+#define SPI2_MOSI_PIN PB15
+
+#define USE_SPI_DEVICE_3
+#define SPI3_NSS_PIN PB8
+#define SPI3_SCK_PIN PC10
+#define SPI3_MISO_PIN PC11
+#define SPI3_MOSI_PIN PC12
+
+#define USE_I2C
+
+#define I2C_DEVICE (I2CDEV_1)
+#define I2C1_SCL PB6
+#define I2C1_SDA PB7
+
+#define I2C_DEVICE_EXT (I2CDEV_2)
+#define I2C2_SCL PB10
+#define I2C2_SDA PB11
+
+#define USE_ADC
+
+#define VBAT_ADC_PIN PC0
+#define VBAT_ADC_CHANNEL ADC_Channel_10
+
+#define CURRENT_METER_ADC_PIN PC4
+#define CURRENT_METER_ADC_CHANNEL ADC_Channel_14
+
+#define RSSI_ADC_PIN PB1
+#define RSSI_ADC_CHANNEL ADC_Channel_9
+
+#define EXTERNAL1_ADC_GPIO_PIN PC5
+#define EXTERNAL1_ADC_CHANNEL ADC_Channel_15
+
+// LED strip configuration using SVR3 pin.
+//#define LED_STRIP
+//#define LED_STRIP_TIMER TIM5
+
+//#define USE_LED_STRIP_ON_DMA1_CHANNEL3
+//#define WS2811_GPIO GPIOA
+//#define WS2811_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA
+//#define WS2811_GPIO_AF GPIO_AF_3
+//#define WS2811_PIN GPIO_Pin_0 // TIM5_CH1
+//#define WS2811_PIN_SOURCE GPIO_PinSource0
+//#define WS2811_TIMER TIM5
+//#define WS2811_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM5
+//#define WS2811_DMA_CHANNEL DMA1_Channel3
+//#define WS2811_IRQ DMA1_Channel3_IRQn
+
+#define BLACKBOX
+//#define DISPLAY
+#define GPS
+#define GTUNE
+#define SERIAL_RX
+#define TELEMETRY
+#define USE_SERVOS
+#define USE_CLI
+
+#define SPEKTRUM_BIND
+// USART2, PD6
+#define BIND_PORT GPIOD
+#define BIND_PIN Pin_6
+
+#define USE_SERIAL_1WIRE
+#define ESC_COUNT 8
+#define S1W_TX_GPIO GPIOA
+#define S1W_TX_PIN GPIO_Pin_9
+#define S1W_RX_GPIO GPIOA
+#define S1W_RX_PIN GPIO_Pin_10
+
+#define USE_QUATERNION
+
+#define TARGET_IO_PORTA 0xffff
+#define TARGET_IO_PORTB 0xffff
+#define TARGET_IO_PORTC 0xffff
+#define TARGET_IO_PORTD 0xffff
+#define TARGET_IO_PORTE 0xffff
diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h
index 6b80b1bbc..d9cc8c437 100644
--- a/src/main/target/NAZE/target.h
+++ b/src/main/target/NAZE/target.h
@@ -173,10 +173,10 @@
#define S1W_RX_GPIO GPIOA
#define S1W_RX_PIN GPIO_Pin_10
-// alternative defaults for AlienWii32 F1 target
-#ifdef ALIENWII32
+// alternative defaults for ALIENFLIGHT F1 target
+#ifdef ALIENFLIGHT
#undef TARGET_BOARD_IDENTIFIER
-#define TARGET_BOARD_IDENTIFIER "AWF1" // AlienWii32 F1.
+#define TARGET_BOARD_IDENTIFIER "AFF1" // ALIENFLIGHTF1.
#undef BOARD_HAS_VOLTAGE_DIVIDER
#define HARDWARE_BIND_PLUG
diff --git a/src/main/vcp/usb_conf.h b/src/main/vcp/usb_conf.h
index 5d25d8919..6b322297e 100644
--- a/src/main/vcp/usb_conf.h
+++ b/src/main/vcp/usb_conf.h
@@ -67,9 +67,11 @@
/* IMR_MSK */
/* mask defining which events has to be handled */
/* by the device application software */
-// HJI #define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM | CNTR_ESOFM | CNTR_RESETM )
-// Disable Suspend/Resume response completely // HJI
-#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_ERRM | CNTR_SOFM | CNTR_RESETM ) // HJI
+// #define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SUSPM | CNTR_ERRM | CNTR_SOFM | CNTR_ESOFM | CNTR_RESETM )
+// Disable Suspend/Resume response completely
+// #define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_ERRM | CNTR_SOFM | CNTR_RESETM )
+// Disable Error interrupt which wasn't really used anyway
+#define IMR_MSK (CNTR_CTRM | CNTR_WKUPM | CNTR_SOFM | CNTR_RESETM )
/*#define CTR_CALLBACK*/
/*#define DOVR_CALLBACK*/
@@ -97,8 +99,6 @@
#define EP6_OUT_Callback NOP_Process
#define EP7_OUT_Callback NOP_Process
-#define USB_MAX_STR_DESC_SIZ 50
-
#endif /* __USB_CONF_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/vcp/usb_desc.c b/src/main/vcp/usb_desc.c
index 832d31b74..64ead56f6 100644
--- a/src/main/vcp/usb_desc.c
+++ b/src/main/vcp/usb_desc.c
@@ -123,4 +123,27 @@ VIRTUAL_COM_PORT_DATA_SIZE, /* wMaxPacketSize: */
0x00, 0x00 /* bInterval */
};
+/* USB String Descriptors */
+const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID] = {
+VIRTUAL_COM_PORT_SIZ_STRING_LANGID,
+USB_STRING_DESCRIPTOR_TYPE, 0x09, 0x04 /* LangID = 0x0409: U.S. English */
+};
+
+const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR] = {
+VIRTUAL_COM_PORT_SIZ_STRING_VENDOR, /* Size of Vendor string */
+USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType*/
+/* Manufacturer: "STMicroelectronics" */
+'S', 0, 'T', 0, 'M', 0, 'i', 0, 'c', 0, 'r', 0, 'o', 0, 'e', 0, 'l', 0, 'e', 0, 'c', 0, 't', 0, 'r', 0, 'o', 0, 'n', 0, 'i', 0, 'c', 0, 's', 0 };
+
+const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT] = {
+VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT, /* bLength */
+USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
+/* Product name: "STM32 Virtual COM Port" */
+'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0, ' ', 0, 'V', 0, 'i', 0, 'r', 0, 't', 0, 'u', 0, 'a', 0, 'l', 0, ' ', 0, 'C', 0, 'O', 0, 'M', 0, ' ', 0, 'P', 0, 'o', 0, 'r', 0, 't', 0, ' ', 0, ' ', 0 };
+
+uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL] = {
+VIRTUAL_COM_PORT_SIZ_STRING_SERIAL, /* bLength */
+USB_STRING_DESCRIPTOR_TYPE, /* bDescriptorType */
+'S', 0, 'T', 0, 'M', 0, '3', 0, '2', 0 };
+
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/vcp/usb_desc.h b/src/main/vcp/usb_desc.h
index 2bcfce6d3..92f38341a 100644
--- a/src/main/vcp/usb_desc.h
+++ b/src/main/vcp/usb_desc.h
@@ -30,8 +30,6 @@
#define __USB_DESC_H
/* Includes ------------------------------------------------------------------*/
-#include "platform.h"
-
/* Exported types ------------------------------------------------------------*/
/* Exported constants --------------------------------------------------------*/
/* Exported macro ------------------------------------------------------------*/
@@ -47,6 +45,10 @@
#define VIRTUAL_COM_PORT_SIZ_DEVICE_DESC 18
#define VIRTUAL_COM_PORT_SIZ_CONFIG_DESC 67
+#define VIRTUAL_COM_PORT_SIZ_STRING_LANGID 4
+#define VIRTUAL_COM_PORT_SIZ_STRING_VENDOR 38
+#define VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT 50
+#define VIRTUAL_COM_PORT_SIZ_STRING_SERIAL 26
#define STANDARD_ENDPOINT_DESC_SIZE 0x09
@@ -54,17 +56,10 @@
extern const uint8_t Virtual_Com_Port_DeviceDescriptor[VIRTUAL_COM_PORT_SIZ_DEVICE_DESC];
extern const uint8_t Virtual_Com_Port_ConfigDescriptor[VIRTUAL_COM_PORT_SIZ_CONFIG_DESC];
-
-#define USBD_MANUFACTURER_STRING "RaceFlight"
-
-#ifndef USBD_PRODUCT_STRING
- #define USBD_PRODUCT_STRING "STM32 Virtual ComPort"
-#endif /* USBD_PRODUCT_STRING */
-
-#ifndef USBD_SERIALNUMBER_STRING
- // start of STM32 flash
- #define USBD_SERIALNUMBER_STRING "0x8000000"
-#endif /* USBD_SERIALNUMBER_STRING */
+extern const uint8_t Virtual_Com_Port_StringLangID[VIRTUAL_COM_PORT_SIZ_STRING_LANGID];
+extern const uint8_t Virtual_Com_Port_StringVendor[VIRTUAL_COM_PORT_SIZ_STRING_VENDOR];
+extern const uint8_t Virtual_Com_Port_StringProduct[VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT];
+extern uint8_t Virtual_Com_Port_StringSerial[VIRTUAL_COM_PORT_SIZ_STRING_SERIAL];
#endif /* __USB_DESC_H */
/************************ (C) COPYRIGHT STMicroelectronics *****END OF FILE****/
diff --git a/src/main/vcp/usb_prop.c b/src/main/vcp/usb_prop.c
index 05820462f..b070ce9cc 100644
--- a/src/main/vcp/usb_prop.c
+++ b/src/main/vcp/usb_prop.c
@@ -45,9 +45,6 @@ LINE_CODING linecoding = { 115200, /* baud rate*/
0x08 /* no. of bits 8*/
};
-static uint8_t UsbStringBuf[USB_MAX_STR_DESC_SIZ];
-static ONE_DESCRIPTOR UsbStringDesc;
-
/* -------------------------------------------------------------------------- */
/* Structures initializations */
/* -------------------------------------------------------------------------- */
@@ -74,6 +71,9 @@ VIRTUAL_COM_PORT_SIZ_DEVICE_DESC };
ONE_DESCRIPTOR Config_Descriptor = { (uint8_t*)Virtual_Com_Port_ConfigDescriptor,
VIRTUAL_COM_PORT_SIZ_CONFIG_DESC };
+ONE_DESCRIPTOR String_Descriptor[4] = { { (uint8_t*)Virtual_Com_Port_StringLangID, VIRTUAL_COM_PORT_SIZ_STRING_LANGID }, { (uint8_t*)Virtual_Com_Port_StringVendor, VIRTUAL_COM_PORT_SIZ_STRING_VENDOR }, { (uint8_t*)Virtual_Com_Port_StringProduct,
+ VIRTUAL_COM_PORT_SIZ_STRING_PRODUCT }, { (uint8_t*)Virtual_Com_Port_StringSerial, VIRTUAL_COM_PORT_SIZ_STRING_SERIAL } };
+
/* Extern variables ----------------------------------------------------------*/
/* Private function prototypes -----------------------------------------------*/
/* Extern function prototypes ------------------------------------------------*/
@@ -290,36 +290,6 @@ uint8_t *Virtual_Com_Port_GetConfigDescriptor(uint16_t Length)
return Standard_GetDescriptorData(Length, &Config_Descriptor);
}
-static uint16_t Virtual_Com_Port_GetStringLength(const uint8_t *buf)
-{
- uint8_t len = 0;
-
- while (*buf != 0) {
- len++;
- buf++;
- }
-
- return len;
-}
-
-static uint8_t *Virtual_Com_Port_GetString(const uint8_t *str, uint8_t *buf, uint16_t *len)
-{
- uint8_t idx = 0;
-
- if (str != NULL) {
- *len = Virtual_Com_Port_GetStringLength(str) * 2 + 2;
- buf[idx++] = *len;
- buf[idx++] = USB_STRING_DESCRIPTOR_TYPE;
-
- while (*str != 0) {
- buf[idx++] = *str++;
- buf[idx++] = 0x00;
- }
- }
-
- return buf;
-}
-
/*******************************************************************************
* Function Name : Virtual_Com_Port_GetStringDescriptor
* Description : Gets the string descriptors according to the needed index
@@ -330,32 +300,11 @@ static uint8_t *Virtual_Com_Port_GetString(const uint8_t *str, uint8_t *buf, uin
uint8_t *Virtual_Com_Port_GetStringDescriptor(uint16_t Length)
{
uint8_t wValue0 = pInformation->USBwValue0;
- uint16_t descLength = 0;
-
- switch (wValue0) {
- case 0:
- UsbStringBuf[0] = 4;
- UsbStringBuf[1] = USB_STRING_DESCRIPTOR_TYPE;
- UsbStringBuf[2] = 0x09;
- UsbStringBuf[3] = 0x04;
- descLength = 4;
- break;
- case 1:
- Virtual_Com_Port_GetString((uint8_t *)USBD_MANUFACTURER_STRING, UsbStringBuf, &descLength);
- break;
- case 2:
- Virtual_Com_Port_GetString((uint8_t *)USBD_PRODUCT_STRING, UsbStringBuf, &descLength);
- break;
- case 3:
- Virtual_Com_Port_GetString((uint8_t *)USBD_SERIALNUMBER_STRING, UsbStringBuf, &descLength);
- break;
- default:
+ if (wValue0 > 4) {
return NULL;
+ } else {
+ return Standard_GetDescriptorData(Length, &String_Descriptor[wValue0]);
}
-
- UsbStringDesc.Descriptor_Size = descLength;
- UsbStringDesc.Descriptor = UsbStringBuf;
- return Standard_GetDescriptorData(Length, &UsbStringDesc);
}
/*******************************************************************************