From b520de715821e8a9af59abcd4e8eba21527c4935 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 15:20:33 +1000 Subject: [PATCH 01/13] Allow for included target.mk files. Saves modifying Makefile with new targets that are similar to others. --- Makefile | 183 ++++++++++++++++------------ src/main/target/BLUEJAYF4/target.mk | 7 ++ 2 files changed, 112 insertions(+), 78 deletions(-) create mode 100644 src/main/target/BLUEJAYF4/target.mk diff --git a/Makefile b/Makefile index 1a63666b18..6cdf873223 100644 --- a/Makefile +++ b/Makefile @@ -43,35 +43,65 @@ FLASH_SIZE ?= FORKNAME = betaflight +# Working directories +ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) +SRC_DIR = $(ROOT)/src/main +OBJECT_DIR = $(ROOT)/obj/main +BIN_DIR = $(ROOT)/obj +CMSIS_DIR = $(ROOT)/lib/main/CMSIS +INCLUDE_DIRS = $(SRC_DIR) \ + $(ROOT)/src/main/target +LINKER_DIR = $(ROOT)/src/main/target + +# default xtal value for F4 targets +HSE_VALUE = 8000000 + +# used for turning on features like VCP and SDCARD +OPTIONS = + CC3D_TARGETS = CC3D CC3D_OPBL NAZE_TARGETS = AFROMINI ALIENFLIGHTF1 SPRACINGF3_TARGETS = IRCFUSIONF3 RMDO -SDCARD_TARGETS = ALIENFLIGHTF4 AQ32_V2 BLUEJAYF4 FURYF3 FURYF4 SPRACINGF3MINI +SDCARD_TARGETS = ALIENFLIGHTF4 AQ32_V2 FURYF3 FURYF4 SPRACINGF3MINI SERIAL_USB_TARGETS = IRCFUSIONF3 SPRACINGF3 # Valid targets for STM VCP support -VCP_TARGETS = $(CC3D_TARGETS) BLUEJAYF4 FURYF3 FURYF4 REVO REVO_OPBL +VCP_TARGETS = $(CC3D_TARGETS) FURYF3 FURYF4 REVO # Valid targets for OP BootLoader support -OPBL_TARGETS = CC3D_OPBL REVO_OPBL +OPBL_TARGETS = CC3D_OPBL +F405_TARGETS = ALIENFLIGHTF4 FURYF4 REVO +F411_TARGETS = -F405_TARGETS = ALIENFLIGHTF4 BLUEJAYF4 FURYF4 REVO REVO_OPBL -F405_TARGETS_16 = -F411_TARGETS = +# silently ignore if the file is not present. Allows for target specific. +-include $(ROOT)/src/main/target/$(TARGET)/target.mk + +F1_TARGETS += $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO PORT103R +F3_TARGETS += ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE DOGE FURYF3 IRCFUSIONF3 KISSFC LUX_RACE MOTOLAB NAZE32PRO RMDO SINGULARITY SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3MINI STM32F3DISCOVERY +F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) -F1_TARGETS = $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO PORT103R -F3_TARGETS = ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE DOGE FURYF3 IRCFUSIONF3 KISSFC 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) +ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) +$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) +endif + +# can get rid of these if all targets that want options get a target.mk +ifeq ($(TARGET),$(filter $(TARGET),$(SDCARD_TARGETS))) +OPTIONS += SDCARD +endif + +ifeq ($(TARGET),$(filter $(TARGET),$(VCP_TARGETS))) +OPTIONS += VCP +endif 64K_TARGETS = CJMCU 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) +1024K_TARGETS = $(F405_TARGETS) # Configure default flash sizes for the targets ifeq ($(FLASH_SIZE),) @@ -106,16 +136,6 @@ FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/version.h | awk '{prin FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) -# Working directories -ROOT := $(patsubst %/,%,$(dir $(lastword $(MAKEFILE_LIST)))) -SRC_DIR = $(ROOT)/src/main -OBJECT_DIR = $(ROOT)/obj/main -BIN_DIR = $(ROOT)/obj -CMSIS_DIR = $(ROOT)/lib/main/CMSIS -INCLUDE_DIRS = $(SRC_DIR) \ - $(ROOT)/src/main/target -LINKER_DIR = $(ROOT)/src/main/target - # Search path for sources VPATH := $(SRC_DIR):$(SRC_DIR)/startup USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver @@ -158,7 +178,7 @@ DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ endif -ifeq ($(TARGET),$(filter $(TARGET), $(SDCARD_TARGETS))) +ifneq ($(filter SDCARD, $(OPTIONS)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(FATFS_DIR) \ @@ -243,7 +263,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ $(ROOT)/src/main/vcpf4 -ifeq ($(TARGET),$(filter $(TARGET),$(SDCARD_TARGETS))) +ifneq ($(filter SDCARD,$(OPTIONS)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(FATFS_DIR) VPATH := $(VPATH):$(FATFS_DIR) @@ -254,19 +274,14 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS))) DEVICE_FLAGS = -DSTM32F411xE -DEVICE_FLAGS += -DHSE_VALUE=8000000 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld -else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS_16))) -DEVICE_FLAGS = -DSTM32F40_41xxx -DEVICE_FLAGS += -DHSE_VALUE=16000000 -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS))) DEVICE_FLAGS = -DSTM32F40_41xxx -DEVICE_FLAGS += -DHSE_VALUE=8000000 LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld else $(error Unknown MCU for F4 target) endif +DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) TARGET_FLAGS = -D$(TARGET) ## End F4 targets @@ -324,7 +339,7 @@ INCLUDE_DIRS := $(INCLUDE_DIRS) \ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) -ifeq ($(TARGET),$(filter $(TARGET), $(VCP_TARGETS))) +ifeq ($(TARGET),$(filter $(TARGET),$(VCP_TARGETS))) INCLUDE_DIRS := $(INCLUDE_DIRS) \ $(USBFS_DIR)/inc \ $(ROOT)/src/main/vcp @@ -350,8 +365,8 @@ ifneq ($(FLASH_SIZE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) endif -TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) -TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) +TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) +TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) # VARIANTS @@ -380,26 +395,14 @@ endif TARGET_DIR = $(ROOT)/src/main/target/CC3D endif -ifeq ($(TARGET),$(filter $(TARGET), REVO_OPBL)) -TARGET_FLAGS := $(TARGET_FLAGS) -DREVO -TARGET_DIR = $(ROOT)/src/main/target/REVO -TARGET_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) -endif - ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),) OPBL=yes endif ifeq ($(OPBL),yes) -ifeq ($(TARGET),$(filter $(TARGET),$(OPBL_TARGETS))) +ifneq ($(filter $(TARGET),$(OPBL_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))) -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_bl.ld -else -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld -endif +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld .DEFAULT_GOAL := binary else $(error OPBL specified with a unsupported target) @@ -415,7 +418,7 @@ COMMON_SRC = \ build_config.c \ debug.c \ version.c \ - $(TARGET_SRC) \ + $(TARGET_DIR_SRC) \ main.c \ mw.c \ scheduler.c \ @@ -497,6 +500,15 @@ HIGHEND_SRC = \ telemetry/smartport.c \ telemetry/ltm.c +ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) +VCP_SRC = \ + vcpf4/stm32f4xx_it.c \ + vcpf4/usb_bsp.c \ + vcpf4/usbd_desc.c \ + vcpf4/usbd_usr.c \ + vcpf4/usbd_cdc_vcp.c \ + drivers/serial_usb_vcp.c +else VCP_SRC = \ vcp/hw_config.c \ vcp/stm32_it.c \ @@ -507,14 +519,7 @@ VCP_SRC = \ vcp/usb_pwr.c \ drivers/serial_usb_vcp.c \ drivers/usb_io.c - -VCPF4_SRC = \ - vcpf4/stm32f4xx_it.c \ - vcpf4/usb_bsp.c \ - vcpf4/usbd_desc.c \ - vcpf4/usbd_usr.c \ - vcpf4/usbd_cdc_vcp.c \ - drivers/serial_usb_vcp.c +endif STM32F10x_COMMON_SRC = \ startup_stm32f10x_md_gcc.S \ @@ -938,20 +943,7 @@ ALIENFLIGHTF4_SRC = \ io/asyncfatfs/fat_standard.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ - $(VCPF4_SRC) - -BLUEJAYF4_SRC = \ - $(STM32F4xx_COMMON_SRC) \ - drivers/accgyro_spi_mpu6500.c \ - drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCPF4_SRC) + $(VCP_SRC) REVO_SRC = \ $(STM32F4xx_COMMON_SRC) \ @@ -960,9 +952,7 @@ REVO_SRC = \ drivers/compass_hmc5883l.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ - $(VCPF4_SRC) - -REVO_OPBL_SRC = $(REVO_SRC) + $(VCP_SRC) FURYF4_SRC = \ $(STM32F4xx_COMMON_SRC) \ @@ -976,7 +966,48 @@ FURYF4_SRC = \ io/asyncfatfs/fat_standard.c \ $(HIGHEND_SRC) \ $(COMMON_SRC) \ - $(VCPF4_SRC) + $(VCP_SRC) + +# check if target.mk supplied +ifneq ($(TARGET_SRC),) +ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) +TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC) + +else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC) +else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) +TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC) +endif + +ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS))) +TARGET_SRC += $(HIGHEND_SRC) +endif + +TARGET_SRC += $(COMMON_SRC) + +ifneq ($(filter SDCARD,$(OPTIONS)),) +TARGET_SRC += \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c +endif + +ifneq ($(filter VCP,$(OPTIONS)),) +TARGET_SRC += $(VCP_SRC) +endif + +# end target.mk supplied - now know the source was supplied above. +else +ifeq ($($(TARGET)_SRC),) +$(error Target source files not found. Have you prepared a target.mk?) +else +TARGET_SRC = $($(TARGET)_SRC) +endif +endif + + + # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src @@ -1053,15 +1084,11 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ # # Things we will build # -ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) -$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) -endif - 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 -TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) -TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $($(TARGET)_SRC)))) +TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC)))) +TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(TARGET_SRC)))) TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk new file mode 100644 index 0000000000..0438a2982f --- /dev/null +++ b/src/main/target/BLUEJAYF4/target.mk @@ -0,0 +1,7 @@ +F405_TARGETS += $(TARGET) +OPTIONS += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_ms5611.c From 1404253c9794a7610ebdfa67113880e4c3cbcc5d Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 15:38:22 +1000 Subject: [PATCH 02/13] Simplified EUSTM32F103RC and PORT103R in Makefile (move to target specific mk file) --- Makefile | 38 +++++++------------------------------- 1 file changed, 7 insertions(+), 31 deletions(-) diff --git a/Makefile b/Makefile index 6cdf873223..fde70569b6 100644 --- a/Makefile +++ b/Makefile @@ -286,36 +286,6 @@ DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) TARGET_FLAGS = -D$(TARGET) ## End F4 targets ## -## Start EUSTM32F103RC PORT103R targets -else ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) - -STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver -STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) -EXCLUDES = stm32f10x_crc.c \ - stm32f10x_cec.c \ - stm32f10x_can.c - -STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) - -# Search path and source files for the CMSIS sources -VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x -CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) - -INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM3/CoreSupport \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ - -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld - -ARCH_FLAGS = -mthumb -mcpu=cortex-m3 -TARGET_FLAGS = -D$(TARGET) -pedantic -DEVICE_FLAGS = -DSTM32F10X_HD -DSTM32F10X - -DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) -## End EUSTM32F103RC PORT103R targets -## ## Start F1 targets else @@ -354,7 +324,13 @@ endif LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m3 TARGET_FLAGS = -D$(TARGET) -pedantic -DEVICE_FLAGS = -DSTM32F10X_MD -DSTM32F10X + +ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) +DEVICE_FLAGS = -DSTM32F10X_MD +else +DEVICE_FLAGS = -DSTM32F10X_HD +endif +DEVICE_FLAGS += -DSTM32F10X endif ## From 6234652e7da7212409436439432205473aaa27b3 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 17:09:28 +1000 Subject: [PATCH 03/13] Fixed VCP_TARGETS --- Makefile | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/Makefile b/Makefile index fde70569b6..5bf4864325 100644 --- a/Makefile +++ b/Makefile @@ -67,7 +67,7 @@ SDCARD_TARGETS = ALIENFLIGHTF4 AQ32_V2 FURYF3 FURYF4 SPRACINGF3MINI SERIAL_USB_TARGETS = IRCFUSIONF3 SPRACINGF3 # Valid targets for STM VCP support -VCP_TARGETS = $(CC3D_TARGETS) FURYF3 FURYF4 REVO +VCP_TARGETS = $(CC3D_TARGETS) ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE LUX_RACE MOTOLAB NAZE32PRO SPARKY SPRACINGF3EVO SPRACINGF3MINI STM32F3DISCOVERY FURYF3 FURYF4 REVO # Valid targets for OP BootLoader support OPBL_TARGETS = CC3D_OPBL From addfbe4ffe92c56fa5bdfe09911e3124fd393ffa Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 21:35:46 +1000 Subject: [PATCH 04/13] Finishing off Makefile changes removing target specifics --- Makefile | 969 +++++------------- .../target/ALIENFLIGHTF1/hardware_revision.c | 111 ++ .../target/ALIENFLIGHTF1/hardware_revision.h | 30 + src/main/target/ALIENFLIGHTF1/target.c | 90 ++ src/main/target/ALIENFLIGHTF1/target.h | 188 ++++ src/main/target/ALIENFLIGHTF1/target.mk | 21 + src/main/target/ALIENFLIGHTF3/target.mk | 12 + src/main/target/ALIENFLIGHTF4/target.mk | 13 + src/main/target/BLUEJAYF4/target.mk | 2 +- src/main/target/CC3D/target.mk | 13 + src/main/target/CHEBUZZF3/target.h | 5 +- src/main/target/CHEBUZZF3/target.mk | 18 + src/main/target/CJMCU/target.h | 2 +- src/main/target/CJMCU/target.mk | 11 + src/main/target/COLIBRI_RACE/target.mk | 17 + src/main/target/DOGE/target.mk | 15 + src/main/target/EUSTM32F103RC/target.mk | 23 + src/main/target/FURYF3/target.mk | 15 + src/main/target/FURYF4/target.mk | 8 + src/main/target/IRCFUSIONF3/target.mk | 8 + src/main/target/KISSFC/target.mk | 10 + src/main/target/LUX_RACE/target.mk | 14 + src/main/target/MOTOLAB/target.mk | 15 + src/main/target/NAZE/target.mk | 21 + src/main/target/NAZE32PRO/target.mk | 4 + src/main/target/OLIMEXINO/target.mk | 12 + src/main/target/PORT103R/target.mk | 23 + src/main/target/REVO/target.mk | 8 + src/main/target/RMDO/target.mk | 13 + src/main/target/SINGULARITY/target.mk | 12 + src/main/target/SPARKY/target.mk | 14 + src/main/target/SPRACINGF3/target.mk | 15 + src/main/target/SPRACINGF3EVO/target.mk | 16 + src/main/target/SPRACINGF3MINI/target.mk | 19 + src/main/target/STM32F3DISCOVERY/target.mk | 18 + ...sh_f405_bl.ld => stm32_flash_f405_opbl.ld} | 0 ...sh_f411_bl.ld => stm32_flash_f411_opbl.ld} | 0 37 files changed, 1075 insertions(+), 710 deletions(-) create mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.c create mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.h create mode 100644 src/main/target/ALIENFLIGHTF1/target.c create mode 100644 src/main/target/ALIENFLIGHTF1/target.h create mode 100644 src/main/target/ALIENFLIGHTF1/target.mk create mode 100644 src/main/target/ALIENFLIGHTF3/target.mk create mode 100644 src/main/target/ALIENFLIGHTF4/target.mk create mode 100644 src/main/target/CC3D/target.mk create mode 100644 src/main/target/CHEBUZZF3/target.mk create mode 100644 src/main/target/CJMCU/target.mk create mode 100644 src/main/target/COLIBRI_RACE/target.mk create mode 100644 src/main/target/DOGE/target.mk create mode 100644 src/main/target/EUSTM32F103RC/target.mk create mode 100644 src/main/target/FURYF3/target.mk create mode 100644 src/main/target/FURYF4/target.mk create mode 100644 src/main/target/IRCFUSIONF3/target.mk create mode 100644 src/main/target/KISSFC/target.mk create mode 100644 src/main/target/LUX_RACE/target.mk create mode 100644 src/main/target/MOTOLAB/target.mk create mode 100644 src/main/target/NAZE/target.mk create mode 100644 src/main/target/NAZE32PRO/target.mk create mode 100644 src/main/target/OLIMEXINO/target.mk create mode 100644 src/main/target/PORT103R/target.mk create mode 100644 src/main/target/REVO/target.mk create mode 100644 src/main/target/RMDO/target.mk create mode 100644 src/main/target/SINGULARITY/target.mk create mode 100644 src/main/target/SPARKY/target.mk create mode 100644 src/main/target/SPRACINGF3/target.mk create mode 100644 src/main/target/SPRACINGF3EVO/target.mk create mode 100644 src/main/target/SPRACINGF3MINI/target.mk create mode 100644 src/main/target/STM32F3DISCOVERY/target.mk rename src/main/target/{stm32_flash_f405_bl.ld => stm32_flash_f405_opbl.ld} (100%) rename src/main/target/{stm32_flash_f411_bl.ld => stm32_flash_f411_opbl.ld} (100%) diff --git a/Makefile b/Makefile index 5bf4864325..8d1c95b4c0 100644 --- a/Makefile +++ b/Makefile @@ -50,36 +50,21 @@ OBJECT_DIR = $(ROOT)/obj/main BIN_DIR = $(ROOT)/obj CMSIS_DIR = $(ROOT)/lib/main/CMSIS INCLUDE_DIRS = $(SRC_DIR) \ - $(ROOT)/src/main/target + $(ROOT)/src/main/target LINKER_DIR = $(ROOT)/src/main/target # default xtal value for F4 targets -HSE_VALUE = 8000000 +HSE_VALUE = 8000000 # used for turning on features like VCP and SDCARD -OPTIONS = +FEATURES = -CC3D_TARGETS = CC3D CC3D_OPBL -NAZE_TARGETS = AFROMINI ALIENFLIGHTF1 -SPRACINGF3_TARGETS = IRCFUSIONF3 RMDO - -SDCARD_TARGETS = ALIENFLIGHTF4 AQ32_V2 FURYF3 FURYF4 SPRACINGF3MINI -SERIAL_USB_TARGETS = IRCFUSIONF3 SPRACINGF3 - -# Valid targets for STM VCP support -VCP_TARGETS = $(CC3D_TARGETS) ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE LUX_RACE MOTOLAB NAZE32PRO SPARKY SPRACINGF3EVO SPRACINGF3MINI STM32F3DISCOVERY FURYF3 FURYF4 REVO - -# Valid targets for OP BootLoader support -OPBL_TARGETS = CC3D_OPBL - -F405_TARGETS = ALIENFLIGHTF4 FURYF4 REVO +F405_TARGETS = F411_TARGETS = # silently ignore if the file is not present. Allows for target specific. -include $(ROOT)/src/main/target/$(TARGET)/target.mk -F1_TARGETS += $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO PORT103R -F3_TARGETS += ALIENFLIGHTF3 CHEBUZZF3 COLIBRI_RACE DOGE FURYF3 IRCFUSIONF3 KISSFC LUX_RACE MOTOLAB NAZE32PRO RMDO SINGULARITY SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3MINI STM32F3DISCOVERY F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) @@ -88,33 +73,21 @@ ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) endif -# can get rid of these if all targets that want options get a target.mk -ifeq ($(TARGET),$(filter $(TARGET),$(SDCARD_TARGETS))) -OPTIONS += SDCARD -endif - -ifeq ($(TARGET),$(filter $(TARGET),$(VCP_TARGETS))) -OPTIONS += VCP -endif - -64K_TARGETS = CJMCU -128K_TARGETS = $(CC3D_TARGETS) AFROMINI ALIENFLIGHTF1 NAZE OLIMEXINO RMDO -256K_TARGETS = $(F3_TARGETS) EUSTM32F103RC PORT103R +128K_TARGETS = $(F1_TARGETS) +256K_TARGETS = $(F3_TARGETS) 512K_TARGETS = $(F411_TARGETS) 1024K_TARGETS = $(F405_TARGETS) -# Configure default flash sizes for the targets +# Configure default flash sizes for the targets (largest size specified gets hit first) ifeq ($(FLASH_SIZE),) -ifeq ($(TARGET),$(filter $(TARGET),$(64K_TARGETS))) -FLASH_SIZE = 64 -else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS))) -FLASH_SIZE = 128 -else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS))) -FLASH_SIZE = 256 +ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS))) +FLASH_SIZE = 1024 else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS))) FLASH_SIZE = 512 -else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS))) -FLASH_SIZE = 1024 +else ifeq ($(TARGET),$(filter $(TARGET),$(256K_TARGETS))) +FLASH_SIZE = 256 +else ifeq ($(TARGET),$(filter $(TARGET),$(128K_TARGETS))) +FLASH_SIZE = 128 else $(error FLASH_SIZE not configured for target $(TARGET)) endif @@ -152,35 +125,34 @@ ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f30x_crc.c \ - stm32f30x_can.c + stm32f30x_can.c STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \ - $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM1/CoreSupport \ - $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM1/CoreSupport \ + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x -ifneq ($(TARGET),$(filter $(TARGET), $(SERIAL_USB_TARGETS))) +ifneq ($(filter VCP, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ - $(USBPERIPH_SRC) - + $(USBPERIPH_SRC) endif -ifneq ($(filter SDCARD, $(OPTIONS)),) +ifneq ($(filter SDCARD, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) \ + $(FATFS_DIR) \ VPATH := $(VPATH):$(FATFS_DIR) endif @@ -199,25 +171,25 @@ else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f4xx_crc.c \ - stm32f4xx_can.c \ - stm32f4xx_fmc.c \ - stm32f4xx_sai.c \ - stm32f4xx_cec.c \ - stm32f4xx_dsi.c \ - stm32f4xx_flash_ramfunc.c \ - stm32f4xx_fmpi2c.c \ - stm32f4xx_lptim.c \ - stm32f4xx_qspi.c \ - stm32f4xx_spdifrx.c \ - stm32f4xx_cryp.c \ - stm32f4xx_cryp_aes.c \ - stm32f4xx_hash_md5.c \ - stm32f4xx_cryp_des.c \ - stm32f4xx_rtc.c \ - stm32f4xx_hash.c \ - stm32f4xx_dbgmcu.c \ - stm32f4xx_cryp_tdes.c \ - stm32f4xx_hash_sha1.c + stm32f4xx_can.c \ + stm32f4xx_fmc.c \ + stm32f4xx_sai.c \ + stm32f4xx_cec.c \ + stm32f4xx_dsi.c \ + stm32f4xx_flash_ramfunc.c \ + stm32f4xx_fmpi2c.c \ + stm32f4xx_lptim.c \ + stm32f4xx_qspi.c \ + stm32f4xx_spdifrx.c \ + stm32f4xx_cryp.c \ + stm32f4xx_cryp_aes.c \ + stm32f4xx_hash_md5.c \ + stm32f4xx_cryp_des.c \ + stm32f4xx_rtc.c \ + stm32f4xx_hash.c \ + stm32f4xx_dbgmcu.c \ + stm32f4xx_cryp_tdes.c \ + stm32f4xx_hash_sha1.c ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) @@ -232,10 +204,10 @@ USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c)) USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c)) EXCLUDES = usb_bsp_template.c \ - usb_conf_template.c \ - usb_hcd_int.c \ - usb_hcd.c \ - usb_otg.c + usb_conf_template.c \ + usb_hcd_int.c \ + usb_hcd.c \ + usb_otg.c USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC)) USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc @@ -245,27 +217,27 @@ USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ - $(USBOTG_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) + $(USBOTG_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) #CMSIS VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \ - $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(USBOTG_DIR)/inc \ - $(USBCORE_DIR)/inc \ - $(USBCDC_DIR)/inc \ - $(USBFS_DIR)/inc \ - $(CMSIS_DIR)/CM4/CoreSupport \ - $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ - $(ROOT)/src/main/vcpf4 + $(STDPERIPH_DIR)/inc \ + $(USBOTG_DIR)/inc \ + $(USBCORE_DIR)/inc \ + $(USBCDC_DIR)/inc \ + $(USBFS_DIR)/inc \ + $(CMSIS_DIR)/CM4/CoreSupport \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ + $(ROOT)/src/main/vcpf4 -ifneq ($(filter SDCARD,$(OPTIONS)),) +ifneq ($(filter SDCARD,$(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) + $(FATFS_DIR) VPATH := $(VPATH):$(FATFS_DIR) endif @@ -292,43 +264,41 @@ else STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f10x_crc.c \ - stm32f10x_cec.c \ - stm32f10x_can.c + stm32f10x_cec.c \ + stm32f10x_can.c STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) # Search path and source files for the CMSIS sources VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM3/CoreSupport \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) -ifeq ($(TARGET),$(filter $(TARGET),$(VCP_TARGETS))) +ifneq ($(filter VCP, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \ - $(USBPERIPH_SRC) + $(USBPERIPH_SRC) endif LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld ARCH_FLAGS = -mthumb -mcpu=cortex-m3 -TARGET_FLAGS = -D$(TARGET) -pedantic +TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS) -ifeq ($(TARGET),$(filter $(TARGET),EUSTM32F103RC PORT103R)) +ifeq ($(DEVICE_FLAGS),) DEVICE_FLAGS = -DSTM32F10X_MD -else -DEVICE_FLAGS = -DSTM32F10X_HD endif DEVICE_FLAGS += -DSTM32F10X @@ -351,598 +321,176 @@ ifeq ($(TARGET),CHEBUZZF3) 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) TARGET_DIR = $(ROOT)/src/main/target/NAZE endif -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_TARGETS)),) -OPBL=yes -endif - ifeq ($(OPBL),yes) -ifneq ($(filter $(TARGET),$(OPBL_TARGETS)),) TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) +ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS))) +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405_opbl.ld +else ifeq ($(TARGET), $(filter $(TARGET),$(F411_TARGETS))) +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411_opbl.ld +else ifeq ($(TARGET), $(filter $(TARGET),$(F3_TARGETS))) +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f303_$(FLASH_SIZE)k_opbl.ld +else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS))) LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld -.DEFAULT_GOAL := binary -else -$(error OPBL specified with a unsupported target) endif +.DEFAULT_GOAL := binary endif INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_DIR) + $(TARGET_DIR) VPATH := $(VPATH):$(TARGET_DIR) COMMON_SRC = \ - build_config.c \ - debug.c \ - version.c \ - $(TARGET_DIR_SRC) \ - main.c \ - mw.c \ - scheduler.c \ - scheduler_tasks.c \ - common/encoding.c \ - common/filter.c \ - common/maths.c \ - common/printf.c \ - common/typeconversion.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/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 \ - io/serial.c \ - io/serial_4way.c \ - io/serial_4way_avrootloader.c \ - io/serial_4way_stk500v2.c \ - io/serial_cli.c \ - io/serial_msp.c \ - io/statusindicator.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 \ - sensors/compass.c \ - sensors/gyro.c \ - sensors/initialisation.c \ - $(CMSIS_SRC) \ - $(DEVICE_STDPERIPH_SRC) + build_config.c \ + debug.c \ + version.c \ + $(TARGET_DIR_SRC) \ + main.c \ + mw.c \ + scheduler.c \ + scheduler_tasks.c \ + common/encoding.c \ + common/filter.c \ + common/maths.c \ + common/printf.c \ + common/typeconversion.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/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 \ + io/serial.c \ + io/serial_4way.c \ + io/serial_4way_avrootloader.c \ + io/serial_4way_stk500v2.c \ + io/serial_cli.c \ + io/serial_msp.c \ + io/statusindicator.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 \ + sensors/compass.c \ + sensors/gyro.c \ + sensors/initialisation.c \ + $(CMSIS_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 \ - 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 + blackbox/blackbox.c \ + blackbox/blackbox_io.c \ + common/colorconversion.c \ + drivers/display_ug2864hsweg01.c \ + flight/gtune.c \ + flight/navigation.c \ + flight/gps_conversion.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 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) VCP_SRC = \ - vcpf4/stm32f4xx_it.c \ - vcpf4/usb_bsp.c \ - vcpf4/usbd_desc.c \ - vcpf4/usbd_usr.c \ - vcpf4/usbd_cdc_vcp.c \ - drivers/serial_usb_vcp.c + vcpf4/stm32f4xx_it.c \ + vcpf4/usb_bsp.c \ + vcpf4/usbd_desc.c \ + vcpf4/usbd_usr.c \ + vcpf4/usbd_cdc_vcp.c \ + drivers/serial_usb_vcp.c else VCP_SRC = \ - vcp/hw_config.c \ - vcp/stm32_it.c \ - vcp/usb_desc.c \ - vcp/usb_endp.c \ - vcp/usb_istr.c \ - vcp/usb_prop.c \ - vcp/usb_pwr.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c + vcp/hw_config.c \ + vcp/stm32_it.c \ + vcp/usb_desc.c \ + vcp/usb_endp.c \ + vcp/usb_istr.c \ + vcp/usb_prop.c \ + vcp/usb_pwr.c \ + drivers/serial_usb_vcp.c \ + drivers/usb_io.c endif STM32F10x_COMMON_SRC = \ - startup_stm32f10x_md_gcc.S \ - drivers/adc_stm32f10x.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/dma.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 + startup_stm32f10x_md_gcc.S \ + drivers/adc_stm32f10x.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/dma.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/dma.c \ - drivers/gpio_stm32f30x.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_uart_stm32f30x.c \ - drivers/system_stm32f30x.c \ - drivers/timer_stm32f30x.c + startup_stm32f30x_md_gcc.S \ + target/system_stm32f30x.c \ + drivers/adc_stm32f30x.c \ + drivers/bus_i2c_stm32f30x.c \ + drivers/dma.c \ + drivers/gpio_stm32f30x.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_uart_stm32f30x.c \ + drivers/system_stm32f30x.c \ + drivers/timer_stm32f30x.c STM32F4xx_COMMON_SRC = \ - startup_stm32f40xx.s \ - target/system_stm32f4xx.c \ - drivers/accgyro_mpu.c \ - drivers/adc_stm32f4xx.c \ - drivers/adc_stm32f4xx.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/gpio_stm32f4xx.c \ - drivers/inverter.c \ - drivers/serial_softserial.c \ - drivers/serial_uart_stm32f4xx.c \ - drivers/system_stm32f4xx.c \ - drivers/timer_stm32f4xx.c \ - drivers/dma_stm32f4xx.c \ - drivers/flash_m25p16.c \ - io/flashfs.c - -NAZE_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - io/flashfs.c \ - hardware_revision.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -ALIENFLIGHTF1_SRC = $(NAZE_SRC) - -AFROMINI_SRC = $(NAZE_SRC) - -EUSTM32F103RC_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -PORT103R_SRC = $(EUSTM32F103RC_SRC) - -OLIMEXINO_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -CJMCU_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/compass_hmc5883l.c \ - hardware_revision.c \ - flight/gtune.c \ - blackbox/blackbox.c \ - blackbox/blackbox_io.c \ - $(COMMON_SRC) - -CC3D_SRC = \ - $(STM32F10x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -NAZE32PRO_SRC = \ - $(STM32F30x_COMMON_SRC) \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -STM32F3DISCOVERY_COMMON_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/light_ws2811strip.c \ - drivers/accgyro_l3gd20.c \ - drivers/accgyro_lsm303dlhc.c \ - drivers/compass_hmc5883l.c \ - $(VCP_SRC) - -STM32F3DISCOVERY_SRC = \ - $(STM32F3DISCOVERY_COMMON_SRC) \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_l3g4200d.c \ - drivers/barometer_ms5611.c \ - drivers/barometer_bmp280.c \ - drivers/compass_ak8975.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -CHEBUZZF3_SRC = \ - $(STM32F3DISCOVERY_SRC) \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -COLIBRI_RACE_SRC = \ - $(STM32F30x_COMMON_SRC) \ - io/i2c_bst.c \ - drivers/bus_bst_stm32f30x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8963.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_usb_vcp.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -KISSFC_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/display_ug2864hsweg01.c \ - drivers/accgyro_mpu6050.c \ - drivers/serial_usb_vcp.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -LUX_RACE_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/accgyro_mpu6500.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_usb_vcp.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -DOGE_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_spi_bmp280.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_usb_vcp.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -SPARKY_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - 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 \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -ALIENFLIGHTF3_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/compass_ak8963.c \ - hardware_revision.c \ - drivers/serial_usb_vcp.c \ - drivers/sonar_hcsr04.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -RMDO_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/barometer_bmp280.c \ - 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) - -SPRACINGF3_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/barometer_ms5611.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/compass_ak8975.c \ - drivers/compass_hmc5883l.c \ - 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) - -IRCFUSIONF3_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/barometer_bmp085.c \ - drivers/flash_m25p16.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) - -SPRACINGF3EVO_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp280.c \ - drivers/compass_ak8963.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_usb_vcp.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - drivers/transponder_ir.c \ - drivers/transponder_ir_stm32f30x.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - io/transponder_ir.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -MOTOLAB_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ - drivers/serial_usb_vcp.c \ - drivers/flash_m25p16.c \ - io/flashfs.c \ - $(HIGHEND_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/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 \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - drivers/transponder_ir.c \ - drivers/transponder_ir_stm32f30x.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - io/transponder_ir.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) -# $(FATFS_SRC) - -SINGULARITY_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu6050.c \ - drivers/flash_m25p16.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_softserial.c \ - drivers/serial_usb_vcp.c \ - drivers/vtx_rtc6705.c \ - io/flashfs.c \ - io/vtx.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -FURYF3_SRC = \ - $(STM32F30x_COMMON_SRC) \ - drivers/accgyro_mpu.c \ - drivers/barometer_ms5611.c \ - drivers/barometer_bmp280.c \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_usb_vcp.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - drivers/flash_m25p16.c \ - drivers/sonar_hcsr04.c \ - drivers/serial_softserial.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - io/flashfs.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -ALIENFLIGHTF4_SRC = \ - $(STM32F4xx_COMMON_SRC) \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/accgyro_spi_mpu9250.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_ak8963.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f4xx.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -REVO_SRC = \ - $(STM32F4xx_COMMON_SRC) \ - drivers/accgyro_spi_mpu6000.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) - -FURYF4_SRC = \ - $(STM32F4xx_COMMON_SRC) \ - drivers/accgyro_spi_mpu6000.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/accgyro_mpu6500.c \ - drivers/barometer_ms5611.c \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c \ - $(HIGHEND_SRC) \ - $(COMMON_SRC) \ - $(VCP_SRC) + startup_stm32f40xx.s \ + target/system_stm32f4xx.c \ + drivers/accgyro_mpu.c \ + drivers/adc_stm32f4xx.c \ + drivers/adc_stm32f4xx.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/gpio_stm32f4xx.c \ + drivers/inverter.c \ + drivers/serial_softserial.c \ + drivers/serial_uart_stm32f4xx.c \ + drivers/system_stm32f4xx.c \ + drivers/timer_stm32f4xx.c \ + drivers/dma_stm32f4xx.c # check if target.mk supplied ifneq ($(TARGET_SRC),) @@ -955,21 +503,29 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) TARGET_SRC := $(STM32F10x_COMMON_SRC) $(TARGET_SRC) endif +ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) +TARGET_SRC += \ + drivers/flash_m25p16.c \ + io/flashfs.c +endif + ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS))) TARGET_SRC += $(HIGHEND_SRC) +else ifneq ($(filter HIGHEND,$(FEATURES)),) +TARGET_SRC += $(HIGHEND_SRC) endif -TARGET_SRC += $(COMMON_SRC) +TARGET_SRC += $(COMMON_SRC) -ifneq ($(filter SDCARD,$(OPTIONS)),) +ifneq ($(filter SDCARD,$(FEATURES)),) TARGET_SRC += \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c endif -ifneq ($(filter VCP,$(OPTIONS)),) +ifneq ($(filter VCP,$(FEATURES)),) TARGET_SRC += $(VCP_SRC) endif @@ -980,11 +536,10 @@ $(error Target source files not found. Have you prepared a target.mk?) else TARGET_SRC = $($(TARGET)_SRC) endif +# end target specific make file checks endif - - # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src @@ -1012,50 +567,50 @@ endif DEBUG_FLAGS = -ggdb3 -DDEBUG CFLAGS += $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(addprefix -D,$(OPTIONS)) \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - $(DEBUG_FLAGS) \ - -std=gnu99 \ - -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ - -ffunction-sections \ - -fdata-sections \ - $(DEVICE_FLAGS) \ - -DUSE_STDPERIPH_DRIVER \ - $(TARGET_FLAGS) \ - -D'__FORKNAME__="$(FORKNAME)"' \ - -D'__TARGET__="$(TARGET)"' \ - -D'__REVISION__="$(REVISION)"' \ - -save-temps=obj \ - -MMD -MP + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -std=gnu99 \ + -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ + -ffunction-sections \ + -fdata-sections \ + $(DEVICE_FLAGS) \ + -DUSE_STDPERIPH_DRIVER \ + $(TARGET_FLAGS) \ + -D'__FORKNAME__="$(FORKNAME)"' \ + -D'__TARGET__="$(TARGET)"' \ + -D'__REVISION__="$(REVISION)"' \ + -save-temps=obj \ + -MMD -MP ASFLAGS = $(ARCH_FLAGS) \ - -x assembler-with-cpp \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -MMD -MP + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + -MMD -MP LDFLAGS = -lm \ - -nostartfiles \ - --specs=nano.specs \ - -lc \ - -lnosys \ - $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(DEBUG_FLAGS) \ - -static \ - -Wl,-gc-sections,-Map,$(TARGET_MAP) \ - -Wl,-L$(LINKER_DIR) \ - -Wl,--cref \ - -T$(LD_SCRIPT) + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -Wl,-L$(LINKER_DIR) \ + -Wl,--cref \ + -T$(LD_SCRIPT) ############################################################################### # No user-serviceable parts below ############################################################################### CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ - --std=c99 --inline-suppr --quiet --force \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -I/usr/include -I/usr/include/linux + --std=c99 --inline-suppr --quiet --force \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + -I/usr/include -I/usr/include/linux # # Things we will build diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.c b/src/main/target/ALIENFLIGHTF1/hardware_revision.c new file mode 100644 index 0000000000..dae3698442 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF1/hardware_revision.c @@ -0,0 +1,111 @@ +/* + * 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/bus_spi.h" +#include "drivers/sensor.h" +#include "drivers/exti.h" +#include "drivers/accgyro.h" +#include "drivers/accgyro_mpu.h" +#include "drivers/accgyro_mpu6500.h" + +#include "hardware_revision.h" + +static const char * const hardwareRevisionNames[] = { + "Unknown", + "Naze 32", + "Naze32 rev.5", + "Naze32 SP" +}; + +uint8_t hardwareRevision = UNKNOWN; + +void detectHardwareRevision(void) +{ + if (hse_value == 8000000) + hardwareRevision = NAZE32; + else if (hse_value == 12000000) + hardwareRevision = NAZE32_REV5; +} + +#ifdef USE_SPI + +#define DISABLE_SPI_CS IOLo(nazeSpiCsPin) +#define ENABLE_SPI_CS IOHi(nazeSpiCsPin) + +#define SPI_DEVICE_NONE (0) +#define SPI_DEVICE_FLASH (1) +#define SPI_DEVICE_MPU (2) + +#define M25P16_INSTRUCTION_RDID 0x9F +#define FLASH_M25P16_ID (0x202015) + +static IO_t nazeSpiCsPin = IO_NONE; + +uint8_t detectSpiDevice(void) +{ +#ifdef NAZE_SPI_CS_PIN + nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); +#endif + + uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; + uint8_t in[4]; + uint32_t flash_id; + + // try autodetect flash chip + delay(50); // short delay required after initialisation of SPI device instance. + ENABLE_SPI_CS; + spiTransfer(NAZE_SPI_INSTANCE, in, out, sizeof(out)); + DISABLE_SPI_CS; + + flash_id = in[1] << 16 | in[2] << 8 | in[3]; + if (flash_id == FLASH_M25P16_ID) + return SPI_DEVICE_FLASH; + + + // try autodetect MPU + delay(50); + ENABLE_SPI_CS; + spiTransferByte(NAZE_SPI_INSTANCE, MPU_RA_WHO_AM_I | MPU6500_BIT_RESET); + in[0] = spiTransferByte(NAZE_SPI_INSTANCE, 0xff); + DISABLE_SPI_CS; + + if (in[0] == MPU6500_WHO_AM_I_CONST) + return SPI_DEVICE_MPU; + + return SPI_DEVICE_NONE; +} + +#endif + +void updateHardwareRevision(void) +{ +#ifdef USE_SPI + uint8_t detectedSpiDevice = detectSpiDevice(); + + if (detectedSpiDevice == SPI_DEVICE_MPU && hardwareRevision == NAZE32_REV5) + hardwareRevision = NAZE32_SP; +#endif +} diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.h b/src/main/target/ALIENFLIGHTF1/hardware_revision.h new file mode 100644 index 0000000000..9f663bb6c2 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF1/hardware_revision.h @@ -0,0 +1,30 @@ +/* + * 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 nazeHardwareRevision_t { + UNKNOWN = 0, + NAZE32, // Naze32 and compatible with 8MHz HSE + NAZE32_REV5, // Naze32 and compatible with 12MHz HSE + NAZE32_SP // Naze32 w/Sensor Platforms +} nazeHardwareRevision_e; + +extern uint8_t hardwareRevision; + +void updateHardwareRevision(void); +void detectHardwareRevision(void); + +void spiBusInit(void); diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c new file mode 100644 index 0000000000..be1c6ff53d --- /dev/null +++ b/src/main/target/ALIENFLIGHTF1/target.c @@ -0,0 +1,90 @@ + +#include +#include + +#include +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input + PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (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), // 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 or servo #1 (swap to servo if needed) + PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) + PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 + PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 + 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), // servo #4 + PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 + PWM6 | (MAP_TO_SERVO_OUTPUT << 8), + PWM7 | (MAP_TO_SERVO_OUTPUT << 8), + PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 + 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), // servo #4 + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 + { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 + { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 + { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 + { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 + { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 + { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 + { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 +}; + diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h new file mode 100644 index 0000000000..52048887f1 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF1/target.h @@ -0,0 +1,188 @@ +/* + * 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 "AFF1" // AlienFlight F1. +#define ALIENFLIGHT +#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP) +#define USE_HARDWARE_REVISION_DETECTION + +#define LED0 PB3 // PB3 (LED) +#define LED1 PB4 // PB4 (LED) + +#define BEEPER PA12 // PA12 (Beeper) + +#define BARO_XCLR_PIN PC13 +#define BARO_EOC_PIN PC14 + +#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO +#define INVERTER_USART USART2 + +#define USE_EXTI + +// SPI2 +// PB15 28 SPI2_MOSI +// PB14 27 SPI2_MISO +// PB13 26 SPI2_SCK +// PB12 25 SPI2_NSS + +#define USE_SPI +#define USE_SPI_DEVICE_2 + +#define NAZE_SPI_INSTANCE SPI2 +#define NAZE_SPI_CS_GPIO GPIOB +#define NAZE_SPI_CS_PIN PB12 +#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB + +// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: +#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO +#define M25P16_CS_PIN NAZE_SPI_CS_PIN +#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE + +#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL +#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO +#define MPU6500_CS_PIN NAZE_SPI_CS_PIN +#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE + + +#define USE_FLASHFS + +#define USE_FLASH_M25P16 + +#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC + +//#define DEBUG_MPU_DATA_READY_INTERRUPT +#define USE_MPU_DATA_READY_SIGNAL + +//#define DEBUG_MAG_DATA_READY_INTERRUPT +#define USE_MAG_DATA_READY_SIGNAL + +#define GYRO +#define USE_GYRO_MPU3050 +#define USE_GYRO_MPU6050 +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 + + +#define GYRO_MPU3050_ALIGN CW0_DEG +#define GYRO_MPU6050_ALIGN CW0_DEG +#define GYRO_MPU6500_ALIGN CW0_DEG + +#define ACC +#define USE_ACC_ADXL345 +#define USE_ACC_BMA280 +#define USE_ACC_MMA8452 +#define USE_ACC_MPU6050 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 + +#define ACC_ADXL345_ALIGN CW270_DEG +#define ACC_MPU6050_ALIGN CW0_DEG +#define ACC_MMA8452_ALIGN CW90_DEG +#define ACC_BMA280_ALIGN CW0_DEG +#define ACC_MPU6500_ALIGN CW0_DEG + +#define BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP085 +#define USE_BARO_BMP280 + +#define MAG +#define USE_MAG_HMC5883 + +#define MAG_HMC5883_ALIGN CW180_DEG + +#define SONAR +#define DISPLAY + +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define USE_SOFTSERIAL1 +#define USE_SOFTSERIAL2 +#define SERIAL_PORT_COUNT 5 + +#define SOFTSERIAL_1_TIMER TIM3 +#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 +#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 +#define SOFTSERIAL_2_TIMER TIM3 +#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 +#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 + +// USART3 only on NAZE32_SP - Flex Port +#define USART3_RX_PIN Pin_11 +#define USART3_TX_PIN Pin_10 +#define USART3_GPIO GPIOB +#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 +#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB + +#define USE_I2C +#define I2C_DEVICE (I2CDEV_2) + +// #define SOFT_I2C // enable to test software i2c +// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) +// #define SOFT_I2C_PB67 + +#define USE_ADC + +#define CURRENT_METER_ADC_GPIO GPIOB +#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 +#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 +#define VBAT_ADC_CHANNEL ADC_Channel_4 + +#define RSSI_ADC_GPIO GPIOA +#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 +#define RSSI_ADC_CHANNEL ADC_Channel_1 + +#define EXTERNAL1_ADC_GPIO GPIOA +#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 +#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 + + +#define LED_STRIP +#define LED_STRIP_TIMER TIM3 +#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 +#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER + +#undef GPS + +#define SPEKTRUM_BIND +// USART2, PA3 +#define BIND_PIN PA3 +#define BINDPLUG_PIN PB5 + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// alternative defaults for AlienFlight F1 target + +#define HARDWARE_BIND_PLUG + +// IO - assuming all IOs on 48pin package +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) + + +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) + +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB) + diff --git a/src/main/target/ALIENFLIGHTF1/target.mk b/src/main/target/ALIENFLIGHTF1/target.mk new file mode 100644 index 0000000000..a73a30ea5d --- /dev/null +++ b/src/main/target/ALIENFLIGHTF1/target.mk @@ -0,0 +1,21 @@ +FEATURES = ONBOARDFLASH HIGHEND +F1_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + hardware_revision.c \ No newline at end of file diff --git a/src/main/target/ALIENFLIGHTF3/target.mk b/src/main/target/ALIENFLIGHTF3/target.mk new file mode 100644 index 0000000000..8c802ecd82 --- /dev/null +++ b/src/main/target/ALIENFLIGHTF3/target.mk @@ -0,0 +1,12 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/compass_ak8963.c \ + hardware_revision.c \ + drivers/sonar_hcsr04.c diff --git a/src/main/target/ALIENFLIGHTF4/target.mk b/src/main/target/ALIENFLIGHTF4/target.mk new file mode 100644 index 0000000000..b3c825022c --- /dev/null +++ b/src/main/target/ALIENFLIGHTF4/target.mk @@ -0,0 +1,13 @@ +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_spi_mpu9250.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8963.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f4xx.c diff --git a/src/main/target/BLUEJAYF4/target.mk b/src/main/target/BLUEJAYF4/target.mk index 0438a2982f..d511472a59 100644 --- a/src/main/target/BLUEJAYF4/target.mk +++ b/src/main/target/BLUEJAYF4/target.mk @@ -1,5 +1,5 @@ F405_TARGETS += $(TARGET) -OPTIONS += SDCARD VCP +FEATURES += SDCARD VCP TARGET_SRC = \ drivers/accgyro_spi_mpu6500.c \ diff --git a/src/main/target/CC3D/target.mk b/src/main/target/CC3D/target.mk new file mode 100644 index 0000000000..86bdb5d5dc --- /dev/null +++ b/src/main/target/CC3D/target.mk @@ -0,0 +1,13 @@ +FEATURES = ONBOARDFLASH HIGHEND +F1_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c diff --git a/src/main/target/CHEBUZZF3/target.h b/src/main/target/CHEBUZZF3/target.h index 8ec0b6b6df..29d60c5491 100644 --- a/src/main/target/CHEBUZZF3/target.h +++ b/src/main/target/CHEBUZZF3/target.h @@ -14,13 +14,16 @@ * You should have received a copy of the GNU General Public License * along with Cleanflight. If not, see . */ - #pragma once #define TARGET_BOARD_IDENTIFIER "CHF3" // Chebuzz F3 #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_NONE +#ifndef STM32F3DISCOVERY +#define STM32F3DISCOVERY +#endif + #define LED0 PE8 // Blue LEDs - PE8/PE12 #define LED0_INVERTED #define LED1 PE10 // Orange LEDs - PE10/PE14 diff --git a/src/main/target/CHEBUZZF3/target.mk b/src/main/target/CHEBUZZF3/target.mk new file mode 100644 index 0000000000..8f0ecfe74b --- /dev/null +++ b/src/main/target/CHEBUZZF3/target.mk @@ -0,0 +1,18 @@ +FEATURES = VCP SDCARD +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/light_ws2811strip.c \ + drivers/accgyro_l3gd20.c \ + drivers/accgyro_lsm303dlhc.c \ + drivers/compass_hmc5883l.c \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_l3g4200d.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c diff --git a/src/main/target/CJMCU/target.h b/src/main/target/CJMCU/target.h index b4cfd23a9f..3b79c9754f 100644 --- a/src/main/target/CJMCU/target.h +++ b/src/main/target/CJMCU/target.h @@ -52,12 +52,12 @@ #define BIND_PIN PA3 - #if (FLASH_SIZE > 64) #define BLACKBOX #define USE_SERVOS #else // Since the CJMCU PCB has holes for 4 motors in each corner we can save same flash space by disabling support for other mixers. +#undef USE_CLI #define USE_QUAD_MIXER_ONLY #define SKIP_TASK_STATISTICS #define SKIP_CLI_COMMAND_HELP diff --git a/src/main/target/CJMCU/target.mk b/src/main/target/CJMCU/target.mk new file mode 100644 index 0000000000..64a0ebfc02 --- /dev/null +++ b/src/main/target/CJMCU/target.mk @@ -0,0 +1,11 @@ +FLASH_SIZE = 64 +F1_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/compass_hmc5883l.c \ + hardware_revision.c \ + flight/gtune.c \ + blackbox/blackbox.c \ + blackbox/blackbox_io.c diff --git a/src/main/target/COLIBRI_RACE/target.mk b/src/main/target/COLIBRI_RACE/target.mk new file mode 100644 index 0000000000..e029261d0b --- /dev/null +++ b/src/main/target/COLIBRI_RACE/target.mk @@ -0,0 +1,17 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + io/i2c_bst.c \ + drivers/bus_bst_stm32f30x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8963.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c diff --git a/src/main/target/DOGE/target.mk b/src/main/target/DOGE/target.mk new file mode 100644 index 0000000000..47c076c140 --- /dev/null +++ b/src/main/target/DOGE/target.mk @@ -0,0 +1,15 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_spi_bmp280.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c + + + + diff --git a/src/main/target/EUSTM32F103RC/target.mk b/src/main/target/EUSTM32F103RC/target.mk new file mode 100644 index 0000000000..1801357a01 --- /dev/null +++ b/src/main/target/EUSTM32F103RC/target.mk @@ -0,0 +1,23 @@ +FEATURES = ONBOARDFLASH HIGHEND +F1_TARGETS += $(TARGET) + +DEVICE_FLAGS = -DSTM32F10X_HD + +TARGET_SRC = \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c diff --git a/src/main/target/FURYF3/target.mk b/src/main/target/FURYF3/target.mk new file mode 100644 index 0000000000..c947d79f2e --- /dev/null +++ b/src/main/target/FURYF3/target.mk @@ -0,0 +1,15 @@ +FEATURES = VCP SDCARD ONBOARDFLASH +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/sonar_hcsr04.c \ + drivers/serial_softserial.c + diff --git a/src/main/target/FURYF4/target.mk b/src/main/target/FURYF4/target.mk new file mode 100644 index 0000000000..c6c3a15733 --- /dev/null +++ b/src/main/target/FURYF4/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP + +TARGET_SRC = \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_ms5611.c diff --git a/src/main/target/IRCFUSIONF3/target.mk b/src/main/target/IRCFUSIONF3/target.mk new file mode 100644 index 0000000000..c58c12fbd6 --- /dev/null +++ b/src/main/target/IRCFUSIONF3/target.mk @@ -0,0 +1,8 @@ +FEATURES = VCP ONBOARDFLASH +F3_TARGETS += $(TARGET) +TARGET_FLAGS = -DSPRACINGF3 + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_bmp085.c \ No newline at end of file diff --git a/src/main/target/KISSFC/target.mk b/src/main/target/KISSFC/target.mk new file mode 100644 index 0000000000..6e198e8559 --- /dev/null +++ b/src/main/target/KISSFC/target.mk @@ -0,0 +1,10 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/display_ug2864hsweg01.c \ + drivers/accgyro_mpu6050.c + + + diff --git a/src/main/target/LUX_RACE/target.mk b/src/main/target/LUX_RACE/target.mk new file mode 100644 index 0000000000..1862327175 --- /dev/null +++ b/src/main/target/LUX_RACE/target.mk @@ -0,0 +1,14 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c + + + + diff --git a/src/main/target/MOTOLAB/target.mk b/src/main/target/MOTOLAB/target.mk new file mode 100644 index 0000000000..f2d22aa0ea --- /dev/null +++ b/src/main/target/MOTOLAB/target.mk @@ -0,0 +1,15 @@ +FEATURES = VCP ONBOARDFLASH +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c + + + diff --git a/src/main/target/NAZE/target.mk b/src/main/target/NAZE/target.mk new file mode 100644 index 0000000000..a73a30ea5d --- /dev/null +++ b/src/main/target/NAZE/target.mk @@ -0,0 +1,21 @@ +FEATURES = ONBOARDFLASH HIGHEND +F1_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ + hardware_revision.c \ No newline at end of file diff --git a/src/main/target/NAZE32PRO/target.mk b/src/main/target/NAZE32PRO/target.mk new file mode 100644 index 0000000000..0a6aeb1210 --- /dev/null +++ b/src/main/target/NAZE32PRO/target.mk @@ -0,0 +1,4 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ No newline at end of file diff --git a/src/main/target/OLIMEXINO/target.mk b/src/main/target/OLIMEXINO/target.mk new file mode 100644 index 0000000000..bda4796ed1 --- /dev/null +++ b/src/main/target/OLIMEXINO/target.mk @@ -0,0 +1,12 @@ +FEATURES = HIGHEND +F1_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c \ No newline at end of file diff --git a/src/main/target/PORT103R/target.mk b/src/main/target/PORT103R/target.mk new file mode 100644 index 0000000000..1801357a01 --- /dev/null +++ b/src/main/target/PORT103R/target.mk @@ -0,0 +1,23 @@ +FEATURES = ONBOARDFLASH HIGHEND +F1_TARGETS += $(TARGET) + +DEVICE_FLAGS = -DSTM32F10X_HD + +TARGET_SRC = \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_l3g4200d.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/barometer_ms5611.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f10x.c \ + drivers/sonar_hcsr04.c diff --git a/src/main/target/REVO/target.mk b/src/main/target/REVO/target.mk new file mode 100644 index 0000000000..148ad83183 --- /dev/null +++ b/src/main/target/REVO/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +FEATURES += VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_spi_mpu6000.c \ + drivers/barometer_ms5611.c \ + drivers/compass_hmc5883l.c + diff --git a/src/main/target/RMDO/target.mk b/src/main/target/RMDO/target.mk new file mode 100644 index 0000000000..c3796b11d8 --- /dev/null +++ b/src/main/target/RMDO/target.mk @@ -0,0 +1,13 @@ +FEATURES = VCP ONBOARDFLASH +F3_TARGETS += $(TARGET) +TARGET_FLAGS = -DSPRACINGF3 + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_bmp280.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c + diff --git a/src/main/target/SINGULARITY/target.mk b/src/main/target/SINGULARITY/target.mk new file mode 100644 index 0000000000..300133e12a --- /dev/null +++ b/src/main/target/SINGULARITY/target.mk @@ -0,0 +1,12 @@ +FEATURES = VCP ONBOARDFLASH +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/vtx_rtc6705.c + + diff --git a/src/main/target/SPARKY/target.mk b/src/main/target/SPARKY/target.mk new file mode 100644 index 0000000000..f02f23ce1b --- /dev/null +++ b/src/main/target/SPARKY/target.mk @@ -0,0 +1,14 @@ +FEATURES = VCP +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c + + + diff --git a/src/main/target/SPRACINGF3/target.mk b/src/main/target/SPRACINGF3/target.mk new file mode 100644 index 0000000000..747e55ea36 --- /dev/null +++ b/src/main/target/SPRACINGF3/target.mk @@ -0,0 +1,15 @@ +FEATURES = VCP ONBOARDFLASH +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6050.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp085.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c diff --git a/src/main/target/SPRACINGF3EVO/target.mk b/src/main/target/SPRACINGF3EVO/target.mk new file mode 100644 index 0000000000..ef081538ba --- /dev/null +++ b/src/main/target/SPRACINGF3EVO/target.mk @@ -0,0 +1,16 @@ +FEATURES = VCP SDCARD +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8963.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_usb_vcp.c \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/transponder_ir.c + diff --git a/src/main/target/SPRACINGF3MINI/target.mk b/src/main/target/SPRACINGF3MINI/target.mk new file mode 100644 index 0000000000..4906d10d42 --- /dev/null +++ b/src/main/target/SPRACINGF3MINI/target.mk @@ -0,0 +1,19 @@ +FEATURES = VCP SDCARD +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + 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 \ + drivers/transponder_ir.c \ + drivers/transponder_ir_stm32f30x.c \ + io/transponder_ir.c + diff --git a/src/main/target/STM32F3DISCOVERY/target.mk b/src/main/target/STM32F3DISCOVERY/target.mk new file mode 100644 index 0000000000..8f0ecfe74b --- /dev/null +++ b/src/main/target/STM32F3DISCOVERY/target.mk @@ -0,0 +1,18 @@ +FEATURES = VCP SDCARD +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/light_ws2811strip.c \ + drivers/accgyro_l3gd20.c \ + drivers/accgyro_lsm303dlhc.c \ + drivers/compass_hmc5883l.c \ + drivers/accgyro_adxl345.c \ + drivers/accgyro_bma280.c \ + drivers/accgyro_mma845x.c \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu3050.c \ + drivers/accgyro_mpu6050.c \ + drivers/accgyro_l3g4200d.c \ + drivers/barometer_ms5611.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c diff --git a/src/main/target/stm32_flash_f405_bl.ld b/src/main/target/stm32_flash_f405_opbl.ld similarity index 100% rename from src/main/target/stm32_flash_f405_bl.ld rename to src/main/target/stm32_flash_f405_opbl.ld diff --git a/src/main/target/stm32_flash_f411_bl.ld b/src/main/target/stm32_flash_f411_opbl.ld similarity index 100% rename from src/main/target/stm32_flash_f411_bl.ld rename to src/main/target/stm32_flash_f411_opbl.ld From 2335fc4b920765f90c51b4cd87252427302b5d24 Mon Sep 17 00:00:00 2001 From: blckmn Date: Mon, 13 Jun 2016 21:55:14 +1000 Subject: [PATCH 05/13] Added scan for VALID_TARGETS so that the all_targets can work? --- Makefile | 26 ++++++-------------------- 1 file changed, 6 insertions(+), 20 deletions(-) diff --git a/Makefile b/Makefile index 8d1c95b4c0..ad3379a1d8 100644 --- a/Makefile +++ b/Makefile @@ -54,20 +54,19 @@ INCLUDE_DIRS = $(SRC_DIR) \ LINKER_DIR = $(ROOT)/src/main/target # default xtal value for F4 targets -HSE_VALUE = 8000000 +HSE_VALUE = 8000000 # used for turning on features like VCP and SDCARD -FEATURES = - -F405_TARGETS = -F411_TARGETS = +FEATURES = # silently ignore if the file is not present. Allows for target specific. -include $(ROOT)/src/main/target/$(TARGET)/target.mk -F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) +F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) -VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) +#VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) +VALID_TARGETS = $(notdir $(wildcard $(ROOT)/src/main/target/*)) +VALID_TARGETS := $(filter-out $(notdir $(wildcard $(ROOT)/src/main/target/*.*)), $(VALID_TARGETS)) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) @@ -314,19 +313,6 @@ endif TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) TARGET_DIR_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), $(NAZE_TARGETS))) -# VARIANTS of NAZE -TARGET_FLAGS := $(TARGET_FLAGS) -DNAZE -D$(TARGET) -TARGET_DIR = $(ROOT)/src/main/target/NAZE -endif - ifeq ($(OPBL),yes) TARGET_FLAGS := -DOPBL $(TARGET_FLAGS) ifeq ($(TARGET), $(filter $(TARGET),$(F405_TARGETS))) From e17f5a4ea3e7c368f9a451bc3bb8dd0759e71792 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 03:00:24 +1000 Subject: [PATCH 06/13] Comment cleaning --- Makefile | 18 +++++++++--------- 1 file changed, 9 insertions(+), 9 deletions(-) diff --git a/Makefile b/Makefile index ad3379a1d8..fcdabb51fc 100644 --- a/Makefile +++ b/Makefile @@ -161,9 +161,9 @@ 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) -## End F3 targets -## -## Start F4 targets +# End F3 targets +# +# Start F4 targets else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) #STDPERIPH @@ -255,9 +255,9 @@ endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) TARGET_FLAGS = -D$(TARGET) -## End F4 targets -## -## Start F1 targets +# End F4 targets +# +# Start F1 targets else STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver @@ -302,9 +302,9 @@ endif DEVICE_FLAGS += -DSTM32F10X endif -## -## End F1 targets -## +# +# End F1 targets +# ifneq ($(FLASH_SIZE),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) From 4e12344aa6999e080c8af8ac9fedd82ca9eea962 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 03:45:32 +1000 Subject: [PATCH 07/13] Updated all_targets to build both binary and hex Added clean_all_targets goal Removed ## above the line --- Makefile | 61 +++++++++++++++++------------ src/main/target/CC3D/target.mk | 2 +- src/main/target/NAZE32PRO/target.mk | 2 +- 3 files changed, 37 insertions(+), 28 deletions(-) diff --git a/Makefile b/Makefile index fcdabb51fc..463fd8bc74 100644 --- a/Makefile +++ b/Makefile @@ -65,11 +65,16 @@ FEATURES = F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) -VALID_TARGETS = $(notdir $(wildcard $(ROOT)/src/main/target/*)) -VALID_TARGETS := $(filter-out $(notdir $(wildcard $(ROOT)/src/main/target/*.*)), $(VALID_TARGETS)) +VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) +VALID_TARGETS := $(subst ./src/main/target/,, $(VALID_TARGETS)) +VALID_TARGETS := $(subst /,, $(VALID_TARGETS)) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) -$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS)) +$(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) +endif + +ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)),) +$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, or F411. Have you prepared a valid target.mk?) endif 128K_TARGETS = $(F1_TARGETS) @@ -77,7 +82,7 @@ endif 512K_TARGETS = $(F411_TARGETS) 1024K_TARGETS = $(F405_TARGETS) -# Configure default flash sizes for the targets (largest size specified gets hit first) +# Configure default flash sizes for the targets (largest size specified gets hit first) if flash not specified already. ifeq ($(FLASH_SIZE),) ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS))) FLASH_SIZE = 1024 @@ -479,7 +484,6 @@ STM32F4xx_COMMON_SRC = \ drivers/dma_stm32f4xx.c # check if target.mk supplied -ifneq ($(TARGET_SRC),) ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC) @@ -514,16 +518,7 @@ endif ifneq ($(filter VCP,$(FEATURES)),) TARGET_SRC += $(VCP_SRC) endif - -# end target.mk supplied - now know the source was supplied above. -else -ifeq ($($(TARGET)_SRC),) -$(error Target source files not found. Have you prepared a target.mk?) -else -TARGET_SRC = $($(TARGET)_SRC) -endif # end target specific make file checks -endif # Search path and source files for the ST stdperiph library @@ -645,37 +640,51 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S @$(CC) -c -o $@ $(ASFLAGS) $< -## all : default task; compile C code, build firmware +## all : default task; compile C code, build firmware all: binary -## all_targets : build all valid target platforms +## all_targets : build all valid target platforms all_targets: for build_target in $(VALID_TARGETS); do \ + echo "" && \ echo "Building $$build_target" && \ - $(MAKE) clean && \ - $(MAKE) -j TARGET=$$build_target || \ + $(MAKE) -j TARGET=$$build_target clean && \ + $(MAKE) -j binary hex TARGET=$$build_target || \ break; \ echo "Building $$build_target succeeded."; \ done -## clean : clean up all temporary / machine-generated files +## clean : clean up all temporary / machine-generated files clean: rm -f $(CLEAN_ARTIFACTS) rm -rf $(OBJECT_DIR)/$(TARGET) + +## clean_test : clean up all temporary / machine-generated files (tests) +clean_test: cd src/test && $(MAKE) clean || true +## clean_all_targets : clean all valid target platforms +clean_all_targets: + for clean_target in $(VALID_TARGETS); do \ + echo "" && \ + echo "Cleaning $$clean_target" && \ + $(MAKE) -j TARGET=$$clean_target clean || \ + break; \ + echo "Cleaning $$clean_target succeeded."; \ + done + flash_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon echo -n 'R' >$(SERIAL_DEVICE) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) -## flash : flash firmware (.hex) onto flight controller +## flash : flash firmware (.hex) onto flight controller flash: flash_$(TARGET) st-flash_$(TARGET): $(TARGET_BIN) st-flash --reset write $< 0x08000000 -## st-flash : flash firmware (.bin) onto flight controller +## st-flash : flash firmware (.bin) onto flight controller st-flash: st-flash_$(TARGET) binary: $(TARGET_BIN) @@ -685,17 +694,17 @@ unbrick_$(TARGET): $(TARGET_HEX) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) -## unbrick : unbrick flight controller +## unbrick : unbrick flight controller unbrick: unbrick_$(TARGET) -## cppcheck : run static analysis on C source code +## cppcheck : run static analysis on C source code cppcheck: $(CSOURCES) $(CPPCHECK) cppcheck-result.xml: $(CSOURCES) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml -## help : print this help message and exit +## help : print this help message and exit help: Makefile @echo "" @echo "Makefile for the $(FORKNAME) firmware" @@ -707,11 +716,11 @@ help: Makefile @echo "" @sed -n 's/^## //p' $< -## targets : print a list of all valid target platforms (for consumption by scripts) +## targets : print a list of all valid target platforms (for consumption by scripts) targets: @echo $(VALID_TARGETS) -## test : run the cleanflight test suite +## test : run the cleanflight test suite test: cd src/test && $(MAKE) test || true diff --git a/src/main/target/CC3D/target.mk b/src/main/target/CC3D/target.mk index 86bdb5d5dc..238eb49068 100644 --- a/src/main/target/CC3D/target.mk +++ b/src/main/target/CC3D/target.mk @@ -1,4 +1,4 @@ -FEATURES = ONBOARDFLASH HIGHEND +FEATURES = ONBOARDFLASH HIGHEND VCP F1_TARGETS += $(TARGET) TARGET_SRC = \ diff --git a/src/main/target/NAZE32PRO/target.mk b/src/main/target/NAZE32PRO/target.mk index 0a6aeb1210..7239854ce6 100644 --- a/src/main/target/NAZE32PRO/target.mk +++ b/src/main/target/NAZE32PRO/target.mk @@ -1,4 +1,4 @@ FEATURES = VCP F3_TARGETS += $(TARGET) -TARGET_SRC = \ No newline at end of file +TARGET_SRC = \ \ No newline at end of file From 6a7976d258bb80bf89489a8b7126443012a05f38 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 03:49:15 +1000 Subject: [PATCH 08/13] Enforced the sorting of the valid targets (for use in make targets) --- Makefile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/Makefile b/Makefile index 463fd8bc74..0ecfd8498d 100644 --- a/Makefile +++ b/Makefile @@ -66,8 +66,8 @@ F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst ./src/main/target/,, $(VALID_TARGETS)) -VALID_TARGETS := $(subst /,, $(VALID_TARGETS)) +VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(sort $(VALID_TARGETS)) ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) From 80f1566af0cfdfeb4ffd5018367cf873bbf653f4 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 11:26:09 +1000 Subject: [PATCH 09/13] Added dynamic support for OPBL targets, and also alternate target names that are based on an existing target. --- Makefile | 57 ++++-- .../target/ALIENFLIGHTF1/hardware_revision.c | 111 ----------- .../target/ALIENFLIGHTF1/hardware_revision.h | 30 --- src/main/target/ALIENFLIGHTF1/target.c | 90 --------- src/main/target/ALIENFLIGHTF1/target.h | 188 ------------------ src/main/target/ALIENFLIGHTF1/target.mk | 21 -- src/main/target/CC3D/CC3D_OPBL.mk | 0 src/main/target/NAZE/ALIENFLIGHTF1.mk | 0 src/main/target/REVO/REVO_OPBL.mk | 0 9 files changed, 37 insertions(+), 460 deletions(-) delete mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.c delete mode 100644 src/main/target/ALIENFLIGHTF1/hardware_revision.h delete mode 100644 src/main/target/ALIENFLIGHTF1/target.c delete mode 100644 src/main/target/ALIENFLIGHTF1/target.h delete mode 100644 src/main/target/ALIENFLIGHTF1/target.mk create mode 100644 src/main/target/CC3D/CC3D_OPBL.mk create mode 100644 src/main/target/NAZE/ALIENFLIGHTF1.mk create mode 100644 src/main/target/REVO/REVO_OPBL.mk diff --git a/Makefile b/Makefile index 0ecfd8498d..f0539a31e3 100644 --- a/Makefile +++ b/Makefile @@ -59,16 +59,31 @@ HSE_VALUE = 8000000 # used for turning on features like VCP and SDCARD FEATURES = -# silently ignore if the file is not present. Allows for target specific. --include $(ROOT)/src/main/target/$(TARGET)/target.mk - -F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) +ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) +OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) +VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) +ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) +BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) +-include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk +else +BASE_TARGET := $(TARGET) +endif + +ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET)) +OPBL = yes +endif + +# silently ignore if the file is not present. Allows for target specific. +-include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk + +F4_TARGETS = $(F405_TARGETS) $(F411_TARGETS) + ifeq ($(filter $(TARGET),$(VALID_TARGETS)),) $(error Target '$(TARGET)' is not valid, must be one of $(VALID_TARGETS). Have you prepared a valid target.mk?) endif @@ -100,9 +115,9 @@ 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 +STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S else -STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S +STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S endif REVISION = $(shell git log -1 --format="%h") @@ -122,7 +137,6 @@ FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) CSOURCES := $(shell find $(SRC_DIR) -name '*.c') - ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) # F3 TARGETS @@ -304,18 +318,21 @@ TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS) ifeq ($(DEVICE_FLAGS),) DEVICE_FLAGS = -DSTM32F10X_MD endif -DEVICE_FLAGS += -DSTM32F10X +DEVICE_FLAGS += -DSTM32F10X endif # # End F1 targets # - -ifneq ($(FLASH_SIZE),) -DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) +ifneq ($(BASE_TARGET), $(TARGET)) +TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET) endif -TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) +ifneq ($(FLASH_SIZE),) +DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) +endif + +TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) ifeq ($(OPBL),yes) @@ -330,6 +347,8 @@ else ifeq ($(TARGET), $(filter $(TARGET),$(F1_TARGETS))) LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k_opbl.ld endif .DEFAULT_GOAL := binary +else +.DEFAULT_GOAL := hex endif INCLUDE_DIRS := $(INCLUDE_DIRS) \ @@ -486,7 +505,6 @@ STM32F4xx_COMMON_SRC = \ # check if target.mk supplied ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC) - else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) TARGET_SRC := $(STM32F30x_COMMON_SRC) $(TARGET_SRC) else ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) @@ -641,10 +659,7 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S ## all : default task; compile C code, build firmware -all: binary - -## all_targets : build all valid target platforms -all_targets: +all: for build_target in $(VALID_TARGETS); do \ echo "" && \ echo "Building $$build_target" && \ @@ -664,7 +679,7 @@ clean_test: cd src/test && $(MAKE) clean || true ## clean_all_targets : clean all valid target platforms -clean_all_targets: +clean_all: for clean_target in $(VALID_TARGETS); do \ echo "" && \ echo "Cleaning $$clean_target" && \ @@ -718,7 +733,9 @@ help: Makefile ## targets : print a list of all valid target platforms (for consumption by scripts) targets: - @echo $(VALID_TARGETS) + @echo "Valid targets: $(VALID_TARGETS)" + @echo "Target: $(TARGET)" + @echo "Base target: $(BASE_TARGET)" ## test : run the cleanflight test suite test: diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.c b/src/main/target/ALIENFLIGHTF1/hardware_revision.c deleted file mode 100644 index dae3698442..0000000000 --- a/src/main/target/ALIENFLIGHTF1/hardware_revision.c +++ /dev/null @@ -1,111 +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 . - */ - -#include -#include -#include - -#include "platform.h" - -#include "build_config.h" - -#include "drivers/system.h" -#include "drivers/bus_spi.h" -#include "drivers/sensor.h" -#include "drivers/exti.h" -#include "drivers/accgyro.h" -#include "drivers/accgyro_mpu.h" -#include "drivers/accgyro_mpu6500.h" - -#include "hardware_revision.h" - -static const char * const hardwareRevisionNames[] = { - "Unknown", - "Naze 32", - "Naze32 rev.5", - "Naze32 SP" -}; - -uint8_t hardwareRevision = UNKNOWN; - -void detectHardwareRevision(void) -{ - if (hse_value == 8000000) - hardwareRevision = NAZE32; - else if (hse_value == 12000000) - hardwareRevision = NAZE32_REV5; -} - -#ifdef USE_SPI - -#define DISABLE_SPI_CS IOLo(nazeSpiCsPin) -#define ENABLE_SPI_CS IOHi(nazeSpiCsPin) - -#define SPI_DEVICE_NONE (0) -#define SPI_DEVICE_FLASH (1) -#define SPI_DEVICE_MPU (2) - -#define M25P16_INSTRUCTION_RDID 0x9F -#define FLASH_M25P16_ID (0x202015) - -static IO_t nazeSpiCsPin = IO_NONE; - -uint8_t detectSpiDevice(void) -{ -#ifdef NAZE_SPI_CS_PIN - nazeSpiCsPin = IOGetByTag(IO_TAG(NAZE_SPI_CS_PIN)); -#endif - - uint8_t out[] = { M25P16_INSTRUCTION_RDID, 0, 0, 0 }; - uint8_t in[4]; - uint32_t flash_id; - - // try autodetect flash chip - delay(50); // short delay required after initialisation of SPI device instance. - ENABLE_SPI_CS; - spiTransfer(NAZE_SPI_INSTANCE, in, out, sizeof(out)); - DISABLE_SPI_CS; - - flash_id = in[1] << 16 | in[2] << 8 | in[3]; - if (flash_id == FLASH_M25P16_ID) - return SPI_DEVICE_FLASH; - - - // try autodetect MPU - delay(50); - ENABLE_SPI_CS; - spiTransferByte(NAZE_SPI_INSTANCE, MPU_RA_WHO_AM_I | MPU6500_BIT_RESET); - in[0] = spiTransferByte(NAZE_SPI_INSTANCE, 0xff); - DISABLE_SPI_CS; - - if (in[0] == MPU6500_WHO_AM_I_CONST) - return SPI_DEVICE_MPU; - - return SPI_DEVICE_NONE; -} - -#endif - -void updateHardwareRevision(void) -{ -#ifdef USE_SPI - uint8_t detectedSpiDevice = detectSpiDevice(); - - if (detectedSpiDevice == SPI_DEVICE_MPU && hardwareRevision == NAZE32_REV5) - hardwareRevision = NAZE32_SP; -#endif -} diff --git a/src/main/target/ALIENFLIGHTF1/hardware_revision.h b/src/main/target/ALIENFLIGHTF1/hardware_revision.h deleted file mode 100644 index 9f663bb6c2..0000000000 --- a/src/main/target/ALIENFLIGHTF1/hardware_revision.h +++ /dev/null @@ -1,30 +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 . - */ - -typedef enum nazeHardwareRevision_t { - UNKNOWN = 0, - NAZE32, // Naze32 and compatible with 8MHz HSE - NAZE32_REV5, // Naze32 and compatible with 12MHz HSE - NAZE32_SP // Naze32 w/Sensor Platforms -} nazeHardwareRevision_e; - -extern uint8_t hardwareRevision; - -void updateHardwareRevision(void); -void detectHardwareRevision(void); - -void spiBusInit(void); diff --git a/src/main/target/ALIENFLIGHTF1/target.c b/src/main/target/ALIENFLIGHTF1/target.c deleted file mode 100644 index be1c6ff53d..0000000000 --- a/src/main/target/ALIENFLIGHTF1/target.c +++ /dev/null @@ -1,90 +0,0 @@ - -#include -#include - -#include -#include "drivers/pwm_mapping.h" - -const uint16_t multiPPM[] = { - PWM1 | (MAP_TO_PPM_INPUT << 8), // PPM input - PWM9 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // Swap to servo if needed - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM14 | (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), // 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 or servo #1 (swap to servo if needed) - PWM10 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #2 or servo #2 (swap to servo if needed) - PWM11 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #1 or #3 - PWM12 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM13 | (MAP_TO_MOTOR_OUTPUT << 8), - PWM14 | (MAP_TO_MOTOR_OUTPUT << 8), // motor #4 or #6 - 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), // servo #4 - PWM5 | (MAP_TO_SERVO_OUTPUT << 8), // servo #5 - PWM6 | (MAP_TO_SERVO_OUTPUT << 8), - PWM7 | (MAP_TO_SERVO_OUTPUT << 8), - PWM8 | (MAP_TO_SERVO_OUTPUT << 8), // servo #8 - 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), // servo #4 - 0xFFFF -}; - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM2, GPIOA, Pin_0, TIM_Channel_1, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM1 - RC1 - { TIM2, GPIOA, Pin_1, TIM_Channel_2, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM2 - RC2 - { TIM2, GPIOA, Pin_2, TIM_Channel_3, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM3 - RC3 - { TIM2, GPIOA, Pin_3, TIM_Channel_4, TIM2_IRQn, 0, Mode_IPD, 0}, // PWM4 - RC4 - { TIM3, GPIOA, Pin_6, TIM_Channel_1, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM5 - RC5 - { TIM3, GPIOA, Pin_7, TIM_Channel_2, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM6 - RC6 - { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM7 - RC7 - { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 0, Mode_IPD, 0}, // PWM8 - RC8 - { TIM1, GPIOA, Pin_8, TIM_Channel_1, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM9 - OUT1 - { TIM1, GPIOA, Pin_11,TIM_Channel_4, TIM1_CC_IRQn, 1, Mode_IPD, 0}, // PWM10 - OUT2 - { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM11 - OUT3 - { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM12 - OUT4 - { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 0, Mode_IPD, 0}, // PWM13 - OUT5 - { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 0, Mode_IPD, 0} // PWM14 - OUT6 -}; - diff --git a/src/main/target/ALIENFLIGHTF1/target.h b/src/main/target/ALIENFLIGHTF1/target.h deleted file mode 100644 index 52048887f1..0000000000 --- a/src/main/target/ALIENFLIGHTF1/target.h +++ /dev/null @@ -1,188 +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 "AFF1" // AlienFlight F1. -#define ALIENFLIGHT -#define DEFAULT_FEATURES (FEATURE_RX_SERIAL | FEATURE_MOTOR_STOP) -#define USE_HARDWARE_REVISION_DETECTION - -#define LED0 PB3 // PB3 (LED) -#define LED1 PB4 // PB4 (LED) - -#define BEEPER PA12 // PA12 (Beeper) - -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_PIN PC14 - -#define INVERTER PB2 // PB2 (BOOT1) abused as inverter select GPIO -#define INVERTER_USART USART2 - -#define USE_EXTI - -// SPI2 -// PB15 28 SPI2_MOSI -// PB14 27 SPI2_MISO -// PB13 26 SPI2_SCK -// PB12 25 SPI2_NSS - -#define USE_SPI -#define USE_SPI_DEVICE_2 - -#define NAZE_SPI_INSTANCE SPI2 -#define NAZE_SPI_CS_GPIO GPIOB -#define NAZE_SPI_CS_PIN PB12 -#define NAZE_CS_GPIO_CLK_PERIPHERAL RCC_APB2Periph_GPIOB - -// We either have this 16mbit flash chip on SPI or the MPU6500 acc/gyro depending on board revision: -#define M25P16_CS_GPIO NAZE_SPI_CS_GPIO -#define M25P16_CS_PIN NAZE_SPI_CS_PIN -#define M25P16_SPI_INSTANCE NAZE_SPI_INSTANCE - -#define MPU6500_CS_GPIO_CLK_PERIPHERAL NAZE_CS_GPIO_CLK_PERIPHERAL -#define MPU6500_CS_GPIO NAZE_SPI_CS_GPIO -#define MPU6500_CS_PIN NAZE_SPI_CS_PIN -#define MPU6500_SPI_INSTANCE NAZE_SPI_INSTANCE - - -#define USE_FLASHFS - -#define USE_FLASH_M25P16 - -#define EXTI_CALLBACK_HANDLER_COUNT 3 // MPU data ready, MAG data ready, BMP085 EOC - -//#define DEBUG_MPU_DATA_READY_INTERRUPT -#define USE_MPU_DATA_READY_SIGNAL - -//#define DEBUG_MAG_DATA_READY_INTERRUPT -#define USE_MAG_DATA_READY_SIGNAL - -#define GYRO -#define USE_GYRO_MPU3050 -#define USE_GYRO_MPU6050 -#define USE_GYRO_MPU6500 -#define USE_GYRO_SPI_MPU6500 - - -#define GYRO_MPU3050_ALIGN CW0_DEG -#define GYRO_MPU6050_ALIGN CW0_DEG -#define GYRO_MPU6500_ALIGN CW0_DEG - -#define ACC -#define USE_ACC_ADXL345 -#define USE_ACC_BMA280 -#define USE_ACC_MMA8452 -#define USE_ACC_MPU6050 -#define USE_ACC_MPU6500 -#define USE_ACC_SPI_MPU6500 - -#define ACC_ADXL345_ALIGN CW270_DEG -#define ACC_MPU6050_ALIGN CW0_DEG -#define ACC_MMA8452_ALIGN CW90_DEG -#define ACC_BMA280_ALIGN CW0_DEG -#define ACC_MPU6500_ALIGN CW0_DEG - -#define BARO -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 - -#define MAG -#define USE_MAG_HMC5883 - -#define MAG_HMC5883_ALIGN CW180_DEG - -#define SONAR -#define DISPLAY - -#define USE_USART1 -#define USE_USART2 -#define USE_USART3 -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 -#define SERIAL_PORT_COUNT 5 - -#define SOFTSERIAL_1_TIMER TIM3 -#define SOFTSERIAL_1_TIMER_RX_HARDWARE 4 // PWM 5 -#define SOFTSERIAL_1_TIMER_TX_HARDWARE 5 // PWM 6 -#define SOFTSERIAL_2_TIMER TIM3 -#define SOFTSERIAL_2_TIMER_RX_HARDWARE 6 // PWM 7 -#define SOFTSERIAL_2_TIMER_TX_HARDWARE 7 // PWM 8 - -// USART3 only on NAZE32_SP - Flex Port -#define USART3_RX_PIN Pin_11 -#define USART3_TX_PIN Pin_10 -#define USART3_GPIO GPIOB -#define USART3_APB1_PERIPHERALS RCC_APB1Periph_USART3 -#define USART3_APB2_PERIPHERALS RCC_APB2Periph_GPIOB - -#define USE_I2C -#define I2C_DEVICE (I2CDEV_2) - -// #define SOFT_I2C // enable to test software i2c -// #define SOFT_I2C_PB1011 // If SOFT_I2C is enabled above, need to define pinout as well (I2C1 = PB67, I2C2 = PB1011) -// #define SOFT_I2C_PB67 - -#define USE_ADC - -#define CURRENT_METER_ADC_GPIO GPIOB -#define CURRENT_METER_ADC_GPIO_PIN GPIO_Pin_1 -#define CURRENT_METER_ADC_CHANNEL ADC_Channel_9 - -#define VBAT_ADC_GPIO GPIOA -#define VBAT_ADC_GPIO_PIN GPIO_Pin_4 -#define VBAT_ADC_CHANNEL ADC_Channel_4 - -#define RSSI_ADC_GPIO GPIOA -#define RSSI_ADC_GPIO_PIN GPIO_Pin_1 -#define RSSI_ADC_CHANNEL ADC_Channel_1 - -#define EXTERNAL1_ADC_GPIO GPIOA -#define EXTERNAL1_ADC_GPIO_PIN GPIO_Pin_5 -#define EXTERNAL1_ADC_CHANNEL ADC_Channel_5 - - -#define LED_STRIP -#define LED_STRIP_TIMER TIM3 -#define WS2811_DMA_TC_FLAG DMA1_FLAG_TC6 -#define WS2811_DMA_HANDLER_IDENTIFER DMA1_CH6_HANDLER - -#undef GPS - -#define SPEKTRUM_BIND -// USART2, PA3 -#define BIND_PIN PA3 -#define BINDPLUG_PIN PB5 - -#define USE_SERIAL_4WAY_BLHELI_INTERFACE - -// alternative defaults for AlienFlight F1 target - -#define HARDWARE_BIND_PLUG - -// IO - assuming all IOs on 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) - - -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4)) - -#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM2 | RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) -#define TIMER_APB2_PERIPHERALS (RCC_APB2Periph_TIM1 | RCC_APB2Periph_GPIOA | RCC_APB2Periph_GPIOB) - diff --git a/src/main/target/ALIENFLIGHTF1/target.mk b/src/main/target/ALIENFLIGHTF1/target.mk deleted file mode 100644 index a73a30ea5d..0000000000 --- a/src/main/target/ALIENFLIGHTF1/target.mk +++ /dev/null @@ -1,21 +0,0 @@ -FEATURES = ONBOARDFLASH HIGHEND -F1_TARGETS += $(TARGET) - -TARGET_SRC = \ - drivers/accgyro_adxl345.c \ - drivers/accgyro_bma280.c \ - drivers/accgyro_l3g4200d.c \ - drivers/accgyro_mma845x.c \ - drivers/accgyro_mpu.c \ - drivers/accgyro_mpu3050.c \ - drivers/accgyro_mpu6050.c \ - drivers/accgyro_mpu6500.c \ - drivers/accgyro_spi_mpu6500.c \ - drivers/barometer_bmp085.c \ - drivers/barometer_bmp280.c \ - drivers/barometer_ms5611.c \ - drivers/compass_hmc5883l.c \ - drivers/light_ws2811strip.c \ - drivers/light_ws2811strip_stm32f10x.c \ - drivers/sonar_hcsr04.c \ - hardware_revision.c \ No newline at end of file diff --git a/src/main/target/CC3D/CC3D_OPBL.mk b/src/main/target/CC3D/CC3D_OPBL.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/NAZE/ALIENFLIGHTF1.mk b/src/main/target/NAZE/ALIENFLIGHTF1.mk new file mode 100644 index 0000000000..e69de29bb2 diff --git a/src/main/target/REVO/REVO_OPBL.mk b/src/main/target/REVO/REVO_OPBL.mk new file mode 100644 index 0000000000..e69de29bb2 From 1afe6b65ca6c0c41d7cf32cd3ff274c2bcd9dcaa Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 14 Jun 2016 11:40:46 +1000 Subject: [PATCH 10/13] Removed cleaning from all goal. --- Makefile | 1 - 1 file changed, 1 deletion(-) diff --git a/Makefile b/Makefile index f0539a31e3..0193442630 100644 --- a/Makefile +++ b/Makefile @@ -663,7 +663,6 @@ all: for build_target in $(VALID_TARGETS); do \ echo "" && \ echo "Building $$build_target" && \ - $(MAKE) -j TARGET=$$build_target clean && \ $(MAKE) -j binary hex TARGET=$$build_target || \ break; \ echo "Building $$build_target succeeded."; \ From be652b8446f6b79244ed982aacdfab4d48cc7c44 Mon Sep 17 00:00:00 2001 From: nathan Date: Mon, 13 Jun 2016 21:36:22 -0700 Subject: [PATCH 11/13] \t -> ____ --- Makefile | 470 +++++++++++++++++++++++++++---------------------------- 1 file changed, 235 insertions(+), 235 deletions(-) diff --git a/Makefile b/Makefile index 0193442630..12352a0ba7 100644 --- a/Makefile +++ b/Makefile @@ -50,7 +50,7 @@ OBJECT_DIR = $(ROOT)/obj/main BIN_DIR = $(ROOT)/obj CMSIS_DIR = $(ROOT)/lib/main/CMSIS INCLUDE_DIRS = $(SRC_DIR) \ - $(ROOT)/src/main/target + $(ROOT)/src/main/target LINKER_DIR = $(ROOT)/src/main/target # default xtal value for F4 targets @@ -65,18 +65,18 @@ OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) #VALID_TARGETS = $(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) -VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) +VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) VALID_TARGETS := $(sort $(VALID_TARGETS)) ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) -include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk else -BASE_TARGET := $(TARGET) +BASE_TARGET := $(TARGET) endif ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET)) -OPBL = yes +OPBL = yes endif # silently ignore if the file is not present. Allows for target specific. @@ -92,8 +92,8 @@ ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS)),) $(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, or F411. Have you prepared a valid target.mk?) endif -128K_TARGETS = $(F1_TARGETS) -256K_TARGETS = $(F3_TARGETS) +128K_TARGETS = $(F1_TARGETS) +256K_TARGETS = $(F3_TARGETS) 512K_TARGETS = $(F411_TARGETS) 1024K_TARGETS = $(F405_TARGETS) @@ -143,34 +143,34 @@ ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f30x_crc.c \ - stm32f30x_can.c + stm32f30x_can.c STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \ - $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM1/CoreSupport \ - $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM1/CoreSupport \ + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x ifneq ($(filter VCP, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ - $(USBPERIPH_SRC) + $(USBPERIPH_SRC) endif ifneq ($(filter SDCARD, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) \ + $(FATFS_DIR) \ VPATH := $(VPATH):$(FATFS_DIR) endif @@ -189,25 +189,25 @@ else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f4xx_crc.c \ - stm32f4xx_can.c \ - stm32f4xx_fmc.c \ - stm32f4xx_sai.c \ - stm32f4xx_cec.c \ - stm32f4xx_dsi.c \ - stm32f4xx_flash_ramfunc.c \ - stm32f4xx_fmpi2c.c \ - stm32f4xx_lptim.c \ - stm32f4xx_qspi.c \ - stm32f4xx_spdifrx.c \ - stm32f4xx_cryp.c \ - stm32f4xx_cryp_aes.c \ - stm32f4xx_hash_md5.c \ - stm32f4xx_cryp_des.c \ - stm32f4xx_rtc.c \ - stm32f4xx_hash.c \ - stm32f4xx_dbgmcu.c \ - stm32f4xx_cryp_tdes.c \ - stm32f4xx_hash_sha1.c + stm32f4xx_can.c \ + stm32f4xx_fmc.c \ + stm32f4xx_sai.c \ + stm32f4xx_cec.c \ + stm32f4xx_dsi.c \ + stm32f4xx_flash_ramfunc.c \ + stm32f4xx_fmpi2c.c \ + stm32f4xx_lptim.c \ + stm32f4xx_qspi.c \ + stm32f4xx_spdifrx.c \ + stm32f4xx_cryp.c \ + stm32f4xx_cryp_aes.c \ + stm32f4xx_hash_md5.c \ + stm32f4xx_cryp_des.c \ + stm32f4xx_rtc.c \ + stm32f4xx_hash.c \ + stm32f4xx_dbgmcu.c \ + stm32f4xx_cryp_tdes.c \ + stm32f4xx_hash_sha1.c ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) @@ -222,10 +222,10 @@ USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c)) USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c)) EXCLUDES = usb_bsp_template.c \ - usb_conf_template.c \ - usb_hcd_int.c \ - usb_hcd.c \ - usb_otg.c + usb_conf_template.c \ + usb_hcd_int.c \ + usb_hcd.c \ + usb_otg.c USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC)) USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc @@ -235,27 +235,27 @@ USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ - $(USBOTG_SRC) \ - $(USBCORE_SRC) \ - $(USBCDC_SRC) + $(USBOTG_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) #CMSIS VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \ - $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(USBOTG_DIR)/inc \ - $(USBCORE_DIR)/inc \ - $(USBCDC_DIR)/inc \ - $(USBFS_DIR)/inc \ - $(CMSIS_DIR)/CM4/CoreSupport \ - $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ - $(ROOT)/src/main/vcpf4 + $(STDPERIPH_DIR)/inc \ + $(USBOTG_DIR)/inc \ + $(USBCORE_DIR)/inc \ + $(USBCDC_DIR)/inc \ + $(USBFS_DIR)/inc \ + $(CMSIS_DIR)/CM4/CoreSupport \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ + $(ROOT)/src/main/vcpf4 ifneq ($(filter SDCARD,$(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(FATFS_DIR) + $(FATFS_DIR) VPATH := $(VPATH):$(FATFS_DIR) endif @@ -282,32 +282,32 @@ else STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) EXCLUDES = stm32f10x_crc.c \ - stm32f10x_cec.c \ - stm32f10x_can.c + stm32f10x_cec.c \ + stm32f10x_can.c STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) # Search path and source files for the CMSIS sources VPATH := $(VPATH):$(CMSIS_DIR)/CM3/CoreSupport:$(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM3/CoreSupport/*.c \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x/*.c)) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(STDPERIPH_DIR)/inc \ - $(CMSIS_DIR)/CM3/CoreSupport \ - $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM3/CoreSupport \ + $(CMSIS_DIR)/CM3/DeviceSupport/ST/STM32F10x \ DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) ifneq ($(filter VCP, $(FEATURES)),) INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(USBFS_DIR)/inc \ - $(ROOT)/src/main/vcp + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp VPATH := $(VPATH):$(USBFS_DIR)/src DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \ - $(USBPERIPH_SRC) + $(USBPERIPH_SRC) endif @@ -316,7 +316,7 @@ ARCH_FLAGS = -mthumb -mcpu=cortex-m3 TARGET_FLAGS := -D$(TARGET) -pedantic $(TARGET_FLAGS) ifeq ($(DEVICE_FLAGS),) -DEVICE_FLAGS = -DSTM32F10X_MD +DEVICE_FLAGS = -DSTM32F10X_MD endif DEVICE_FLAGS += -DSTM32F10X @@ -352,155 +352,155 @@ else endif INCLUDE_DIRS := $(INCLUDE_DIRS) \ - $(TARGET_DIR) + $(TARGET_DIR) VPATH := $(VPATH):$(TARGET_DIR) COMMON_SRC = \ - build_config.c \ - debug.c \ - version.c \ - $(TARGET_DIR_SRC) \ - main.c \ - mw.c \ - scheduler.c \ - scheduler_tasks.c \ - common/encoding.c \ - common/filter.c \ - common/maths.c \ - common/printf.c \ - common/typeconversion.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/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 \ - io/serial.c \ - io/serial_4way.c \ - io/serial_4way_avrootloader.c \ - io/serial_4way_stk500v2.c \ - io/serial_cli.c \ - io/serial_msp.c \ - io/statusindicator.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 \ - sensors/compass.c \ - sensors/gyro.c \ - sensors/initialisation.c \ - $(CMSIS_SRC) \ - $(DEVICE_STDPERIPH_SRC) + build_config.c \ + debug.c \ + version.c \ + $(TARGET_DIR_SRC) \ + main.c \ + mw.c \ + scheduler.c \ + scheduler_tasks.c \ + common/encoding.c \ + common/filter.c \ + common/maths.c \ + common/printf.c \ + common/typeconversion.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/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 \ + io/serial.c \ + io/serial_4way.c \ + io/serial_4way_avrootloader.c \ + io/serial_4way_stk500v2.c \ + io/serial_cli.c \ + io/serial_msp.c \ + io/statusindicator.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 \ + sensors/compass.c \ + sensors/gyro.c \ + sensors/initialisation.c \ + $(CMSIS_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 \ - 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 + blackbox/blackbox.c \ + blackbox/blackbox_io.c \ + common/colorconversion.c \ + drivers/display_ug2864hsweg01.c \ + flight/gtune.c \ + flight/navigation.c \ + flight/gps_conversion.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 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) VCP_SRC = \ - vcpf4/stm32f4xx_it.c \ - vcpf4/usb_bsp.c \ - vcpf4/usbd_desc.c \ - vcpf4/usbd_usr.c \ - vcpf4/usbd_cdc_vcp.c \ - drivers/serial_usb_vcp.c + vcpf4/stm32f4xx_it.c \ + vcpf4/usb_bsp.c \ + vcpf4/usbd_desc.c \ + vcpf4/usbd_usr.c \ + vcpf4/usbd_cdc_vcp.c \ + drivers/serial_usb_vcp.c else VCP_SRC = \ - vcp/hw_config.c \ - vcp/stm32_it.c \ - vcp/usb_desc.c \ - vcp/usb_endp.c \ - vcp/usb_istr.c \ - vcp/usb_prop.c \ - vcp/usb_pwr.c \ - drivers/serial_usb_vcp.c \ - drivers/usb_io.c + vcp/hw_config.c \ + vcp/stm32_it.c \ + vcp/usb_desc.c \ + vcp/usb_endp.c \ + vcp/usb_istr.c \ + vcp/usb_prop.c \ + vcp/usb_pwr.c \ + drivers/serial_usb_vcp.c \ + drivers/usb_io.c endif STM32F10x_COMMON_SRC = \ - startup_stm32f10x_md_gcc.S \ - drivers/adc_stm32f10x.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/dma.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 + startup_stm32f10x_md_gcc.S \ + drivers/adc_stm32f10x.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/dma.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/dma.c \ - drivers/gpio_stm32f30x.c \ - drivers/light_ws2811strip_stm32f30x.c \ - drivers/serial_uart_stm32f30x.c \ - drivers/system_stm32f30x.c \ - drivers/timer_stm32f30x.c + startup_stm32f30x_md_gcc.S \ + target/system_stm32f30x.c \ + drivers/adc_stm32f30x.c \ + drivers/bus_i2c_stm32f30x.c \ + drivers/dma.c \ + drivers/gpio_stm32f30x.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/serial_uart_stm32f30x.c \ + drivers/system_stm32f30x.c \ + drivers/timer_stm32f30x.c STM32F4xx_COMMON_SRC = \ - startup_stm32f40xx.s \ - target/system_stm32f4xx.c \ - drivers/accgyro_mpu.c \ - drivers/adc_stm32f4xx.c \ - drivers/adc_stm32f4xx.c \ - drivers/bus_i2c_stm32f10x.c \ - drivers/gpio_stm32f4xx.c \ - drivers/inverter.c \ - drivers/serial_softserial.c \ - drivers/serial_uart_stm32f4xx.c \ - drivers/system_stm32f4xx.c \ - drivers/timer_stm32f4xx.c \ - drivers/dma_stm32f4xx.c + startup_stm32f40xx.s \ + target/system_stm32f4xx.c \ + drivers/accgyro_mpu.c \ + drivers/adc_stm32f4xx.c \ + drivers/adc_stm32f4xx.c \ + drivers/bus_i2c_stm32f10x.c \ + drivers/gpio_stm32f4xx.c \ + drivers/inverter.c \ + drivers/serial_softserial.c \ + drivers/serial_uart_stm32f4xx.c \ + drivers/system_stm32f4xx.c \ + drivers/timer_stm32f4xx.c \ + drivers/dma_stm32f4xx.c # check if target.mk supplied ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) @@ -513,24 +513,24 @@ endif ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) TARGET_SRC += \ - drivers/flash_m25p16.c \ - io/flashfs.c + drivers/flash_m25p16.c \ + io/flashfs.c endif ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS) $(F3_TARGETS))) TARGET_SRC += $(HIGHEND_SRC) else ifneq ($(filter HIGHEND,$(FEATURES)),) -TARGET_SRC += $(HIGHEND_SRC) +TARGET_SRC += $(HIGHEND_SRC) endif TARGET_SRC += $(COMMON_SRC) ifneq ($(filter SDCARD,$(FEATURES)),) TARGET_SRC += \ - drivers/sdcard.c \ - drivers/sdcard_standard.c \ - io/asyncfatfs/asyncfatfs.c \ - io/asyncfatfs/fat_standard.c + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c endif ifneq ($(filter VCP,$(FEATURES)),) @@ -566,50 +566,50 @@ endif DEBUG_FLAGS = -ggdb3 -DDEBUG CFLAGS += $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(addprefix -D,$(OPTIONS)) \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - $(DEBUG_FLAGS) \ - -std=gnu99 \ - -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ - -ffunction-sections \ - -fdata-sections \ - $(DEVICE_FLAGS) \ - -DUSE_STDPERIPH_DRIVER \ - $(TARGET_FLAGS) \ - -D'__FORKNAME__="$(FORKNAME)"' \ - -D'__TARGET__="$(TARGET)"' \ - -D'__REVISION__="$(REVISION)"' \ - -save-temps=obj \ - -MMD -MP + $(LTO_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -std=gnu99 \ + -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ + -ffunction-sections \ + -fdata-sections \ + $(DEVICE_FLAGS) \ + -DUSE_STDPERIPH_DRIVER \ + $(TARGET_FLAGS) \ + -D'__FORKNAME__="$(FORKNAME)"' \ + -D'__TARGET__="$(TARGET)"' \ + -D'__REVISION__="$(REVISION)"' \ + -save-temps=obj \ + -MMD -MP ASFLAGS = $(ARCH_FLAGS) \ - -x assembler-with-cpp \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -MMD -MP + -x assembler-with-cpp \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + -MMD -MP LDFLAGS = -lm \ - -nostartfiles \ - --specs=nano.specs \ - -lc \ - -lnosys \ - $(ARCH_FLAGS) \ - $(LTO_FLAGS) \ - $(DEBUG_FLAGS) \ - -static \ - -Wl,-gc-sections,-Map,$(TARGET_MAP) \ - -Wl,-L$(LINKER_DIR) \ - -Wl,--cref \ - -T$(LD_SCRIPT) + -nostartfiles \ + --specs=nano.specs \ + -lc \ + -lnosys \ + $(ARCH_FLAGS) \ + $(LTO_FLAGS) \ + $(DEBUG_FLAGS) \ + -static \ + -Wl,-gc-sections,-Map,$(TARGET_MAP) \ + -Wl,-L$(LINKER_DIR) \ + -Wl,--cref \ + -T$(LD_SCRIPT) ############################################################################### # No user-serviceable parts below ############################################################################### CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ - --std=c99 --inline-suppr --quiet --force \ - $(addprefix -I,$(INCLUDE_DIRS)) \ - -I/usr/include -I/usr/include/linux + --std=c99 --inline-suppr --quiet --force \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + -I/usr/include -I/usr/include/linux # # Things we will build @@ -638,7 +638,7 @@ $(TARGET_BIN): $(TARGET_ELF) $(TARGET_ELF): $(TARGET_OBJS) @echo LD $(notdir $@) @$(CC) -o $@ $^ $(LDFLAGS) - $(SIZE) $(TARGET_ELF) + $(SIZE) $(TARGET_ELF) # Compile $(OBJECT_DIR)/$(TARGET)/%.o: %.c @@ -659,7 +659,7 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.S ## all : default task; compile C code, build firmware -all: +all: for build_target in $(VALID_TARGETS); do \ echo "" && \ echo "Building $$build_target" && \ From 0fd8774d5028cb196a4f8445e0c0d0dcb266756f Mon Sep 17 00:00:00 2001 From: nathan Date: Mon, 13 Jun 2016 22:45:53 -0700 Subject: [PATCH 12/13] takin' a look --- Makefile | 5 + fake_travis_build.sh | 3 +- q | 59 --- src/main/blackbox/blackbox.c | 1 + src/main/blackbox/blackbox_io.c | 1 + src/main/config/config.c | 27 ++ src/main/config/config.h | 1 + src/main/config/config_master.h | 5 + src/main/drivers/max7456.c | 188 ++++++++ src/main/drivers/max7456.h | 125 +++++ src/main/drivers/rtc6705.c | 151 ++++++ src/main/drivers/rtc6705.h | 25 + src/main/flight/mixer.h | 2 + src/main/io/osd.c | 710 +++++++++++++++++++++++++++++ src/main/io/osd.h | 61 +++ src/main/io/serial_cli.c | 29 ++ src/main/io/serial_msp.c | 33 +- src/main/io/serial_msp.h | 9 + src/main/main.c | 11 + src/main/mw.c | 11 + src/main/scheduler.h | 4 +- src/main/scheduler_tasks.c | 12 +- src/main/target/SIRINFPV/target.c | 62 +++ src/main/target/SIRINFPV/target.h | 182 ++++++++ src/main/target/SIRINFPV/target.mk | 16 + src/main/telemetry/ltm.c | 1 + src/main/telemetry/smartport.c | 1 + top_makefile | 2 + 28 files changed, 1674 insertions(+), 63 deletions(-) delete mode 100644 q create mode 100644 src/main/drivers/max7456.c create mode 100644 src/main/drivers/max7456.h create mode 100644 src/main/drivers/rtc6705.c create mode 100644 src/main/drivers/rtc6705.h create mode 100644 src/main/io/osd.c create mode 100644 src/main/io/osd.h create mode 100644 src/main/target/SIRINFPV/target.c create mode 100644 src/main/target/SIRINFPV/target.h create mode 100644 src/main/target/SIRINFPV/target.mk diff --git a/Makefile b/Makefile index 12352a0ba7..40224afded 100644 --- a/Makefile +++ b/Makefile @@ -536,6 +536,11 @@ endif ifneq ($(filter VCP,$(FEATURES)),) TARGET_SRC += $(VCP_SRC) endif + +ifneq ($(filter MAX_OSD, $(FEATURES)),) +TARGET_SRC += $(SRC_DIR)/drivers/max7456.c \ + $(SRC_DIR)/io/osd.c +endif # end target specific make file checks diff --git a/fake_travis_build.sh b/fake_travis_build.sh index 7749d64354..339c4008d0 100755 --- a/fake_travis_build.sh +++ b/fake_travis_build.sh @@ -17,7 +17,8 @@ targets=("PUBLISHMETA=True" \ "TARGET=ALIENFLIGHTF1" \ "TARGET=ALIENFLIGHTF3" \ "TARGET=DOGE" \ - "TARGET=SINGULARITY") + "TARGET=SINGULARITY" \ + "TARGET=SIRINFPV") #fake a travis build environment export TRAVIS_BUILD_NUMBER=$(date +%s) diff --git a/q b/q deleted file mode 100644 index 04586033b6..0000000000 --- a/q +++ /dev/null @@ -1,59 +0,0 @@ -diff --git a/src/main/io/rc_controls.c b/src/main/io/rc_controls.c -index fdde2cf..53464ef 100644 ---- a/src/main/io/rc_controls.c -+++ b/src/main/io/rc_controls.c -@@ -67,6 +67,7 @@ static pidProfile_t *pidProfile; - static bool isUsingSticksToArm = true; -  - int16_t rcCommand[4]; // interval [1000;2000] for THROTTLE and [-500;+500] for ROLL/PITCH/YAW -+int16_t rcCommandSmooth[4]; // Smoothed RcCommand -  - uint32_t rcModeActivationMask; // one bit per mode defined in boxId_e -  -diff --git a/src/main/io/rc_controls.h b/src/main/io/rc_controls.h -index eaec277..dd8afaf 100644 ---- a/src/main/io/rc_controls.h -+++ b/src/main/io/rc_controls.h -@@ -147,6 +147,7 @@ typedef struct controlRateConfig_s { - } controlRateConfig_t; -  - extern int16_t rcCommand[4]; -+extern int16_t rcCommandSmooth[4]; // Smoothed RcCommand -  - typedef struct rcControlsConfig_s { - uint8_t deadband; // introduce a deadband around the stick center for pitch and roll axis. Must be greater than zero. -diff --git a/src/main/mw.c b/src/main/mw.c -index 125674c..5da79cf 100644 ---- a/src/main/mw.c -+++ b/src/main/mw.c -@@ -181,7 +181,7 @@ void filterRc(void) -  - if (isRXDataNew) { - for (int channel=0; channel < 4; channel++) { -- deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); -+ deltaRC[channel] = rcCommand[channel] - (lastCommand[channel] - deltaRC[channel] * factor / rcInterpolationFactor); - lastCommand[channel] = rcCommand[channel]; - } -  -@@ -194,7 +194,7 @@ void filterRc(void) - // Interpolate steps of rcCommand - if (factor > 0) { - for (int channel=0; channel < 4; channel++) { -- rcCommand[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; -+ rcCommandSmooth[channel] = lastCommand[channel] - deltaRC[channel] * factor/rcInterpolationFactor; - } - } else { - factor = 0; -@@ -649,8 +649,11 @@ void subTaskMainSubprocesses(void) { -  - const uint32_t startTime = micros(); -  -+ filterRc(); -+ - if (masterConfig.rxConfig.rcSmoothing || flightModeFlags) { -- filterRc(); -+ int axis; -+ for (axis = 0; axis <= 4; axis++) rcCommand[axis] = rcCommandSmooth[axis]; - } -  - // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 80df3ba141..4b3aa51cc8 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -60,6 +60,7 @@ #include "io/serial_cli.h" #include "io/serial_msp.h" #include "io/statusindicator.h" +#include "io/osd.h" #include "io/vtx.h" #include "rx/rx.h" diff --git a/src/main/blackbox/blackbox_io.c b/src/main/blackbox/blackbox_io.c index 0eeead3156..82c105eb4a 100644 --- a/src/main/blackbox/blackbox_io.c +++ b/src/main/blackbox/blackbox_io.c @@ -36,6 +36,7 @@ #include "io/escservo.h" #include "rx/rx.h" #include "io/rc_controls.h" +#include "io/osd.h" #include "io/vtx.h" #include "io/gimbal.h" diff --git a/src/main/config/config.c b/src/main/config/config.c index 7c2fc82ccd..ad8cf1f43b 100755 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -55,6 +55,7 @@ #include "io/rc_curves.h" #include "io/ledstrip.h" #include "io/gps.h" +#include "io/osd.h" #include "io/vtx.h" #include "rx/rx.h" @@ -418,6 +419,32 @@ static void resetConf(void) featureSet(DEFAULT_FEATURES); #endif +#ifdef SIRINFPV + featureSet(FEATURE_OSD); + featureSet(FEATURE_RX_SERIAL); + masterConfig.serialConfig.portConfigs[2].functionMask = FUNCTION_RX_SERIAL; + //masterConfig.batteryConfig.vbatscale = 20; + masterConfig.mag_hardware = MAG_NONE; // disabled by default + masterConfig.rxConfig.serialrx_provider = SERIALRX_SBUS; + masterConfig.blackbox_device = 1; + masterConfig.blackbox_rate_num = 1; + masterConfig.blackbox_rate_denom = 1; +#endif + +#ifdef OSD + masterConfig.vtx_channel = 19; + masterConfig.osdProfile.system = 0; + masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] = -29; + masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] = -59; + masterConfig.osdProfile.item_pos[OSD_TIMER] = -39; + masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] = -9; + masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] = 26; + masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL] = 1; + masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] = -80; + masterConfig.osdProfile.item_pos[OSD_ARMED] = -107; + masterConfig.osdProfile.item_pos[OSD_DISARMED] = -109; +#endif + #ifdef BOARD_HAS_VOLTAGE_DIVIDER // only enable the VBAT feature by default if the board has a voltage divider otherwise // the user may see incorrect readings and unexpected issues with pin mappings may occur. diff --git a/src/main/config/config.h b/src/main/config/config.h index 7bd7a2e052..219cc31bea 100644 --- a/src/main/config/config.h +++ b/src/main/config/config.h @@ -46,6 +46,7 @@ typedef enum { FEATURE_TRANSPONDER = 1 << 21, FEATURE_AIRMODE = 1 << 22, FEATURE_SUPEREXPO_RATES = 1 << 23, + FEATURE_OSD = 1 << 24, } features_e; void handleOneshotFeatureChangeOnRestart(void); diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 01bf4e8f3f..6d1c943179 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -125,6 +125,11 @@ typedef struct master_t { uint8_t transponderData[6]; #endif +#ifdef OSD + uint8_t vtx_channel; + osd_profile osdProfile; +#endif + profile_t profile[MAX_PROFILE_COUNT]; uint8_t current_profile_index; diff --git a/src/main/drivers/max7456.c b/src/main/drivers/max7456.c new file mode 100644 index 0000000000..9a9605fb2d --- /dev/null +++ b/src/main/drivers/max7456.c @@ -0,0 +1,188 @@ +/* + * 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 + +#include "common/printf.h" +#include "platform.h" +#include "version.h" + +#ifdef USE_MAX7456 + +#include "drivers/bus_spi.h" +#include "drivers/system.h" + +#include "max7456.h" + +#define DISABLE_MAX7456 GPIO_SetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN) +#define ENABLE_MAX7456 GPIO_ResetBits(MAX7456_CS_GPIO, MAX7456_CS_PIN) + + +uint16_t max_screen_size; +uint8_t video_signal_type = 0; +uint8_t max7456_lock = 0; +char screen[480]; + + +uint8_t max7456_send(uint8_t add, uint8_t data) { + spiTransferByte(MAX7456_SPI_INSTANCE, add); + return spiTransferByte(MAX7456_SPI_INSTANCE, data); +} + + +void max7456_init(uint8_t system) { + uint8_t max_screen_rows; + uint8_t srdata = 0; + uint16_t x; + char buf[30]; + + //Minimum spi clock period for max7456 is 100ns (10Mhz) + spiSetDivisor(MAX7456_SPI_INSTANCE, SPI_9MHZ_CLOCK_DIVIDER); + + delay(1000); + // force soft reset on Max7456 + ENABLE_MAX7456; + max7456_send(VM0_REG, MAX7456_RESET); + delay(100); + + srdata = max7456_send(0xA0, 0xFF); + if ((0x01 & srdata) == 0x01){ //PAL + video_signal_type = VIDEO_MODE_PAL; + } + else if((0x02 & srdata) == 0x02){ //NTSC + video_signal_type = VIDEO_MODE_NTSC; + } + + // Override detected type: 0-AUTO, 1-PAL, 2-NTSC + switch(system) { + case 1: + video_signal_type = VIDEO_MODE_PAL; + break; + case 2: + video_signal_type = VIDEO_MODE_NTSC; + break; + } + + if (video_signal_type) { //PAL + max_screen_size = 480; + max_screen_rows = 16; + } else { // NTSC + max_screen_size = 390; + max_screen_rows = 13; + } + + // set all rows to same charactor black/white level + for(x = 0; x < max_screen_rows; x++) { + max7456_send(MAX7456ADD_RB0 + x, BWBRIGHTNESS); + } + + // make sure the Max7456 is enabled + max7456_send(VM0_REG, OSD_ENABLE | video_signal_type); + + DISABLE_MAX7456; + delay(100); + + x = 160; + for (int i = 1; i < 5; i++) { + for (int j = 3; j < 27; j++) + screen[i * 30 + j] = (char)x++; + } + tfp_sprintf(buf, "BF VERSION: %s", FC_VERSION_STRING); + max7456_write_string(buf, 5*30+5); + max7456_write_string("MENU: THRT MID", 6*30+7); + max7456_write_string("YAW RIGHT", 7*30+13); + max7456_write_string("PITCH UP", 8*30+13); + max7456_draw_screen(); +} + +// Copy string from ram into screen buffer +void max7456_write_string(const char *string, int16_t address) { + char *dest; + + if (address >= 0) + dest = screen + address; + else + dest = screen + (max_screen_size + address); + + while(*string) + *dest++ = *string++; +} + +void max7456_draw_screen(void) { + uint16_t xx; + if (!max7456_lock) { + ENABLE_MAX7456; + for (xx = 0; xx < max_screen_size; ++xx) { + max7456_send(MAX7456ADD_DMAH, xx>>8); + max7456_send(MAX7456ADD_DMAL, xx); + max7456_send(MAX7456ADD_DMDI, screen[xx]); + screen[xx] = ' '; + } + DISABLE_MAX7456; + } +} + +void max7456_draw_screen_fast(void) { + uint16_t xx; + if (!max7456_lock) { + ENABLE_MAX7456; + max7456_send(MAX7456ADD_DMAH, 0); + max7456_send(MAX7456ADD_DMAL, 0); + max7456_send(MAX7456ADD_DMM, 1); + for (xx = 0; xx < max_screen_size; ++xx) { + max7456_send(MAX7456ADD_DMDI, screen[xx]); + screen[xx] = ' '; + } + max7456_send(MAX7456ADD_DMDI, 0xFF); + max7456_send(MAX7456ADD_DMM, 0); + DISABLE_MAX7456; + } +} + + +void max7456_write_nvm(uint8_t char_address, uint8_t *font_data) { + uint8_t x; + + max7456_lock = 1; + ENABLE_MAX7456; + + // disable display + max7456_send(VM0_REG, video_signal_type); + + max7456_send(MAX7456ADD_CMAH, char_address); // set start address high + + for(x = 0; x < 54; x++) { + max7456_send(MAX7456ADD_CMAL, x); //set start address low + max7456_send(MAX7456ADD_CMDI, font_data[x]); + } + + // transfer 54 bytes from shadow ram to NVM + max7456_send(MAX7456ADD_CMM, WRITE_NVR); + + // wait until bit 5 in the status register returns to 0 (12ms) + while ((spiTransferByte(MAX7456_SPI_INSTANCE, MAX7456ADD_STAT) & STATUS_REG_NVR_BUSY) != 0); + + max7456_send(VM0_REG, video_signal_type | 0x0C); + DISABLE_MAX7456; + max7456_lock = 0; +} + + +#endif diff --git a/src/main/drivers/max7456.h b/src/main/drivers/max7456.h new file mode 100644 index 0000000000..86bd4dd1ee --- /dev/null +++ b/src/main/drivers/max7456.h @@ -0,0 +1,125 @@ +/* + * 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 + +#ifndef WHITEBRIGHTNESS + #define WHITEBRIGHTNESS 0x01 +#endif +#ifndef BLACKBRIGHTNESS + #define BLACKBRIGHTNESS 0x00 +#endif + +#define BWBRIGHTNESS ((BLACKBRIGHTNESS << 2) | WHITEBRIGHTNESS) + +//MAX7456 opcodes +#define DMM_REG 0x04 +#define DMAH_REG 0x05 +#define DMAL_REG 0x06 +#define DMDI_REG 0x07 +#define VM0_REG 0x00 +#define VM1_REG 0x01 + +// video mode register 0 bits +#define VIDEO_BUFFER_DISABLE 0x01 +#define MAX7456_RESET 0x02 +#define VERTICAL_SYNC_NEXT_VSYNC 0x04 +#define OSD_ENABLE 0x08 +#define SYNC_MODE_AUTO 0x00 +#define SYNC_MODE_INTERNAL 0x30 +#define SYNC_MODE_EXTERNAL 0x20 +#define VIDEO_MODE_PAL 0x40 +#define VIDEO_MODE_NTSC 0x00 + +// video mode register 1 bits + + +// duty cycle is on_off +#define BLINK_DUTY_CYCLE_50_50 0x00 +#define BLINK_DUTY_CYCLE_33_66 0x01 +#define BLINK_DUTY_CYCLE_25_75 0x02 +#define BLINK_DUTY_CYCLE_75_25 0x03 + +// blinking time +#define BLINK_TIME_0 0x00 +#define BLINK_TIME_1 0x04 +#define BLINK_TIME_2 0x08 +#define BLINK_TIME_3 0x0C + +// background mode brightness (percent) +#define BACKGROUND_BRIGHTNESS_0 0x00 +#define BACKGROUND_BRIGHTNESS_7 0x01 +#define BACKGROUND_BRIGHTNESS_14 0x02 +#define BACKGROUND_BRIGHTNESS_21 0x03 +#define BACKGROUND_BRIGHTNESS_28 0x04 +#define BACKGROUND_BRIGHTNESS_35 0x05 +#define BACKGROUND_BRIGHTNESS_42 0x06 +#define BACKGROUND_BRIGHTNESS_49 0x07 + +#define BACKGROUND_MODE_GRAY 0x40 + +//MAX7456 commands +#define CLEAR_DISPLAY 0x04 +#define CLEAR_DISPLAY_VERT 0x06 +#define END_STRING 0xff + + +#define MAX7456ADD_VM0 0x00 //0b0011100// 00 // 00 ,0011100 +#define MAX7456ADD_VM1 0x01 +#define MAX7456ADD_HOS 0x02 +#define MAX7456ADD_VOS 0x03 +#define MAX7456ADD_DMM 0x04 +#define MAX7456ADD_DMAH 0x05 +#define MAX7456ADD_DMAL 0x06 +#define MAX7456ADD_DMDI 0x07 +#define MAX7456ADD_CMM 0x08 +#define MAX7456ADD_CMAH 0x09 +#define MAX7456ADD_CMAL 0x0a +#define MAX7456ADD_CMDI 0x0b +#define MAX7456ADD_OSDM 0x0c +#define MAX7456ADD_RB0 0x10 +#define MAX7456ADD_RB1 0x11 +#define MAX7456ADD_RB2 0x12 +#define MAX7456ADD_RB3 0x13 +#define MAX7456ADD_RB4 0x14 +#define MAX7456ADD_RB5 0x15 +#define MAX7456ADD_RB6 0x16 +#define MAX7456ADD_RB7 0x17 +#define MAX7456ADD_RB8 0x18 +#define MAX7456ADD_RB9 0x19 +#define MAX7456ADD_RB10 0x1a +#define MAX7456ADD_RB11 0x1b +#define MAX7456ADD_RB12 0x1c +#define MAX7456ADD_RB13 0x1d +#define MAX7456ADD_RB14 0x1e +#define MAX7456ADD_RB15 0x1f +#define MAX7456ADD_OSDBL 0x6c +#define MAX7456ADD_STAT 0xA0 + +#define NVM_RAM_SIZE 54 +#define WRITE_NVR 0xA0 +#define STATUS_REG_NVR_BUSY 0x20 + +extern uint16_t max_screen_size; +char screen[480]; + + +void max7456_init(uint8_t system); +void max7456_draw_screen(void); +void max7456_draw_screen_fast(void); +void max7456_write_string(const char *string, int16_t address); +void max7456_write_nvm(uint8_t char_address, uint8_t *font_data); diff --git a/src/main/drivers/rtc6705.c b/src/main/drivers/rtc6705.c new file mode 100644 index 0000000000..319430f526 --- /dev/null +++ b/src/main/drivers/rtc6705.c @@ -0,0 +1,151 @@ +/* + * 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" + +#ifdef USE_RTC6705 + +#include "drivers/bus_spi.h" +#include "drivers/system.h" +#include "drivers/gpio.h" + +#include "rtc6705.h" + +#define RTC6705_SPICLK_ON GPIO_SetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN) +#define RTC6705_SPICLK_OFF GPIO_ResetBits(RTC6705_SPICLK_GPIO, RTC6705_SPICLK_PIN) + +#define RTC6705_SPIDATA_ON GPIO_SetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN) +#define RTC6705_SPIDATA_OFF GPIO_ResetBits(RTC6705_SPIDATA_GPIO, RTC6705_SPIDATA_PIN) + +#define RTC6705_SPILE_ON GPIO_SetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN) +#define RTC6705_SPILE_OFF GPIO_ResetBits(RTC6705_SPILE_GPIO, RTC6705_SPILE_PIN) + +char *vtx_bands[] = { + "BOSCAM A", + "BOSCAM B", + "BOSCAM E", + "FATSHARK", + "RACEBAND", +}; + +uint16_t vtx_freq[] = +{ + 5865, 5845, 5825, 5805, 5785, 5765, 5745, 5725, + 5733, 5752, 5771, 5790, 5809, 5828, 5847, 5866, + 5705, 5685, 5665, 5645, 5885, 5905, 5925, 5945, + 5740, 5760, 5780, 5800, 5820, 5840, 5860, 5880, + 5658, 5695, 5732, 5769, 5806, 5843, 5880, 5917, +}; + +uint16_t current_vtx_channel; + +void rtc6705_init(void) { + gpio_config_t gpio; + +#ifdef STM32F303 + #ifdef RTC6705_SPICLK_PERIPHERAL + RCC_AHBPeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE); + #endif + #ifdef RTC6705_SPILE_PERIPHERAL + RCC_AHBPeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE); + #endif + #ifdef RTC6705_SPIDATA_PERIPHERAL + RCC_AHBPeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE); + #endif +#endif +#ifdef STM32F10X + #ifdef RTC6705_SPICLK_PERIPHERAL + RCC_APB2PeriphClockCmd(RTC6705_SPICLK_PERIPHERAL, ENABLE); + #endif + #ifdef RTC6705_SPILE_PERIPHERAL + RCC_APB2PeriphClockCmd(RTC6705_SPILE_PERIPHERAL, ENABLE); + #endif + #ifdef RTC6705_SPIDATA_PERIPHERAL + RCC_APB2PeriphClockCmd(RTC6705_SPIDATA_PERIPHERAL, ENABLE); + #endif +#endif + + gpio.pin = RTC6705_SPICLK_PIN; + gpio.speed = Speed_50MHz; + gpio.mode = Mode_Out_PP; + gpioInit(RTC6705_SPICLK_GPIO, &gpio); + + gpio.pin = RTC6705_SPILE_PIN; + gpio.speed = Speed_50MHz; + gpio.mode = Mode_Out_PP; + gpioInit(RTC6705_SPILE_GPIO, &gpio); + + gpio.pin = RTC6705_SPIDATA_PIN; + gpio.speed = Speed_50MHz; + gpio.mode = Mode_Out_PP; + gpioInit(RTC6705_SPIDATA_GPIO, &gpio); +} + +void rtc6705_write_register(uint8_t addr, uint32_t data) { + uint8_t i; + + RTC6705_SPILE_OFF; + delay(1); + // send address + for (i=0; i<4; i++) { + if ((addr >> i) & 1) + RTC6705_SPIDATA_ON; + else + RTC6705_SPIDATA_OFF; + + RTC6705_SPICLK_ON; + delay(1); + RTC6705_SPICLK_OFF; + delay(1); + } + // Write bit + + RTC6705_SPIDATA_ON; + RTC6705_SPICLK_ON; + delay(1); + RTC6705_SPICLK_OFF; + delay(1); + for (i=0; i<20; i++) { + if ((data >> i) & 1) + RTC6705_SPIDATA_ON; + else + RTC6705_SPIDATA_OFF; + RTC6705_SPICLK_ON; + delay(1); + RTC6705_SPICLK_OFF; + delay(1); + } + RTC6705_SPILE_ON; +} + + +void rtc6705_set_channel(uint16_t channel_freq) { + + uint32_t freq = (uint32_t)channel_freq * 1000; + uint32_t N, A; + + freq /= 40; + N = freq / 64; + A = freq % 64; + rtc6705_write_register(0, 400); + rtc6705_write_register(1, (N << 7) | A); +} +#endif diff --git a/src/main/drivers/rtc6705.h b/src/main/drivers/rtc6705.h new file mode 100644 index 0000000000..511d090878 --- /dev/null +++ b/src/main/drivers/rtc6705.h @@ -0,0 +1,25 @@ +/* + * 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 + +extern char* vtx_bands[]; +extern uint16_t vtx_freq[]; +extern uint16_t current_vtx_channel; + +void rtc6705_init(void); +void rtc6705_set_channel(uint16_t channel_freq); diff --git a/src/main/flight/mixer.h b/src/main/flight/mixer.h index 8828ba08b3..22c1c008d1 100644 --- a/src/main/flight/mixer.h +++ b/src/main/flight/mixer.h @@ -187,6 +187,8 @@ void writeServos(void); void filterServos(void); #endif +bool motorLimitReached; + extern int16_t motor[MAX_SUPPORTED_MOTORS]; extern int16_t motor_disarmed[MAX_SUPPORTED_MOTORS]; bool motorLimitReached; diff --git a/src/main/io/osd.c b/src/main/io/osd.c new file mode 100644 index 0000000000..ebc489dd94 --- /dev/null +++ b/src/main/io/osd.c @@ -0,0 +1,710 @@ +/* + * 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 +#include + +#include "platform.h" +#include "scheduler.h" + +#include "common/axis.h" +#include "common/color.h" +#include "common/atomic.h" +#include "common/maths.h" +#include "common/typeconversion.h" + +#include "drivers/nvic.h" + +#include "drivers/sensor.h" +#include "drivers/system.h" +#include "drivers/gpio.h" +#include "drivers/light_led.h" +#include "drivers/sound_beeper.h" +#include "drivers/timer.h" +#include "drivers/serial.h" +#include "drivers/serial_softserial.h" +#include "drivers/serial_uart.h" +#include "drivers/accgyro.h" +#include "drivers/compass.h" +#include "drivers/pwm_mapping.h" +#include "drivers/pwm_rx.h" +#include "drivers/adc.h" +#include "drivers/bus_i2c.h" +#include "drivers/bus_bst.h" +#include "drivers/bus_spi.h" +#include "drivers/inverter.h" +#include "drivers/flash_m25p16.h" +#include "drivers/sonar_hcsr04.h" +#include "drivers/gyro_sync.h" +#include "drivers/usb_io.h" +#include "drivers/transponder_ir.h" +#include "drivers/sdcard.h" + +#include "rx/rx.h" + +#include "io/beeper.h" +#include "io/serial.h" +#include "io/flashfs.h" +#include "io/gps.h" +#include "io/escservo.h" +#include "io/rc_controls.h" +#include "io/gimbal.h" +#include "io/ledstrip.h" +#include "io/display.h" +#include "io/asyncfatfs/asyncfatfs.h" +#include "io/transponder_ir.h" +#include "io/osd.h" + +#include "sensors/sensors.h" +#include "sensors/sonar.h" +#include "sensors/barometer.h" +#include "sensors/compass.h" +#include "sensors/acceleration.h" +#include "sensors/gyro.h" +#include "sensors/battery.h" +#include "sensors/boardalignment.h" +#include "sensors/initialisation.h" + +#include "telemetry/telemetry.h" +#include "blackbox/blackbox.h" + +#include "flight/pid.h" +#include "flight/imu.h" +#include "flight/mixer.h" +#include "flight/failsafe.h" +#include "flight/navigation.h" + +#include "config/runtime_config.h" +#include "config/config.h" +#include "config/config_profile.h" +#include "config/config_master.h" + +#ifdef USE_HARDWARE_REVISION_DETECTION +#include "hardware_revision.h" +#endif + +#include "build_config.h" +#include "debug.h" + +#ifdef OSD + +#include "drivers/max7456.h" +#include "drivers/rtc6705.h" +#include "scheduler.h" +#include "common/printf.h" + +#define MICROSECONDS_IN_A_SECOND (1000 * 1000) + +#define OSD_UPDATE_FREQUENCY (MICROSECONDS_IN_A_SECOND / 5) +#define OSD_LINE_LENGTH 30 + +#define STICKMIN 10 +#define STICKMAX 90 + + +static uint32_t next_osd_update_at = 0; +static uint32_t armed_seconds = 0; +static uint32_t armed_at = 0; +static bool armed = false; + +static uint8_t current_page = 0; +static uint8_t sticks[] = {0,0,0,0}; +static char string_buffer[30]; +static uint8_t cursor_row = 255; +static uint8_t cursor_col = 0; +static bool in_menu = false; +static bool activating_menu = false; +extern uint16_t rssi; + + +#ifdef USE_RTC6705 +void update_vtx_band(bool increase, uint8_t col) { + (void)col; + if (increase) { + if (current_vtx_channel < 32) + current_vtx_channel += 8; + } else { + if (current_vtx_channel > 7) + current_vtx_channel -= 8; + } +} + +void print_vtx_band(uint16_t pos, uint8_t col) { + (void)col; + sprintf(string_buffer, "%s", vtx_bands[current_vtx_channel / 8]); + max7456_write_string(string_buffer, pos); +} + +void update_vtx_channel(bool increase, uint8_t col) { + (void)col; + if (increase) { + if ((current_vtx_channel % 8) < 7) + current_vtx_channel++; + } else { + if ((current_vtx_channel % 8) > 0) + current_vtx_channel--; + } +} + +void print_vtx_channel(uint16_t pos, uint8_t col) { + (void)col; + sprintf(string_buffer, "%d", current_vtx_channel % 8 + 1); + max7456_write_string(string_buffer, pos); +} + +void print_vtx_freq(uint16_t pos, uint8_t col) { + (void)col; + sprintf(string_buffer, "%d M", vtx_freq[current_vtx_channel]); + max7456_write_string(string_buffer, pos); +} +#endif + +void print_pid(uint16_t pos, uint8_t col, int pid_term) { + switch(col) { + case 0: + sprintf(string_buffer, "%d", currentProfile->pidProfile.P8[pid_term]); + break; + case 1: + sprintf(string_buffer, "%d", currentProfile->pidProfile.I8[pid_term]); + break; + case 2: + sprintf(string_buffer, "%d", currentProfile->pidProfile.D8[pid_term]); + break; + default: + return; + } + max7456_write_string(string_buffer, pos); +} + +void print_roll_pid(uint16_t pos, uint8_t col) { + print_pid(pos, col, ROLL); +} + +void print_pitch_pid(uint16_t pos, uint8_t col) { + print_pid(pos, col, PITCH); +} + +void print_yaw_pid(uint16_t pos, uint8_t col) { + print_pid(pos, col, YAW); +} + +void print_roll_rate(uint16_t pos, uint8_t col) { + if (col == 0) { + sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_ROLL]); + max7456_write_string(string_buffer, pos); + } +} + +void print_pitch_rate(uint16_t pos, uint8_t col) { + if (col == 0) { + sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_PITCH]); + max7456_write_string(string_buffer, pos); + } +} + +void print_yaw_rate(uint16_t pos, uint8_t col) { + if (col == 0) { + sprintf(string_buffer, "%d", currentControlRateProfile->rates[FD_YAW]); + max7456_write_string(string_buffer, pos); + } +} + +void print_tpa_rate(uint16_t pos, uint8_t col) { + if (col == 0) { + sprintf(string_buffer, "%d", currentControlRateProfile->dynThrPID); + max7456_write_string(string_buffer, pos); + } +} + +void print_tpa_brkpt(uint16_t pos, uint8_t col) { + if (col == 0) { + sprintf(string_buffer, "%d", currentControlRateProfile->tpa_breakpoint); + max7456_write_string(string_buffer, pos); + } +} + +void update_int_pid(bool inc, uint8_t col, int pid_term) { + void* ptr; + switch(col) { + case 0: + ptr = ¤tProfile->pidProfile.P8[pid_term]; + break; + case 1: + ptr = ¤tProfile->pidProfile.I8[pid_term]; + break; + case 2: + ptr = ¤tProfile->pidProfile.D8[pid_term]; + break; + default: + return; + } + + if (inc) { + if (*(uint8_t*)ptr < 200) + *(uint8_t*)ptr += 1; + } else { + if (*(uint8_t*)ptr > 0) + *(uint8_t*)ptr -= 1; + } +} + +void update_roll_pid(bool inc, uint8_t col) { + update_int_pid(inc, col, ROLL); +} + +void update_pitch_pid(bool inc, uint8_t col) { + update_int_pid(inc, col, PITCH); +} + +void update_yaw_pid(bool inc, uint8_t col) { + update_int_pid(inc, col, YAW); +} + +void update_roll_rate(bool inc, uint8_t col) { + (void)col; + if (inc) { + if (currentControlRateProfile->rates[FD_ROLL] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX) + currentControlRateProfile->rates[FD_ROLL]++; + } else { + if (currentControlRateProfile->rates[FD_ROLL] > 0) + currentControlRateProfile->rates[FD_ROLL]--; + } +} + +void update_pitch_rate(bool increase, uint8_t col) { + (void)col; + if (increase) { + if (currentControlRateProfile->rates[FD_PITCH] < CONTROL_RATE_CONFIG_ROLL_PITCH_RATE_MAX) + currentControlRateProfile->rates[FD_PITCH]++; + } else { + if (currentControlRateProfile->rates[FD_PITCH] > 0) + currentControlRateProfile->rates[FD_PITCH]--; + } +} + +void update_yaw_rate(bool increase, uint8_t col) { + (void)col; + if (increase) { + if (currentControlRateProfile->rates[FD_YAW] < CONTROL_RATE_CONFIG_YAW_RATE_MAX) + currentControlRateProfile->rates[FD_YAW]++; + } else { + if (currentControlRateProfile->rates[FD_YAW] > 0) + currentControlRateProfile->rates[FD_YAW]--; + } +} + +void update_tpa_rate(bool increase, uint8_t col) { + (void)col; + if (increase) { + if (currentControlRateProfile->dynThrPID < CONTROL_RATE_CONFIG_TPA_MAX) + currentControlRateProfile->dynThrPID++; + } else { + if (currentControlRateProfile->dynThrPID > 0) + currentControlRateProfile->dynThrPID--; + } +} + +void update_tpa_brkpt(bool increase, uint8_t col) { + (void)col; + if (increase) { + if (currentControlRateProfile->tpa_breakpoint < PWM_RANGE_MAX) + currentControlRateProfile->tpa_breakpoint++; + } else { + if (currentControlRateProfile->tpa_breakpoint > PWM_RANGE_MIN) + currentControlRateProfile->tpa_breakpoint--; + } +} + +void print_average_system_load(uint16_t pos, uint8_t col) { + (void)col; + sprintf(string_buffer, "%d", averageSystemLoadPercent); + max7456_write_string(string_buffer, pos); +} + +void print_batt_voltage(uint16_t pos, uint8_t col) { + (void)col; + sprintf(string_buffer, "%d.%1d", vbat / 10, vbat % 10); + max7456_write_string(string_buffer, pos); +} + +/* + TODO: add this to menu + { "rc_rate", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcRate8, .config.minmax = { 0, 250 } }, + { "rc_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcExpo8, .config.minmax = { 0, 100 } }, + { "rc_yaw_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].rcYawExpo8, .config.minmax = { 0, 100 } }, + { "thr_mid", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrMid8, .config.minmax = { 0, 100 } }, + { "thr_expo", VAR_UINT8 | PROFILE_RATE_VALUE, &masterConfig.profile[0].controlRateProfile[0].thrExpo8, .config.minmax = { 0, 100 } }, + { "acro_plus_factor", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusFactor, .config.minmax = {1, 100 } }, + { "acro_plus_offset", VAR_UINT8 | MASTER_VALUE, &masterConfig.rxConfig.acroPlusOffset, .config.minmax = {1, 90 } }, +*/ + +page_t menu_pages[] = { + { + .title = "STATUS", + .cols_number = 1, + .rows_number = 2, + .cols = { + { + .title = NULL, + .x_pos = 15 + } + }, + .rows = { + { + .title = "AVG LOAD", + .update = NULL, + .print = print_average_system_load + }, + { + .title = "BATT", + .update = NULL, + .print = print_batt_voltage + }, + } + }, +#ifdef USE_RTC6705 + { + .title = "VTX SETTINGS", + .cols_number = 1, + .rows_number = 3, + .cols = { + { + .title = NULL, + .x_pos = 15 + } + }, + .rows = { + { + .title = "BAND", + .update = update_vtx_band, + .print = print_vtx_band + }, + { + .title = "CHANNEL", + .update = update_vtx_channel, + .print = print_vtx_channel + }, + { + .title = "FREQUENCY", + .update = NULL, + .print = print_vtx_freq + } + } + }, +#endif + { + .title = "PID SETTINGS", + .cols_number = 3, + .rows_number = 8, + .cols = { + { + .title = "P", + .x_pos = 13 + }, + { + .title = "I", + .x_pos = 19 + }, + { + .title = "D", + .x_pos = 25 + } + }, + .rows = { + { + .title = "ROLL", + .update = update_roll_pid, + .print = print_roll_pid + }, + { + .title = "PITCH", + .update = update_pitch_pid, + .print = print_pitch_pid + }, + { + .title = "YAW", + .update = update_yaw_pid, + .print = print_yaw_pid + }, + { + .title = "ROLL RATE", + .update = update_roll_rate, + .print = print_roll_rate + }, + { + .title = "PITCH RATE", + .update = update_pitch_rate, + .print = print_pitch_rate + }, + { + .title = "YAW RATE", + .update = update_yaw_rate, + .print = print_yaw_rate + }, + { + .title = "TPA RATE", + .update = update_tpa_rate, + .print = print_tpa_rate + }, + { + .title = "TPA BRKPT", + .update = update_tpa_brkpt, + .print = print_tpa_brkpt + }, + } + }, +}; + +void show_menu(void) { + uint8_t line = 1; + uint16_t pos; + col_t *col; + row_t *row; + int16_t cursor_x, cursor_y; + + if (activating_menu) { + if (sticks[YAW] < 60 && sticks[YAW] > 40 && sticks[PITCH] > 40 && sticks[PITCH] < 60 && sticks[ROLL] > 40 && sticks[ROLL] < 60) + activating_menu = false; + else + return; + } + + if (sticks[YAW] > STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMIN && sticks[PITCH] < STICKMAX) { + if (cursor_row > MAX_MENU_ROWS) { + switch(cursor_col) { + case 0: + in_menu = false; + break; + case 1: + in_menu = false; +#ifdef USE_RTC6705 + if (masterConfig.vtx_channel != current_vtx_channel) { + masterConfig.vtx_channel = current_vtx_channel; + rtc6705_set_channel(vtx_freq[current_vtx_channel]); + } +#endif + writeEEPROM(); + break; + case 2: + if (current_page < (sizeof(menu_pages) / sizeof(page_t) - 1)) + current_page++; + else + current_page = 0; + } + } else { + if (menu_pages[current_page].rows[cursor_row].update) + menu_pages[current_page].rows[cursor_row].update(true, cursor_col); + } + } + + if (sticks[YAW] < STICKMIN && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMIN && sticks[PITCH] < STICKMAX) { + if (cursor_row > MAX_MENU_ROWS) { + if (cursor_col == 2 && current_page > 0) { + current_page--; + } + } else { + if (menu_pages[current_page].rows[cursor_row].update) + menu_pages[current_page].rows[cursor_row].update(false, cursor_col); + } + } + + if (sticks[PITCH] > STICKMAX && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) { + if (cursor_row > MAX_MENU_ROWS) { + cursor_row = menu_pages[current_page].rows_number - 1; + cursor_col = 0; + } else { + if (cursor_row > 0) + cursor_row--; + } + } + if (sticks[PITCH] < STICKMIN && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) { + if (cursor_row < (menu_pages[current_page].rows_number - 1)) + cursor_row++; + else + cursor_row = 255; + } + if (sticks[ROLL] > STICKMAX && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) { + if (cursor_row > MAX_MENU_ROWS) { + if (cursor_col < 2) + cursor_col++; + } else { + if (cursor_col < (menu_pages[current_page].cols_number - 1)) + cursor_col++; + } + } + if (sticks[ROLL] < STICKMIN && sticks[YAW] > STICKMIN && sticks[YAW] < STICKMAX) { + if (cursor_col > 0) + cursor_col--; + } + + if (cursor_row > MAX_MENU_ROWS) { + cursor_row = 255; + cursor_y = -1; + switch(cursor_col) { + case 0: + cursor_x = 0; + break; + case 1: + cursor_x = 9; + break; + case 2: + cursor_x = 23; + break; + default: + cursor_x = 0; + } + } + + sprintf(string_buffer, "EXIT SAVE+EXIT PAGE"); + max7456_write_string(string_buffer, -29); + + pos = (OSD_LINE_LENGTH - strlen(menu_pages[current_page].title)) / 2 + line * OSD_LINE_LENGTH; + sprintf(string_buffer, "%s", menu_pages[current_page].title); + max7456_write_string(string_buffer, pos); + + line += 2; + + for (int i = 0; i < menu_pages[current_page].cols_number; i++){ + col = &menu_pages[current_page].cols[i]; + if (cursor_col == i && cursor_row < MAX_MENU_ROWS) + cursor_x = col->x_pos - 1; + + if (col->title) { + sprintf(string_buffer, "%s", col->title); + max7456_write_string(string_buffer, line * OSD_LINE_LENGTH + col->x_pos); + } + } + + line++; + for (int i = 0; i < menu_pages[current_page].rows_number; i++) { + row = &menu_pages[current_page].rows[i]; + if (cursor_row == i) + cursor_y = line; + + sprintf(string_buffer, "%s", row->title); + max7456_write_string(string_buffer, line * OSD_LINE_LENGTH + 1); + for (int j = 0; j < menu_pages[current_page].cols_number; j++) { + col = &menu_pages[current_page].cols[j]; + row->print(line * OSD_LINE_LENGTH + col->x_pos, j); + } + line++; + } + + max7456_write_string(">", cursor_x + cursor_y * OSD_LINE_LENGTH); +} + +void updateOsd(void) +{ + static uint8_t skip = 0; + static bool blink = false; + static uint8_t arming = 0; + uint32_t seconds; + char line[30]; + uint32_t now = micros(); + + bool updateNow = (int32_t)(now - next_osd_update_at) >= 0L; + if (!updateNow) { + return; + } + next_osd_update_at = now + OSD_UPDATE_FREQUENCY; + if ( !(skip % 2)) + blink = !blink; + + if (skip++ & 1) { + if (ARMING_FLAG(ARMED)) { + if (!armed) { + armed = true; + armed_at = now; + in_menu = false; + arming = 5; + } + } else { + if (armed) { + armed = false; + armed_seconds += ((now - armed_at) / 1000000); + } + for (uint8_t channelIndex = 0; channelIndex < 4; channelIndex++) { + sticks[channelIndex] = (constrain(rcData[channelIndex], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN); + } + if (!in_menu && sticks[YAW] > STICKMAX && sticks[THROTTLE] > STICKMIN && sticks[THROTTLE] < STICKMAX && sticks[ROLL] > STICKMIN && sticks[ROLL] < STICKMAX && sticks[PITCH] > STICKMAX) { + in_menu = true; + cursor_row = 255; + cursor_col = 2; + activating_menu = true; + } + } + if (in_menu) { + show_menu(); + } else { + if (batteryWarningVoltage > vbat && blink && masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING] != -1) { + max7456_write_string("LOW VOLTAGE", masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING]); + } + if (arming && blink && masterConfig.osdProfile.item_pos[OSD_ARMED] != -1) { + max7456_write_string("ARMED", masterConfig.osdProfile.item_pos[OSD_ARMED]); + arming--; + } + if (!armed && masterConfig.osdProfile.item_pos[OSD_DISARMED] != -1) { + max7456_write_string("DISARMED", masterConfig.osdProfile.item_pos[OSD_DISARMED]); + } + + if (masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE] != -1) { + sprintf(line, "\x01%d.%1d", vbat / 10, vbat % 10); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE]); + } + if (masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE] != -1) { + sprintf(line, "\x02%d", rssi / 10); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE]); + } + if (masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS] != -1) { + sprintf(line, "\x03%3d", (constrain(rcData[THROTTLE], PWM_RANGE_MIN, PWM_RANGE_MAX) - PWM_RANGE_MIN) * 100 / (PWM_RANGE_MAX - PWM_RANGE_MIN)); + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS]); + } + if (masterConfig.osdProfile.item_pos[OSD_TIMER] != -1) { + if (armed) { + seconds = armed_seconds + ((now-armed_at) / 1000000); + sprintf(line, "\x04 %02d:%02d", seconds / 60, seconds % 60); + } else { + seconds = now / 1000000; + sprintf(line, "\x05 %02d:%02d", seconds / 60, seconds % 60); + } + max7456_write_string(line, masterConfig.osdProfile.item_pos[OSD_TIMER]); + } + if (masterConfig.osdProfile.item_pos[OSD_CPU_LOAD] != -1) { + print_average_system_load(masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], 0); + } + } + } else { + max7456_draw_screen_fast(); + } +} + + +void osdInit(void) +{ +#ifdef USE_RTC6705 + rtc6705_init(); + current_vtx_channel = masterConfig.vtx_channel; + rtc6705_set_channel(vtx_freq[current_vtx_channel]); +#endif + max7456_init(masterConfig.osdProfile.system); + +} + +#endif diff --git a/src/main/io/osd.h b/src/main/io/osd.h new file mode 100644 index 0000000000..c72a417761 --- /dev/null +++ b/src/main/io/osd.h @@ -0,0 +1,61 @@ +/* + * 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 . + */ + +#define MAX_MENU_ROWS 8 +#define MAX_MENU_COLS 3 + +typedef struct { + const char* title; + uint8_t x_pos; +} col_t; + +typedef struct { + const char* title; + void (*update)(bool increase, uint8_t col); + void (*print)(uint16_t pos, uint8_t col); +} row_t; + +typedef struct { + const char* title; + uint8_t cols_number; + uint8_t rows_number; + col_t cols[MAX_MENU_COLS]; + row_t rows[MAX_MENU_ROWS]; +} page_t; + + +typedef enum { + OSD_MAIN_BATT_VOLTAGE, + OSD_RSSI_VALUE, + OSD_TIMER, + OSD_THROTTLE_POS, + OSD_CPU_LOAD, + OSD_VTX_CHANNEL, + OSD_VOLTAGE_WARNING, + OSD_ARMED, + OSD_DISARMED, + OSD_MAX_ITEMS, // MUST BE LAST +} osd_items; + + +typedef struct { + uint8_t system; + int16_t item_pos[OSD_MAX_ITEMS]; +} osd_profile; + +void updateOsd(void); +void osdInit(void); diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 2ea0b022fc..bba0361042 100644 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -60,6 +60,7 @@ #include "io/flashfs.h" #include "io/beeper.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/osd.h" #include "io/vtx.h" #include "rx/rx.h" @@ -446,6 +447,13 @@ static const char * const lookupTableDebug[DEBUG_COUNT] = { "AIRMODE", "PIDLOOP", }; +#ifdef OSD +static const char * const lookupTableOsdType[] = { + "AUTO", + "PAL", + "NTSC" +}; +#endif static const char * const lookupTableSuperExpoYaw[] = { "OFF", "ON", "ALWAYS" @@ -482,6 +490,9 @@ typedef enum { TABLE_DEBUG, TABLE_SUPEREXPO_YAW, TABLE_MOTOR_PWM_PROTOCOL, +#ifdef OSD + TABLE_OSD, +#endif } lookupTableIndex_e; static const lookupTableEntry_t lookupTables[] = { @@ -506,6 +517,9 @@ static const lookupTableEntry_t lookupTables[] = { { lookupTableDebug, sizeof(lookupTableDebug) / sizeof(char *) }, { lookupTableSuperExpoYaw, sizeof(lookupTableSuperExpoYaw) / sizeof(char *) }, { lookupTableFastPwm, sizeof(lookupTableFastPwm) / sizeof(char *) }, +#ifdef OSD + { lookupTableOsdType, sizeof(lookupTableOsdType) / sizeof(char *) }, +#endif }; #define VALUE_TYPE_OFFSET 0 @@ -786,6 +800,21 @@ const clivalue_t valueTable[] = { #ifdef LED_STRIP { "ledstrip_visual_beeper", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.ledstrip_visual_beeper, .config.lookup = { TABLE_OFF_ON } }, #endif +#ifdef USE_RTC6705 + { "vtx_channel", VAR_INT16 | MASTER_VALUE, &masterConfig.vtx_channel, .config.minmax = { 0, 39 } }, +#endif +#ifdef OSD + { "osd_system", VAR_UINT8 | MASTER_VALUE, &masterConfig.osdProfile.system, .config.minmax = { 0, 2 } }, + { "osd_main_voltage_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_MAIN_BATT_VOLTAGE], .config.minmax = { -480, 480 } }, + { "osd_rssi_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_RSSI_VALUE], .config.minmax = { -480, 480 } }, + { "osd_timer_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_TIMER], .config.minmax = { -480, 480 } }, + { "osd_throttle_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_THROTTLE_POS], .config.minmax = { -480, 480 } }, + { "osd_cpu_load_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_CPU_LOAD], .config.minmax = { -480, 480 } }, + { "osd_vtx_channel_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VTX_CHANNEL], .config.minmax = { -480, 480 } }, + { "osd_voltage_warning_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_VOLTAGE_WARNING], .config.minmax = { -480, 480 } }, + { "osd_armed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_ARMED], .config.minmax = { -480, 480 } }, + { "osd_disarmed_pos", VAR_INT16 | MASTER_VALUE, &masterConfig.osdProfile.item_pos[OSD_DISARMED], .config.minmax = { -480, 480 } }, +#endif }; #define VALUE_COUNT (sizeof(valueTable) / sizeof(clivalue_t)) diff --git a/src/main/io/serial_msp.c b/src/main/io/serial_msp.c index 31756bbe08..1eb219ab1f 100644 --- a/src/main/io/serial_msp.c +++ b/src/main/io/serial_msp.c @@ -44,6 +44,8 @@ #include "drivers/gyro_sync.h" #include "drivers/sdcard.h" #include "drivers/buf_writer.h" +#include "drivers/max7456.h" +#include "drivers/rtc6705.h" #include "rx/rx.h" #include "rx/msp.h" @@ -57,6 +59,7 @@ #include "io/flashfs.h" #include "io/transponder_ir.h" #include "io/asyncfatfs/asyncfatfs.h" +#include "io/osd.h" #include "io/vtx.h" #include "telemetry/telemetry.h" @@ -1255,7 +1258,9 @@ static bool processInCommand(void) uint8_t wp_no; int32_t lat = 0, lon = 0, alt = 0; #endif - +#ifdef OSD + uint8_t addr, font_data[64]; +#endif switch (currentPort->cmdMSP) { case MSP_SELECT_SETTING: if (!ARMING_FLAG(ARMED)) { @@ -1516,6 +1521,32 @@ static bool processInCommand(void) transponderUpdateData(masterConfig.transponderData); break; #endif +#ifdef OSD + case MSP_SET_OSD_CONFIG: + masterConfig.osdProfile.system = read8(); + for (i = 0; i < OSD_MAX_ITEMS; i++) + masterConfig.osdProfile.item_pos[i] = read16(); + break; + case MSP_OSD_CHAR_WRITE: + addr = read8(); + for (i = 0; i < 54; i++) { + font_data[i] = read8(); + } + max7456_write_nvm(addr, font_data); + break; +#endif + +#ifdef USE_RTC6705 + case MSP_SET_VTX_CONFIG: + tmp = read16(); + if (tmp < 40) + masterConfig.vtx_channel = tmp; + if (current_vtx_channel != masterConfig.vtx_channel) { + current_vtx_channel = masterConfig.vtx_channel; + rtc6705_set_channel(vtx_freq[current_vtx_channel]); + } + break; +#endif #ifdef USE_FLASHFS case MSP_DATAFLASH_ERASE: diff --git a/src/main/io/serial_msp.h b/src/main/io/serial_msp.h index c1041cf618..7db0e06942 100644 --- a/src/main/io/serial_msp.h +++ b/src/main/io/serial_msp.h @@ -168,6 +168,15 @@ static const char * const boardIdentifier = TARGET_BOARD_IDENTIFIER; #define MSP_TRANSPONDER_CONFIG 82 //in message Get transponder settings #define MSP_SET_TRANSPONDER_CONFIG 83 //out message Set transponder settings +#define MSP_OSD_CONFIG 84 //in message Get osd settings +#define MSP_SET_OSD_CONFIG 85 //out message Set osd settings + +#define MSP_OSD_CHAR_READ 86 //in message Get osd settings +#define MSP_OSD_CHAR_WRITE 87 //out message Set osd settings + +#define MSP_VTX_CONFIG 88 //in message Get vtx settings +#define MSP_SET_VTX_CONFIG 89 //out message Set vtx settings + // // Baseflight MSP commands (if enabled they exist in Cleanflight) // diff --git a/src/main/main.c b/src/main/main.c index 2a08223606..d175872d6a 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -72,6 +72,7 @@ #include "io/display.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/transponder_ir.h" +#include "io/osd.h" #include "io/vtx.h" #include "sensors/sensors.h" @@ -134,6 +135,7 @@ void ledStripInit(ledConfig_t *ledConfigsToUse, hsvColor_t *colorsToUse); void spektrumBind(rxConfig_t *rxConfig); const sonarHardware_t *sonarGetHardwareConfiguration(batteryConfig_t *batteryConfig); void sonarInit(const sonarHardware_t *sonarHardware); +void osdInit(void); typedef enum { SYSTEM_STATE_INITIALISING = 0, @@ -467,6 +469,12 @@ void init(void) } #endif +#ifdef OSD + if (feature(FEATURE_OSD)) { + osdInit(); + } +#endif + if (!sensorsAutodetect(&masterConfig.sensorAlignmentConfig, masterConfig.acc_hardware, masterConfig.mag_hardware, @@ -737,6 +745,9 @@ void main_init(void) #ifdef TRANSPONDER setTaskEnabled(TASK_TRANSPONDER, feature(FEATURE_TRANSPONDER)); #endif +#ifdef OSD + setTaskEnabled(TASK_OSD, feature(FEATURE_OSD)); +#endif #ifdef USE_BST setTaskEnabled(TASK_BST_MASTER_PROCESS, true); #endif diff --git a/src/main/mw.c b/src/main/mw.c index 717dc10e8b..a52258129e 100644 --- a/src/main/mw.c +++ b/src/main/mw.c @@ -65,6 +65,8 @@ #include "io/statusindicator.h" #include "io/asyncfatfs/asyncfatfs.h" #include "io/transponder_ir.h" +#include "io/osd.h" + #include "io/vtx.h" #include "rx/rx.h" @@ -963,3 +965,12 @@ void taskTransponder(void) } } #endif + +#ifdef OSD +void taskUpdateOsd(void) +{ + if (feature(FEATURE_OSD)) { + updateOsd(); + } +} +#endif diff --git a/src/main/scheduler.h b/src/main/scheduler.h index 237776c259..c55bbaeb05 100755 --- a/src/main/scheduler.h +++ b/src/main/scheduler.h @@ -79,7 +79,9 @@ typedef enum { #ifdef TRANSPONDER TASK_TRANSPONDER, #endif - +#ifdef OSD + TASK_OSD, +#endif #ifdef USE_BST TASK_BST_MASTER_PROCESS, #endif diff --git a/src/main/scheduler_tasks.c b/src/main/scheduler_tasks.c index c2b949259a..393f6d2c0e 100644 --- a/src/main/scheduler_tasks.c +++ b/src/main/scheduler_tasks.c @@ -40,6 +40,9 @@ void taskUpdateDisplay(void); void taskTelemetry(void); void taskLedStrip(void); void taskTransponder(void); +#ifdef OSD +void taskUpdateOsd(void); +#endif #ifdef USE_BST void taskBstReadWrite(void); void taskBstMasterProcess(void); @@ -168,7 +171,14 @@ cfTask_t cfTasks[TASK_COUNT] = { .staticPriority = TASK_PRIORITY_LOW, }, #endif - +#ifdef OSD + [TASK_OSD] = { + .taskName = "OSD", + .taskFunc = taskUpdateOsd, + .desiredPeriod = 1000000 / 60, // 60 Hz + .staticPriority = TASK_PRIORITY_LOW, + }, +#endif #ifdef TELEMETRY [TASK_TELEMETRY] = { .taskName = "TELEMETRY", diff --git a/src/main/target/SIRINFPV/target.c b/src/main/target/SIRINFPV/target.c new file mode 100644 index 0000000000..4ccf123ea2 --- /dev/null +++ b/src/main/target/SIRINFPV/target.c @@ -0,0 +1,62 @@ + +#include +#include + +#include +#include "drivers/pwm_mapping.h" + +const uint16_t multiPPM[] = { + // No PPM + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t multiPWM[] = { + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPPM[] = { + // No PPM + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const uint16_t airPWM[] = { + PWM1 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM2 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM3 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM4 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM5 | (MAP_TO_MOTOR_OUTPUT << 8), + PWM6 | (MAP_TO_MOTOR_OUTPUT << 8), + 0xFFFF +}; + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + + { TIM4, GPIOB, Pin_6, TIM_Channel_1, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource6, GPIO_AF_2, 0}, // PWM1 - PB6 + { TIM4, GPIOB, Pin_7, TIM_Channel_2, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource7, GPIO_AF_2, 0}, // PWM2 - PB6 + { TIM4, GPIOB, Pin_8, TIM_Channel_3, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource8, GPIO_AF_2, 0}, // PWM3 - PB8 + { TIM4, GPIOB, Pin_9, TIM_Channel_4, TIM4_IRQn, 1, Mode_AF_PP, GPIO_PinSource9, GPIO_AF_2, 0}, // PWM4 - PB9 + + { TIM3, GPIOB, Pin_0, TIM_Channel_3, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource0, GPIO_AF_2, 0}, // PWM5 - PB0 - *TIM3_CH3 + { TIM3, GPIOB, Pin_1, TIM_Channel_4, TIM3_IRQn, 1, Mode_AF_PP, GPIO_PinSource1, GPIO_AF_2, 0}, // PWM6 - PB1 - *TIM3_CH4 + +}; + + diff --git a/src/main/target/SIRINFPV/target.h b/src/main/target/SIRINFPV/target.h new file mode 100644 index 0000000000..0fb5ac2fdb --- /dev/null +++ b/src/main/target/SIRINFPV/target.h @@ -0,0 +1,182 @@ +/* + * 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 "SIRF" + +#define LED0 PB2 +#define BEEPER PA1 + +#define EXTI15_10_CALLBACK_HANDLER_COUNT 1 // MPU_INT + +#define USE_EXTI +#define USE_MPU_DATA_READY_SIGNAL +#define MPU_INT_EXTI PA8 +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_MPU6500 +#define USE_GYRO_SPI_MPU6500 + +#define ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_MPU6500 +#define USE_ACC_SPI_MPU6500 + +// MPU6000 +#define ACC_MPU6000_ALIGN CW180_DEG +#define GYRO_MPU6000_ALIGN CW180_DEG + +#define MPU6000_CS_PIN PA4 +#define MPU6000_SPI_INSTANCE SPI1 + +// MPU6500 +#define ACC_MPU6500_ALIGN CW90_DEG +#define GYRO_MPU6500_ALIGN CW90_DEG + +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define USB_IO + +#define USE_VCP +#define USE_USART1 +#define USE_USART2 +#define USE_USART3 +#define SERIAL_PORT_COUNT 4 + +#ifndef UART1_GPIO +#define UART1_TX_PIN GPIO_Pin_9 // PA9 +#define UART1_RX_PIN GPIO_Pin_10 // PA10 +#define UART1_GPIO GPIOA +#define UART1_GPIO_AF GPIO_AF_7 +#define UART1_TX_PINSOURCE GPIO_PinSource9 +#define UART1_RX_PINSOURCE GPIO_PinSource10 +#endif + +#define UART2_TX_PIN GPIO_Pin_2 // PA14 / SWCLK +#define UART2_RX_PIN GPIO_Pin_3 // PA15 +#define UART2_GPIO GPIOA +#define UART2_GPIO_AF GPIO_AF_7 +#define UART2_TX_PINSOURCE GPIO_PinSource2 +#define UART2_RX_PINSOURCE GPIO_PinSource3 + +#ifndef UART3_GPIO +#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 +#endif + +#undef USE_I2C + +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 // PB12,13,14,15 on AF5 +#define USE_SPI_DEVICE_3 + +#define SPI1_NSS_PIN PA4 +#define SPI1_SCK_PIN PA5 +#define SPI1_MISO_PIN PA6 +#define SPI1_MOSI_PIN PA7 + +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 + +#define SPI3_NSS_PIN PA15 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PB5 + +#define USE_MAX7456 +#define MAX7456_CS_GPIO GPIOA +#define MAX7456_CS_PIN GPIO_Pin_15 +#define MAX7456_SPI_INSTANCE SPI3 + +#define USE_RTC6705 +#define RTC6705_SPIDATA_GPIO GPIOC +#define RTC6705_SPIDATA_PIN Pin_15 +#define RTC6705_SPIDATA_PERIPHERAL RCC_AHBPeriph_GPIOC +#define RTC6705_SPILE_GPIO GPIOC +#define RTC6705_SPILE_PIN Pin_14 +#define RTC6705_SPILE_PERIPHERAL RCC_AHBPeriph_GPIOC +#define RTC6705_SPICLK_GPIO GPIOC +#define RTC6705_SPICLK_PIN Pin_13 +#define RTC6705_SPICLK_PERIPHERAL RCC_AHBPeriph_GPIOC + +#define USE_SDCARD +#define USE_SDCARD_SPI2 + +#define SDCARD_SPI_INSTANCE SPI2 +#define SDCARD_SPI_CS_GPIO SPI2_GPIO +#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN + +// SPI2 is on the APB1 bus whose clock runs at 36MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 128 +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 + +// Note, this is the same DMA channel as USART1_RX. Luckily we don't use DMA for USART Rx. +#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA1_FLAG_TC5 + +// Performance logging for SD card operations: +// #define AFATFS_USE_INTROSPECTIVE_LOGGING + +#define USE_ADC +#define BOARD_HAS_VOLTAGE_DIVIDER + +#define ADC_INSTANCE ADC1 +#define ADC_DMA_CHANNEL DMA1_Channel1 +#define ADC_AHB_PERIPHERAL RCC_AHBPeriph_DMA1 + +#define VBAT_ADC_GPIO GPIOA +#define VBAT_ADC_GPIO_PIN GPIO_Pin_0 +#define VBAT_ADC_CHANNEL ADC_Channel_1 + +//#define USE_QUAD_MIXER_ONLY +#define BLACKBOX +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT +#define TELEMETRY +#define SERIAL_RX +#define USE_CLI +#define OSD + +#define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT + +#define USE_SERVOS +#define DEFAULT_RX_FEATURE FEATURE_RX_PPM + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +// IO - stm32f303cc in 48pin package +#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)|BIT(3)|BIT(4)) + +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS (TIM_N(3) | TIM_N(4)) +#define TIMER_APB1_PERIPHERALS (RCC_APB1Periph_TIM3 | RCC_APB1Periph_TIM4) +#define TIMER_AHB_PERIPHERALS (RCC_AHBPeriph_GPIOB) + diff --git a/src/main/target/SIRINFPV/target.mk b/src/main/target/SIRINFPV/target.mk new file mode 100644 index 0000000000..a4543b227c --- /dev/null +++ b/src/main/target/SIRINFPV/target.mk @@ -0,0 +1,16 @@ +FEATURES = VCP SDCARD MAX_OSD +F3_TARGETS += $(TARGET) + +TARGET_SRC = \ + drivers/accgyro_mpu.c \ + drivers/accgyro_mpu6500.c \ + drivers/accgyro_spi_mpu6000.c \ + drivers/accgyro_spi_mpu6500.c \ + drivers/barometer_bmp280.c \ + drivers/compass_ak8975.c \ + drivers/compass_hmc5883l.c \ + drivers/flash_m25p16.c \ + drivers/light_ws2811strip.c \ + drivers/light_ws2811strip_stm32f30x.c \ + drivers/rtc6705.c + diff --git a/src/main/telemetry/ltm.c b/src/main/telemetry/ltm.c index ad184b5aa6..fd775c8773 100644 --- a/src/main/telemetry/ltm.c +++ b/src/main/telemetry/ltm.c @@ -62,6 +62,7 @@ #include "io/gps.h" #include "io/ledstrip.h" #include "io/beeper.h" +#include "io/osd.h" #include "io/vtx.h" #include "rx/rx.h" diff --git a/src/main/telemetry/smartport.c b/src/main/telemetry/smartport.c index 47685ab0a8..36b7c95569 100644 --- a/src/main/telemetry/smartport.c +++ b/src/main/telemetry/smartport.c @@ -37,6 +37,7 @@ #include "io/gimbal.h" #include "io/serial.h" #include "io/ledstrip.h" +#include "io/osd.h" #include "io/vtx.h" #include "sensors/boardalignment.h" diff --git a/top_makefile b/top_makefile index 4b1bb90e78..1eeee5cfbb 100644 --- a/top_makefile +++ b/top_makefile @@ -15,6 +15,7 @@ ALL_TARGETS += ircfusionf3 ALL_TARGETS += afromini ALL_TARGETS += doge ALL_TARGETS += singularity +ALL_TARGETS += sirinfpv CLEAN_TARGETS := $(addprefix clean_, $(ALL_TARGETS)) @@ -35,6 +36,7 @@ clean_ircfusionf3 ircfusionf3 : opts := TARGET=IRCFUSIONF3 clean_afromini afromini : opts := TARGET=AFROMINI clean_doge doge : opts := TARGET=DOGE clean_singularity singularity : opts := TARGET=SINGULARITY +clean_sirinfpv sirinfpv: opts := TARGET=SIRINFPV .PHONY: all clean From d1841df0d5afecb067b6ade8175e30c9c820e4c8 Mon Sep 17 00:00:00 2001 From: nathan Date: Mon, 13 Jun 2016 22:53:46 -0700 Subject: [PATCH 13/13] init cursor_x --- src/main/io/osd.c | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/src/main/io/osd.c b/src/main/io/osd.c index ebc489dd94..1cae90f982 100644 --- a/src/main/io/osd.c +++ b/src/main/io/osd.c @@ -477,7 +477,8 @@ void show_menu(void) { uint16_t pos; col_t *col; row_t *row; - int16_t cursor_x, cursor_y; + int16_t cursor_x = 0; + int16_t cursor_y = 0; if (activating_menu) { if (sticks[YAW] < 60 && sticks[YAW] > 40 && sticks[PITCH] > 40 && sticks[PITCH] < 60 && sticks[ROLL] > 40 && sticks[ROLL] < 60)