mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-19 14:25:20 +03:00
Merge pull request #485 from martinbudden/bf_makefile2
Further tidying of makefile
This commit is contained in:
commit
3fafb0c55c
6 changed files with 335 additions and 114 deletions
209
Makefile
209
Makefile
|
@ -44,40 +44,35 @@ FLASH_SIZE ?=
|
|||
FORKNAME = betaflight
|
||||
|
||||
CC3D_TARGETS = CC3D CC3D_OPBL
|
||||
NAZE_TARGETS = ALIENFLIGHTF1 AFROMMINI
|
||||
SDCARD_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 SPRACINGF3MINI AQ32_V2 FURYF4 FURYF3
|
||||
SPRACINGF3_TARGETS = RMDO IRCFUSIONF3
|
||||
SERIAL_USB_TARGETS = SPRACINGF3 IRCFUSIONF3
|
||||
NAZE_TARGETS = AFROMINI ALIENFLIGHTF1
|
||||
SPRACINGF3_TARGETS = IRCFUSIONF3 RMDO
|
||||
|
||||
SDCARD_TARGETS = ALIENFLIGHTF4 AQ32_V2 BLUEJAYF4 FURYF3 FURYF4 SPRACINGF3MINI
|
||||
SERIAL_USB_TARGETS = IRCFUSIONF3 SPRACINGF3
|
||||
|
||||
# Valid targets for STM VCP support
|
||||
VCP_VALID_TARGETS = FURYF4 FURYF3 REVO BLUEJAYF4 $(CC3D_TARGETS)
|
||||
VCP_TARGETS = $(CC3D_TARGETS) BLUEJAYF4 FURYF3 FURYF4 REVO
|
||||
|
||||
F405_TARGETS = REVO ALIENFLIGHTF4 BLUEJAYF4 FURYF4
|
||||
F405_TARGETS_16 =
|
||||
F411_TARGETS =
|
||||
# Valid targets for OP BootLoader support
|
||||
OPBL_TARGETS = CC3D_OPBL
|
||||
|
||||
F1_TARGETS = NAZE OLIMEXINO $(CC3D_TARGETS) PORT103R ALIENFLIGHTF1 AFROMINI
|
||||
F3_TARGETS = STM32F3DISCOVERY CHEBUZZF3 NAZE32PRO SPRACINGF3 IRCFUSIONF3 SPARKY ALIENFLIGHTF3 COLIBRI_RACE LUX_RACE MOTOLAB RMDO SPRACINGF3MINI SPRACINGF3EVO DOGE SINGULARITY FURYF3
|
||||
|
||||
F405_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 FURYF4 REVO
|
||||
F405_TARGETS_16 =
|
||||
F411_TARGETS =
|
||||
|
||||
F1_TARGETS = $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO PORT103R
|
||||
F3_TARGETS = ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE DOGE FURYF3 IRCFUSIONF3 LUX_RACE MOTOLAB NAZE32PRO RMDO SINGULARITY SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3MINI STM32F3DISCOVERY
|
||||
F4_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16) $(F411_TARGETS)
|
||||
VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)
|
||||
|
||||
# Valid targets for OP BootLoader support
|
||||
OPBL_VALID_TARGETS = CC3D_OPBL
|
||||
|
||||
64K_TARGETS = CJMCU
|
||||
128K_TARGETS = ALIENFLIGHTF1 $(CC3D_TARGETS) NAZE OLIMEXINO RMDO AFROMINI
|
||||
256K_TARGETS = EUSTM32F103RC PORT103R $(F3_TARGETS)
|
||||
128K_TARGETS = $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO RMDO
|
||||
256K_TARGETS = $(F3_TARGETS) EUSTM32F103RC PORT103R
|
||||
512K_TARGETS = $(F411_TARGETS)
|
||||
1024K_TARGETS = $(F405_TARGETS) $(F405_TARGETS_16)
|
||||
|
||||
# note that there is no hardfault debugging startup file assembly handler for other platforms
|
||||
ifeq ($(DEBUG_HARDFAULTS),F3)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
|
||||
else
|
||||
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
|
||||
endif
|
||||
|
||||
# Configure default flash sizes for the targets
|
||||
ifeq ($(FLASH_SIZE),)
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(64K_TARGETS)))
|
||||
|
@ -95,6 +90,14 @@ $(error FLASH_SIZE not configured for target $(TARGET))
|
|||
endif
|
||||
endif
|
||||
|
||||
# note that there is no hardfault debugging startup file assembly handler for other platforms
|
||||
ifeq ($(DEBUG_HARDFAULTS),F3)
|
||||
CFLAGS += -DDEBUG_HARDFAULTS
|
||||
STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S
|
||||
else
|
||||
STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S
|
||||
endif
|
||||
|
||||
REVISION = $(shell git log -1 --format="%h")
|
||||
|
||||
FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/version.h | awk '{print $$3}' )
|
||||
|
@ -122,7 +125,9 @@ FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c))
|
|||
|
||||
CSOURCES := $(shell find $(SRC_DIR) -name '*.c')
|
||||
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS)))
|
||||
# F3 TARGETS
|
||||
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver
|
||||
STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c))
|
||||
|
@ -165,16 +170,6 @@ LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k.ld
|
|||
ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion
|
||||
DEVICE_FLAGS = -DSTM32F303xC -DSTM32F303
|
||||
TARGET_FLAGS = -D$(TARGET)
|
||||
ifeq ($(TARGET),CHEBUZZF3)
|
||||
# CHEBUZZ is a VARIANT of STM32F3DISCOVERY
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(SPRACINGF3_TARGETS)))
|
||||
# RMDO and IRCFUSIONF3 are a VARIANT of SPRACINGF3
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSPRACINGF3
|
||||
endif
|
||||
|
||||
## End F3 targets
|
||||
##
|
||||
## Start F4 targets
|
||||
|
@ -274,10 +269,9 @@ $(error Unknown MCU for F4 target)
|
|||
endif
|
||||
|
||||
TARGET_FLAGS = -D$(TARGET)
|
||||
|
||||
## end F4 targets
|
||||
## End F4 targets
|
||||
##
|
||||
## Start F1 targets
|
||||
## Start EUSTM32F103RC PORT103R targets
|
||||
else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R))
|
||||
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
|
||||
|
@ -305,7 +299,9 @@ TARGET_FLAGS = -D$(TARGET) -pedantic
|
|||
DEVICE_FLAGS = -DSTM32F10X_HD -DSTM32F10X
|
||||
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
## End EUSTM32F103RC PORT103R targets
|
||||
##
|
||||
## Start F1 targets
|
||||
else
|
||||
|
||||
STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver
|
||||
|
@ -328,7 +324,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
|||
|
||||
DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC)
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET), $(VCP_VALID_TARGETS)))
|
||||
ifeq ($(TARGET),$(filter $(TARGET), $(VCP_TARGETS)))
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(USBFS_DIR)/inc \
|
||||
$(ROOT)/src/main/vcp
|
||||
|
@ -347,7 +343,7 @@ DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X
|
|||
|
||||
endif
|
||||
##
|
||||
## end F1/F3 target
|
||||
## End F1 targets
|
||||
##
|
||||
|
||||
ifneq ($(FLASH_SIZE),)
|
||||
|
@ -357,6 +353,18 @@ endif
|
|||
TARGET_DIR = $(ROOT)/src/main/target/$(TARGET)
|
||||
TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c))
|
||||
|
||||
# VARIANTS
|
||||
|
||||
ifeq ($(TARGET),CHEBUZZF3)
|
||||
# CHEBUZZ is a VARIANT of STM32F3DISCOVERY
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSTM32F3DISCOVERY
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET),$(SPRACINGF3_TARGETS)))
|
||||
# VARIANTS of SPRACINGF3
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DSPRACINGF3
|
||||
endif
|
||||
|
||||
ifeq ($(TARGET),$(filter $(TARGET), $(NAZE_TARGETS)))
|
||||
# VARIANTS of NAZE
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -D$(TARGET)
|
||||
|
@ -367,16 +375,17 @@ ifeq ($(TARGET),$(filter $(TARGET), $(CC3D_TARGETS)))
|
|||
TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D
|
||||
ifeq ($(TARGET),CC3D_OPBL)
|
||||
TARGET_FLAGS := $(TARGET_FLAGS) -DCC3D_OPBL
|
||||
CC3D_OPBL_SRC = $(CC3D_SRC)
|
||||
endif
|
||||
TARGET_DIR = $(ROOT)/src/main/target/CC3D
|
||||
endif
|
||||
|
||||
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
||||
ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),)
|
||||
OPBL=yes
|
||||
endif
|
||||
|
||||
ifeq ($(OPBL),yes)
|
||||
ifneq ($(filter $(TARGET),$(OPBL_VALID_TARGETS)),)
|
||||
ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),)
|
||||
TARGET_FLAGS := -DOPBL $(TARGET_FLAGS)
|
||||
LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld
|
||||
.DEFAULT_GOAL := binary
|
||||
|
@ -385,49 +394,49 @@ $(error OPBL specified with a unsupported target)
|
|||
endif
|
||||
endif
|
||||
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_DIR)
|
||||
INCLUDE_DIRS := $(INCLUDE_DIRS) \
|
||||
$(TARGET_DIR)
|
||||
|
||||
VPATH := $(VPATH):$(TARGET_DIR)
|
||||
VPATH := $(VPATH):$(TARGET_DIR)
|
||||
|
||||
COMMON_SRC = \
|
||||
build_config.c \
|
||||
debug.c \
|
||||
version.c \
|
||||
$(TARGET_SRC) \
|
||||
config/config.c \
|
||||
config/runtime_config.c \
|
||||
main.c \
|
||||
mw.c \
|
||||
scheduler.c \
|
||||
scheduler_tasks.c \
|
||||
common/encoding.c \
|
||||
common/filter.c \
|
||||
common/maths.c \
|
||||
common/printf.c \
|
||||
common/typeconversion.c \
|
||||
common/encoding.c \
|
||||
common/filter.c \
|
||||
scheduler.c \
|
||||
scheduler_tasks.c \
|
||||
main.c \
|
||||
mw.c \
|
||||
flight/altitudehold.c \
|
||||
flight/failsafe.c \
|
||||
flight/pid.c \
|
||||
flight/imu.c \
|
||||
flight/mixer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
drivers/serial.c \
|
||||
drivers/sound_beeper.c \
|
||||
drivers/system.c \
|
||||
drivers/gyro_sync.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/exti.c \
|
||||
drivers/io.c \
|
||||
drivers/rcc.c \
|
||||
drivers/bus_spi.c \
|
||||
config/config.c \
|
||||
config/runtime_config.c \
|
||||
drivers/adc.c \
|
||||
drivers/buf_writer.c \
|
||||
drivers/bus_i2c_soft.c \
|
||||
drivers/bus_spi.c \
|
||||
drivers/exti.c \
|
||||
drivers/gyro_sync.c \
|
||||
drivers/io.c \
|
||||
drivers/light_led.c \
|
||||
drivers/pwm_mapping.c \
|
||||
drivers/pwm_output.c \
|
||||
drivers/pwm_rx.c \
|
||||
drivers/light_led.c \
|
||||
drivers/rcc.c \
|
||||
drivers/serial.c \
|
||||
drivers/serial_uart.c \
|
||||
drivers/sound_beeper.c \
|
||||
drivers/system.c \
|
||||
drivers/timer.c \
|
||||
flight/altitudehold.c \
|
||||
flight/failsafe.c \
|
||||
flight/imu.c \
|
||||
flight/mixer.c \
|
||||
flight/pid.c \
|
||||
io/beeper.c \
|
||||
io/rc_controls.c \
|
||||
io/rc_curves.c \
|
||||
|
@ -438,16 +447,16 @@ COMMON_SRC = \
|
|||
io/serial_cli.c \
|
||||
io/serial_msp.c \
|
||||
io/statusindicator.c \
|
||||
rx/rx.c \
|
||||
rx/pwm.c \
|
||||
rx/msp.c \
|
||||
rx/sbus.c \
|
||||
rx/sumd.c \
|
||||
rx/sumh.c \
|
||||
rx/spektrum.c \
|
||||
rx/xbus.c \
|
||||
rx/ibus.c \
|
||||
rx/jetiexbus.c \
|
||||
rx/msp.c \
|
||||
rx/pwm.c \
|
||||
rx/rx.c \
|
||||
rx/sbus.c \
|
||||
rx/spektrum.c \
|
||||
rx/sumd.c \
|
||||
rx/sumh.c \
|
||||
rx/xbus.c \
|
||||
sensors/acceleration.c \
|
||||
sensors/battery.c \
|
||||
sensors/boardalignment.c \
|
||||
|
@ -458,22 +467,23 @@ COMMON_SRC = \
|
|||
$(DEVICE_STDPERIPH_SRC)
|
||||
|
||||
HIGHEND_SRC = \
|
||||
blackbox/blackbox.c \
|
||||
blackbox/blackbox_io.c \
|
||||
common/colorconversion.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
flight/gtune.c \
|
||||
flight/navigation.c \
|
||||
flight/gps_conversion.c \
|
||||
common/colorconversion.c \
|
||||
io/gps.c \
|
||||
io/ledstrip.c \
|
||||
io/display.c \
|
||||
sensors/sonar.c \
|
||||
sensors/barometer.c \
|
||||
telemetry/telemetry.c \
|
||||
telemetry/frsky.c \
|
||||
telemetry/hott.c \
|
||||
telemetry/smartport.c \
|
||||
telemetry/ltm.c \
|
||||
sensors/sonar.c \
|
||||
sensors/barometer.c \
|
||||
blackbox/blackbox.c \
|
||||
blackbox/blackbox_io.c
|
||||
telemetry/ltm.c
|
||||
|
||||
VCP_SRC = \
|
||||
vcp/hw_config.c \
|
||||
|
@ -496,26 +506,26 @@ VCPF4_SRC = \
|
|||
|
||||
STM32F10x_COMMON_SRC = \
|
||||
startup_stm32f10x_md_gcc.S \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer_stm32f10x.c \
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/adc_stm32f10x.c \
|
||||
drivers/bus_i2c_stm32f10x.c \
|
||||
drivers/dma.c \
|
||||
drivers/inverter.c
|
||||
drivers/gpio_stm32f10x.c \
|
||||
drivers/inverter.c \
|
||||
drivers/serial_softserial.c \
|
||||
drivers/serial_uart_stm32f10x.c \
|
||||
drivers/system_stm32f10x.c \
|
||||
drivers/timer_stm32f10x.c
|
||||
|
||||
STM32F30x_COMMON_SRC = \
|
||||
startup_stm32f30x_md_gcc.S \
|
||||
target/system_stm32f30x.c \
|
||||
drivers/adc_stm32f30x.c \
|
||||
drivers/bus_i2c_stm32f30x.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/dma.c \
|
||||
drivers/gpio_stm32f30x.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_uart_stm32f30x.c \
|
||||
drivers/system_stm32f30x.c \
|
||||
drivers/dma.c \
|
||||
drivers/timer_stm32f30x.c
|
||||
|
||||
STM32F4xx_COMMON_SRC = \
|
||||
|
@ -549,9 +559,7 @@ NAZE_SRC = \
|
|||
drivers/barometer_bmp085.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
|
@ -581,7 +589,6 @@ EUSTM32F103RC_SRC = \
|
|||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
|
@ -624,7 +631,6 @@ CC3D_SRC = \
|
|||
drivers/barometer_bmp280.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f10x.c \
|
||||
|
@ -643,7 +649,6 @@ NAZE32PRO_SRC = \
|
|||
STM32F3DISCOVERY_COMMON_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/accgyro_l3gd20.c \
|
||||
drivers/accgyro_lsm303dlhc.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
|
@ -686,7 +691,6 @@ COLIBRI_RACE_SRC = \
|
|||
drivers/compass_ak8963.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 \
|
||||
|
@ -723,7 +727,6 @@ DOGE_SRC = \
|
|||
|
||||
SPARKY_SRC = \
|
||||
$(STM32F30x_COMMON_SRC) \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
|
@ -756,7 +759,6 @@ RMDO_SRC = \
|
|||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
|
@ -771,11 +773,10 @@ SPRACINGF3_SRC = \
|
|||
drivers/accgyro_mpu.c \
|
||||
drivers/accgyro_mpu6050.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/barometer_bmp085.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
|
@ -802,7 +803,6 @@ SPRACINGF3EVO_SRC = \
|
|||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
drivers/serial_usb_vcp.c \
|
||||
|
@ -820,7 +820,6 @@ SPRACINGF3EVO_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 \
|
||||
|
@ -842,7 +841,6 @@ SPRACINGF3MINI_SRC = \
|
|||
drivers/barometer_bmp280.c \
|
||||
drivers/compass_ak8975.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/flash_m25p16.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f30x.c \
|
||||
|
@ -882,7 +880,6 @@ FURYF3_SRC = \
|
|||
drivers/accgyro_mpu.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/barometer_bmp280.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/accgyro_spi_mpu6500.c \
|
||||
|
@ -910,7 +907,6 @@ ALIENFLIGHTF4_SRC = \
|
|||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_ak8963.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/light_ws2811strip.c \
|
||||
drivers/light_ws2811strip_stm32f4xx.c \
|
||||
drivers/sdcard.c \
|
||||
|
@ -926,7 +922,6 @@ BLUEJAYF4_SRC = \
|
|||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/sdcard.c \
|
||||
drivers/sdcard_standard.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
|
@ -940,7 +935,6 @@ REVO_SRC = \
|
|||
drivers/accgyro_spi_mpu6000.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/compass_hmc5883l.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
$(HIGHEND_SRC) \
|
||||
$(COMMON_SRC) \
|
||||
$(VCPF4_SRC)
|
||||
|
@ -951,7 +945,6 @@ FURYF4_SRC = \
|
|||
drivers/accgyro_spi_mpu6500.c \
|
||||
drivers/accgyro_mpu6500.c \
|
||||
drivers/barometer_ms5611.c \
|
||||
drivers/display_ug2864hsweg01.c \
|
||||
drivers/sdcard.c \
|
||||
drivers/sdcard_standard.c \
|
||||
io/asyncfatfs/asyncfatfs.c \
|
||||
|
@ -1039,8 +1032,6 @@ ifeq ($(filter $(TARGET),$(VALID_TARGETS)),)
|
|||
$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS))
|
||||
endif
|
||||
|
||||
CC3D_OPBL_SRC = $(CC3D_SRC)
|
||||
|
||||
TARGET_BIN = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).bin
|
||||
TARGET_HEX = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET).hex
|
||||
TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf
|
||||
|
|
|
@ -350,7 +350,7 @@ void init(void)
|
|||
#endif
|
||||
};
|
||||
#ifdef AFROMINI
|
||||
beeperConfig.gpioMode = Mode_Out_PP; // AFROMINI override
|
||||
beeperConfig.isOD = true;
|
||||
beeperConfig.isInverted = true;
|
||||
#endif
|
||||
#ifdef NAZE
|
||||
|
|
105
src/main/target/IRCFUSIONF3/target.c
Normal file
105
src/main/target/IRCFUSIONF3/target.c
Normal file
|
@ -0,0 +1,105 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
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),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
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), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
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),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
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),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
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),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
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), // server #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
|
||||
{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
|
||||
{ TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10}, // PWM3 - PA11
|
||||
{ TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10}, // PWM4 - PA12
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM5 - PB8
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM6 - PB9
|
||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM7 - PA2
|
||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM8 - PA3
|
||||
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
|
@ -19,6 +19,8 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "IFF3"
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define LED0 PB3
|
||||
|
||||
#define USABLE_TIMER_CHANNEL_COUNT 17
|
||||
|
@ -79,7 +81,7 @@
|
|||
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
|
||||
|
||||
#define M25P16_CS_GPIO GPIOB
|
||||
#define M25P16_CS_PIN GPIO_Pin_12
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_ADC
|
||||
|
@ -128,4 +130,12 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
|
|
105
src/main/target/RMDO/target.c
Normal file
105
src/main/target/RMDO/target.c
Normal file
|
@ -0,0 +1,105 @@
|
|||
|
||||
#include <stdbool.h>
|
||||
#include <stdint.h>
|
||||
|
||||
#include <platform.h>
|
||||
#include "drivers/pwm_mapping.h"
|
||||
|
||||
const uint16_t multiPPM[] = {
|
||||
PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input
|
||||
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
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),
|
||||
PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed
|
||||
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), // Swap to servo if needed
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const uint16_t multiPWM[] = {
|
||||
PWM1 | (MAP_TO_PWM_INPUT << 8),
|
||||
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),
|
||||
PWM9 | (MAP_TO_MOTOR_OUTPUT << 8),
|
||||
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),
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
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),
|
||||
PWM5 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM6 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM7 | (MAP_TO_SERVO_OUTPUT << 8),
|
||||
PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #10
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
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), // server #6
|
||||
0xFFFF
|
||||
};
|
||||
|
||||
const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = {
|
||||
{ TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_1}, // RC_CH1 - PA0 - *TIM2_CH1
|
||||
{ TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_1}, // RC_CH2 - PA1 - *TIM2_CH2, TIM15_CH1N
|
||||
// Production boards swapped RC_CH3/4 swapped to make it easier to use SerialRX using supplied cables - compared to first prototype.
|
||||
{ TIM2, GPIOB, Pin_11, TIM_Channel_4, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_1}, // RC_CH3 - PB11 - *TIM2_CH4, USART3_RX (AF7)
|
||||
{ TIM2, GPIOB, Pin_10, TIM_Channel_3, TIM2_IRQn, 0, Mode_AF_PP, GPIO_PinSource10, GPIO_AF_1}, // RC_CH4 - PB10 - *TIM2_CH3, USART3_TX (AF7)
|
||||
{ TIM3, GPIOB, Pin_4, TIM_Channel_1, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource4, GPIO_AF_2}, // RC_CH5 - PB4 - *TIM3_CH1
|
||||
{ TIM3, GPIOB, Pin_5, TIM_Channel_2, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource5, GPIO_AF_2}, // RC_CH6 - PB5 - *TIM3_CH2
|
||||
{ TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2}, // RC_CH7 - PB0 - *TIM3_CH3, TIM1_CH2N, TIM8_CH2N
|
||||
{ TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2}, // RC_CH8 - PB1 - *TIM3_CH4, TIM1_CH3N, TIM8_CH3N
|
||||
|
||||
{ TIM16, GPIOA, Pin_6, TIM_Channel_1, TIM1_UP_TIM16_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_1}, // PWM1 - PA6 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1
|
||||
{ TIM17, GPIOA, Pin_7, TIM_Channel_1, TIM1_TRG_COM_TIM17_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_1}, // PWM2 - PA7 - TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1
|
||||
{ TIM4, GPIOA, Pin_11, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource11, GPIO_AF_10}, // PWM3 - PA11
|
||||
{ TIM4, GPIOA, Pin_12, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource12, GPIO_AF_10}, // PWM4 - PA12
|
||||
{ TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2}, // PWM5 - PB8
|
||||
{ TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2}, // PWM6 - PB9
|
||||
{ TIM15, GPIOA, Pin_2, TIM_Channel_1, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource2, GPIO_AF_9}, // PWM7 - PA2
|
||||
{ TIM15, GPIOA, Pin_3, TIM_Channel_2, TIM1_BRK_TIM15_IRQn, 1, Mode_AF_PP, GPIO_PinSource3, GPIO_AF_9}, // PWM8 - PA3
|
||||
|
||||
{ TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_6}, // GPIO_TIMER / LED_STRIP
|
||||
};
|
||||
|
|
@ -19,6 +19,8 @@
|
|||
|
||||
#define TARGET_BOARD_IDENTIFIER "RMDO" // Ready Made RC DoDo
|
||||
|
||||
#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE
|
||||
|
||||
#define LED0 PB3
|
||||
|
||||
#define BEEPER PC15
|
||||
|
@ -97,7 +99,7 @@
|
|||
#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5
|
||||
|
||||
#define M25P16_CS_GPIO GPIOB
|
||||
#define M25P16_CS_PIN GPIO_Pin_12
|
||||
#define M25P16_CS_PIN PB12
|
||||
#define M25P16_SPI_INSTANCE SPI2
|
||||
|
||||
#define USE_ADC
|
||||
|
@ -148,4 +150,12 @@
|
|||
#define TARGET_IO_PORTA 0xffff
|
||||
#define TARGET_IO_PORTB 0xffff
|
||||
#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1))
|
||||
#define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4))
|
||||
|
||||
|
||||
#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17))
|
||||
|
||||
#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4)
|
||||
#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_TIM15 | RCC_APB2Periph_TIM16 | RCC_APB2Periph_TIM17)
|
||||
#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOA | RCC_AHBPeriph_GPIOB)
|
||||
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue