diff --git a/Makefile b/Makefile index 5df29e4700..b83c5b0f19 100644 --- a/Makefile +++ b/Makefile @@ -168,7 +168,7 @@ ifeq ($(DEBUG_HARDFAULTS),F7) CFLAGS += -DDEBUG_HARDFAULTS endif -REVISION = $(shell git log -1 --format="%h") +REVISION := $(shell git log -1 --format="%h") FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' ) FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' ) @@ -503,6 +503,7 @@ COMMON_SRC = \ drivers/rx_nrf24l01.c \ drivers/rx_spi.c \ drivers/rx_xn297.c \ + drivers/pwm_esc_detect.c \ drivers/pwm_output.c \ drivers/pwm_rx.c \ drivers/rcc.c \ @@ -597,8 +598,13 @@ HIGHEND_SRC = \ telemetry/ltm.c \ telemetry/mavlink.c \ sensors/esc_sensor.c \ + io/vtx_smartaudio.c -SPEED_OPTIMISED_SRC = \ +SPEED_OPTIMISED_SRC := "" +SIZE_OPTIMISED_SRC := "" + +ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ common/encoding.c \ common/filter.c \ common/maths.c \ @@ -682,7 +688,7 @@ SPEED_OPTIMISED_SRC = \ telemetry/mavlink.c \ telemetry/esc_telemetry.c \ -SIZE_OPTIMISED_SRC = \ +SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ drivers/serial_escserial.c \ io/serial_cli.c \ io/serial_4way.c \ @@ -697,7 +703,8 @@ SIZE_OPTIMISED_SRC = \ cms/cms_menu_misc.c \ cms/cms_menu_osd.c \ cms/cms_menu_vtx.c \ - io/vtx_smartaudio.c + io/vtx_smartaudio.c +endif #F3 ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) VCP_SRC = \ @@ -857,32 +864,41 @@ SIZE := $(ARM_SDK_PREFIX)size # Tool options. # -ifeq ($(DEBUG),GDB) -OPTIMISE = -O0 -CC_SPEED_OPTIMISATION = $(OPTIMISE) -CC_OPTIMISATION = $(OPTIMISE) -CC_SIZE_OPTIMISATION = $(OPTIMISE) -LTO_FLAGS = $(OPTIMISE) -else +ifneq ($(DEBUG),GDB) +OPTIMISATION_BASE := -flto -fuse-linker-plugin -ffast-math +OPTIMISE_SPEED := "" +OPTIMISE_SIZE := "" + ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) -OPTIMISE_SPEED = -Os -OPTIMISE = -Os -OPTIMISE_SIZE = -Os +OPTIMISE_DEFAULT := -Os + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) + else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) -OPTIMISE_SPEED = -Ofast -OPTIMISE = -O2 -OPTIMISE_SIZE = -Os +OPTIMISE_DEFAULT := -O2 +OPTIMISE_SPEED := -Ofast +OPTIMISE_SIZE := -Os + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) + else -OPTIMISE_SPEED = -Ofast -OPTIMISE = -Ofast -OPTIMISE_SIZE = -Ofast -endif -OPTIMISATION_BASE = -flto -fuse-linker-plugin -ffast-math -CC_SPEED_OPTIMISATION = $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) -CC_OPTIMISATION = $(OPTIMISATION_BASE) $(OPTIMISE) -CC_SIZE_OPTIMISATION = $(OPTIMISATION_BASE) $(OPTIMISE_SIZE) -LTO_FLAGS = $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) -endif +OPTIMISE_DEFAULT := -Ofast + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) + +endif #TARGETS + +CC_DEFAULT_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) +CC_SPEED_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) +CC_SIZE_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SIZE) + +else #DEBUG +OPTIMISE_DEFAULT := -O0 + +CC_DEBUG_OPTIMISATION := $(OPTIMISE_DEFAULT) + +LTO_FLAGS := $(OPTIMISE_DEFAULT) +endif #DEBUG DEBUG_FLAGS = -ggdb3 -DDEBUG @@ -967,16 +983,23 @@ $(TARGET_ELF): $(TARGET_OBJS) $(V0) $(SIZE) $(TARGET_ELF) # Compile +ifneq ($(DEBUG),GDB) $(OBJECT_DIR)/$(TARGET)/%.o: %.c $(V1) mkdir -p $(dir $@) - $(V1) $(if $(findstring $(subst ./src/main/,,$<), $(SPEED_OPTIMISED_SRC)), \ + $(V1) $(if $(findstring $(subst ./src/main/,,$<),$(SPEED_OPTIMISED_SRC)), \ echo "%% (speed optimised) $(notdir $<)" "$(STDOUT)" && \ $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_SPEED_OPTIMISATION) $<, \ - $(if $(findstring $(subst ./src/main/,,$<), $(SIZE_OPTIMISED_SRC)), \ + $(if $(findstring $(subst ./src/main/,,$<),$(SIZE_OPTIMISED_SRC)), \ echo "%% (size optimised) $(notdir $<)" "$(STDOUT)" && \ $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_SIZE_OPTIMISATION) $<, \ echo "%% $(notdir $<)" "$(STDOUT)" && \ - $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_OPTIMISATION) $<)) + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_DEFAULT_OPTIMISATION) $<)) +else +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(V1) mkdir -p $(dir $@) + $(V1) echo "%% $(notdir $<)" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_DEBUG_OPTIMISATION) $< +endif # Assemble $(OBJECT_DIR)/$(TARGET)/%.o: %.s diff --git a/Makefile.orig b/Makefile.orig new file mode 100644 index 0000000000..6d60e98c3a --- /dev/null +++ b/Makefile.orig @@ -0,0 +1,1134 @@ +############################################################################### +# "THE BEER-WARE LICENSE" (Revision 42): +# wrote this file. As long as you retain this notice you +# can do whatever you want with this stuff. If we meet some day, and you think +# this stuff is worth it, you can buy me a beer in return +############################################################################### +# +# Makefile for building the betaflight firmware. +# +# Invoke this with 'make help' to see the list of supported targets. +# +############################################################################### + + +# Things that the user might override on the commandline +# + +# The target to build, see VALID_TARGETS below +TARGET ?= NAZE + +# Compile-time options +OPTIONS ?= + +# compile for OpenPilot BootLoader support +OPBL ?= no + +# Debugger optons, must be empty or GDB +DEBUG ?= + +# Insert the debugging hardfault debugger +# releases should not be built with this flag as it does not disable pwm output +DEBUG_HARDFAULTS ?= + +# Serial port/Device for flashing +SERIAL_DEVICE ?= $(firstword $(wildcard /dev/ttyUSB*) no-port-found) + +# Flash size (KB). Some low-end chips actually have more flash than advertised, use this to override. +FLASH_SIZE ?= + +## V : Set verbosity level based on the V= parameter +## V=0 Low +## V=1 High +export AT := @ + +ifndef V +export V0 := +export V1 := $(AT) +export STDOUT := +else ifeq ($(V), 0) +export V0 := $(AT) +export V1 := $(AT) +export STDOUT:= "> /dev/null" +export MAKE := $(MAKE) --no-print-directory +else ifeq ($(V), 1) +export V0 := +export V1 := +export STDOUT := +endif + +############################################################################### +# Things that need to be maintained as the source changes +# + +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/link + +# Build tools, so we all share the same versions +# import macros common to all supported build systems +include $(ROOT)/make/system-id.mk +# developer preferences, edit these at will, they'll be gitignored +include $(ROOT)/make/local.mk + +# configure some directories that are relative to wherever ROOT_DIR is located +TOOLS_DIR := $(ROOT)/tools +BUILD_DIR := $(ROOT)/build +DL_DIR := $(ROOT)/downloads + +export RM := rm + +# import macros that are OS specific +include $(ROOT)/make/$(OSFAMILY).mk + +# include the tools makefile +include $(ROOT)/make/tools.mk + +# default xtal value for F4 targets +HSE_VALUE = 8000000 + +# used for turning on features like VCP and SDCARD +FEATURES = + +SAMPLE_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 CC3D FURYF4 NAZE REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO STM32F3DISCOVERY +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 := $(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) +F7_TARGETS = $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_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 + +ifeq ($(filter $(TARGET),$(F1_TARGETS) $(F3_TARGETS) $(F4_TARGETS) $(F7_TARGETS)),) +$(error Target '$(TARGET)' has not specified a valid STM group, must be one of F1, F3, F405, F411 or F7x5. Have you prepared a valid target.mk?) +endif + +128K_TARGETS = $(F1_TARGETS) +256K_TARGETS = $(F3_TARGETS) +512K_TARGETS = $(F411_TARGETS) $(F7X5XE_TARGETS) +1024K_TARGETS = $(F405_TARGETS) $(F7X5XG_TARGETS) $(F7X6XG_TARGETS) +2048K_TARGETS = $(F7X5XI_TARGETS) + +# 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),$(2048K_TARGETS))) +FLASH_SIZE = 2048 +else ifeq ($(TARGET),$(filter $(TARGET),$(1024K_TARGETS))) +FLASH_SIZE = 1024 +else ifeq ($(TARGET),$(filter $(TARGET),$(512K_TARGETS))) +FLASH_SIZE = 512 +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 +endif + +# note that there is no hardfault debugging startup file assembly handler for other platforms +ifeq ($(DEBUG_HARDFAULTS),F3) +CFLAGS += -DDEBUG_HARDFAULTS +STM32F30x_COMMON_SRC = startup_stm32f3_debug_hardfault_handler.S +else +STM32F30x_COMMON_SRC = startup_stm32f30x_md_gcc.S +endif + +ifeq ($(DEBUG_HARDFAULTS),F7) +CFLAGS += -DDEBUG_HARDFAULTS +endif + +REVISION := $(shell git log -1 --format="%h") + +FC_VER_MAJOR := $(shell grep " FC_VERSION_MAJOR" src/main/build/version.h | awk '{print $$3}' ) +FC_VER_MINOR := $(shell grep " FC_VERSION_MINOR" src/main/build/version.h | awk '{print $$3}' ) +FC_VER_PATCH := $(shell grep " FC_VERSION_PATCH" src/main/build/version.h | awk '{print $$3}' ) + +FC_VER := $(FC_VER_MAJOR).$(FC_VER_MINOR).$(FC_VER_PATCH) + +# Search path for sources +VPATH := $(SRC_DIR):$(SRC_DIR)/startup +USBFS_DIR = $(ROOT)/lib/main/STM32_USB-FS-Device_Driver +USBPERIPH_SRC = $(notdir $(wildcard $(USBFS_DIR)/src/*.c)) +FATFS_DIR = $(ROOT)/lib/main/FatFS +FATFS_SRC = $(notdir $(wildcard $(FATFS_DIR)/*.c)) + +CSOURCES := $(shell find $(SRC_DIR) -name '*.c') + +ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +# F3 TARGETS + +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F30x_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f30x_crc.c \ + stm32f30x_can.c + +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) +DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) + +VPATH := $(VPATH):$(CMSIS_DIR)/CM1/CoreSupport:$(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM1/CoreSupport/*.c \ + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x/*.c)) + +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/inc \ + $(CMSIS_DIR)/CM1/CoreSupport \ + $(CMSIS_DIR)/CM1/DeviceSupport/ST/STM32F30x + +ifneq ($(filter VCP, $(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp + +VPATH := $(VPATH):$(USBFS_DIR)/src + +DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC)\ + $(USBPERIPH_SRC) +endif + +ifneq ($(filter SDCARD, $(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) \ + +VPATH := $(VPATH):$(FATFS_DIR) +endif + +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 +# End F3 targets +# +# Start F4 targets +else ifeq ($(TARGET),$(filter $(TARGET), $(F4_TARGETS))) + +#STDPERIPH +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F4xx_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f4xx_crc.c \ + stm32f4xx_can.c \ + stm32f4xx_fmc.c \ + stm32f4xx_sai.c \ + stm32f4xx_cec.c \ + stm32f4xx_dsi.c \ + stm32f4xx_flash_ramfunc.c \ + stm32f4xx_fmpi2c.c \ + stm32f4xx_lptim.c \ + stm32f4xx_qspi.c \ + stm32f4xx_spdifrx.c \ + stm32f4xx_cryp.c \ + stm32f4xx_cryp_aes.c \ + stm32f4xx_hash_md5.c \ + stm32f4xx_cryp_des.c \ + stm32f4xx_rtc.c \ + stm32f4xx_hash.c \ + stm32f4xx_dbgmcu.c \ + stm32f4xx_cryp_tdes.c \ + stm32f4xx_hash_sha1.c + + +ifeq ($(TARGET),$(filter $(TARGET), $(F411_TARGETS))) +EXCLUDES += stm32f4xx_fsmc.c +endif + +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) + +#USB +USBCORE_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Core +USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/src/*.c)) +USBOTG_DIR = $(ROOT)/lib/main/STM32_USB_OTG_Driver +USBOTG_SRC = $(notdir $(wildcard $(USBOTG_DIR)/src/*.c)) +EXCLUDES = usb_bsp_template.c \ + usb_conf_template.c \ + usb_hcd_int.c \ + usb_hcd.c \ + usb_otg.c + +USBOTG_SRC := $(filter-out ${EXCLUDES}, $(USBOTG_SRC)) +USBCDC_DIR = $(ROOT)/lib/main/STM32_USB_Device_Library/Class/cdc +USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/src/*.c)) +EXCLUDES = usbd_cdc_if_template.c +USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) +VPATH := $(VPATH):$(USBOTG_DIR)/src:$(USBCORE_DIR)/src:$(USBCDC_DIR)/src + +DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ + $(USBOTG_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) + +#CMSIS +VPATH := $(VPATH):$(CMSIS_DIR)/CM4/CoreSupport:$(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM4/CoreSupport/*.c \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx/*.c)) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/inc \ + $(USBOTG_DIR)/inc \ + $(USBCORE_DIR)/inc \ + $(USBCDC_DIR)/inc \ + $(USBFS_DIR)/inc \ + $(CMSIS_DIR)/CM4/CoreSupport \ + $(CMSIS_DIR)/CM4/DeviceSupport/ST/STM32F4xx \ + $(ROOT)/src/main/vcpf4 + +ifneq ($(filter SDCARD,$(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) +endif + +#Flags +ARCH_FLAGS = -mthumb -mcpu=cortex-m4 -march=armv7e-m -mfloat-abi=hard -mfpu=fpv4-sp-d16 -fsingle-precision-constant -Wdouble-promotion + +ifeq ($(TARGET),$(filter $(TARGET),$(F411_TARGETS))) +DEVICE_FLAGS = -DSTM32F411xE +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f411.ld +else ifeq ($(TARGET),$(filter $(TARGET),$(F405_TARGETS))) +DEVICE_FLAGS = -DSTM32F40_41xxx +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f405.ld +else +$(error Unknown MCU for F4 target) +endif +DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) + +# End F4 targets +# +# Start F7 targets +else ifeq ($(TARGET),$(filter $(TARGET), $(F7_TARGETS))) + +#STDPERIPH +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F7xx_HAL_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/Src/*.c)) +EXCLUDES = stm32f7xx_hal_timebase_rtc_wakeup_template.c \ + stm32f7xx_hal_timebase_rtc_alarm_template.c \ + stm32f7xx_hal_timebase_tim_template.c + +STDPERIPH_SRC := $(filter-out ${EXCLUDES}, $(STDPERIPH_SRC)) + +#USB +USBCORE_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Core +USBCORE_SRC = $(notdir $(wildcard $(USBCORE_DIR)/Src/*.c)) +EXCLUDES = usbd_conf_template.c +USBCORE_SRC := $(filter-out ${EXCLUDES}, $(USBCORE_SRC)) + +USBCDC_DIR = $(ROOT)/lib/main/Middlewares/ST/STM32_USB_Device_Library/Class/CDC +USBCDC_SRC = $(notdir $(wildcard $(USBCDC_DIR)/Src/*.c)) +EXCLUDES = usbd_cdc_if_template.c +USBCDC_SRC := $(filter-out ${EXCLUDES}, $(USBCDC_SRC)) + +VPATH := $(VPATH):$(USBCDC_DIR)/Src:$(USBCORE_DIR)/Src + +DEVICE_STDPERIPH_SRC := $(STDPERIPH_SRC) \ + $(USBCORE_SRC) \ + $(USBCDC_SRC) + +#CMSIS +VPATH := $(VPATH):$(CMSIS_DIR)/CM7/Include:$(CMSIS_DIR)/CM7/Device/ST/STM32F7xx +VPATH := $(VPATH):$(STDPERIPH_DIR)/Src +CMSIS_SRC = $(notdir $(wildcard $(CMSIS_DIR)/CM7/Include/*.c \ + $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/*.c)) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(STDPERIPH_DIR)/Inc \ + $(USBCORE_DIR)/Inc \ + $(USBCDC_DIR)/Inc \ + $(CMSIS_DIR)/CM7/Include \ + $(CMSIS_DIR)/CM7/Device/ST/STM32F7xx/Include \ + $(ROOT)/src/main/vcp_hal + +ifneq ($(filter SDCARD,$(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(FATFS_DIR) +VPATH := $(VPATH):$(FATFS_DIR) +endif + +#Flags +ARCH_FLAGS = -mthumb -mcpu=cortex-m7 -mfloat-abi=hard -mfpu=fpv5-sp-d16 -fsingle-precision-constant -Wdouble-promotion + +ifeq ($(TARGET),$(filter $(TARGET),$(F7X5XG_TARGETS))) +DEVICE_FLAGS = -DSTM32F745xx -DUSE_HAL_DRIVER -D__FPU_PRESENT +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f745.ld +else ifeq ($(TARGET),$(filter $(TARGET),$(F7X6XG_TARGETS))) +DEVICE_FLAGS = -DSTM32F746xx -DUSE_HAL_DRIVER -D__FPU_PRESENT +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f746.ld +else +$(error Unknown MCU for F7 target) +endif +DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) + +TARGET_FLAGS = -D$(TARGET) + +# End F7 targets +# +# Start F1 targets +else + +STDPERIPH_DIR = $(ROOT)/lib/main/STM32F10x_StdPeriph_Driver +STDPERIPH_SRC = $(notdir $(wildcard $(STDPERIPH_DIR)/src/*.c)) +EXCLUDES = stm32f10x_crc.c \ + stm32f10x_cec.c \ + stm32f10x_can.c + +STDPERIPH_SRC := $(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 \ + +DEVICE_STDPERIPH_SRC = $(STDPERIPH_SRC) + +ifneq ($(filter VCP, $(FEATURES)),) +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(USBFS_DIR)/inc \ + $(ROOT)/src/main/vcp + +VPATH := $(VPATH):$(USBFS_DIR)/src + +DEVICE_STDPERIPH_SRC := $(DEVICE_STDPERIPH_SRC) \ + $(USBPERIPH_SRC) + +endif + +LD_SCRIPT = $(LINKER_DIR)/stm32_flash_f103_$(FLASH_SIZE)k.ld +ARCH_FLAGS = -mthumb -mcpu=cortex-m3 + +ifeq ($(DEVICE_FLAGS),) +DEVICE_FLAGS = -DSTM32F10X_MD +endif +DEVICE_FLAGS += -DSTM32F10X + +endif +# +# End F1 targets +# +ifneq ($(BASE_TARGET), $(TARGET)) +TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET) +endif + +ifneq ($(FLASH_SIZE),) +DEVICE_FLAGS := $(DEVICE_FLAGS) -DFLASH_SIZE=$(FLASH_SIZE) +endif + +ifneq ($(HSE_VALUE),) +DEVICE_FLAGS := $(DEVICE_FLAGS) -DHSE_VALUE=$(HSE_VALUE) +endif + +TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) +TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) + +ifeq ($(OPBL),yes) +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 +endif +.DEFAULT_GOAL := binary +else +.DEFAULT_GOAL := hex +endif + +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(ROOT)/lib/main/MAVLink + +INCLUDE_DIRS := $(INCLUDE_DIRS) \ + $(TARGET_DIR) + +VPATH := $(VPATH):$(TARGET_DIR) + +COMMON_SRC = \ + build/build_config.c \ + build/debug.c \ + build/version.c \ + $(TARGET_DIR_SRC) \ + main.c \ + common/encoding.c \ + common/filter.c \ + common/maths.c \ + common/printf.c \ + common/streambuf.c \ + common/typeconversion.c \ + config/config_eeprom.c \ + config/feature.c \ + config/parameter_group.c \ + drivers/adc.c \ + drivers/buf_writer.c \ + drivers/bus_i2c_soft.c \ + drivers/bus_spi.c \ + drivers/bus_spi_soft.c \ + drivers/display.c \ + drivers/exti.c \ + drivers/gyro_sync.c \ + drivers/io.c \ + drivers/light_led.c \ + drivers/resource.c \ + drivers/rx_nrf24l01.c \ + drivers/rx_spi.c \ + drivers/rx_xn297.c \ + drivers/pwm_esc_detect.c \ + drivers/pwm_output.c \ + drivers/pwm_rx.c \ + drivers/rcc.c \ + drivers/serial.c \ + drivers/serial_uart.c \ + drivers/sound_beeper.c \ + drivers/stack_check.c \ + drivers/system.c \ + drivers/timer.c \ + fc/config.c \ + fc/fc_tasks.c \ + fc/fc_msp.c \ + fc/mw.c \ + fc/rc_controls.c \ + fc/rc_curves.c \ + fc/runtime_config.c \ + flight/altitudehold.c \ + flight/failsafe.c \ + flight/imu.c \ + flight/mixer.c \ + flight/pid.c \ + flight/servos.c \ + io/beeper.c \ + io/serial.c \ + io/serial_4way.c \ + io/serial_4way_avrootloader.c \ + io/serial_4way_stk500v2.c \ + io/serial_cli.c \ + io/statusindicator.c \ + msp/msp_serial.c \ + rx/ibus.c \ + rx/jetiexbus.c \ + rx/msp.c \ + rx/nrf24_cx10.c \ + rx/nrf24_inav.c \ + rx/nrf24_h8_3d.c \ + rx/nrf24_syma.c \ + rx/nrf24_v202.c \ + rx/pwm.c \ + rx/rx.c \ + rx/rx_spi.c \ + rx/crsf.c \ + rx/sbus.c \ + rx/spektrum.c \ + rx/sumd.c \ + rx/sumh.c \ + rx/xbus.c \ + scheduler/scheduler.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 \ + cms/cms.c \ + cms/cms_menu_blackbox.c \ + cms/cms_menu_builtin.c \ + cms/cms_menu_imu.c \ + cms/cms_menu_ledstrip.c \ + cms/cms_menu_misc.c \ + cms/cms_menu_osd.c \ + cms/cms_menu_vtx.c \ + common/colorconversion.c \ + drivers/display_ug2864hsweg01.c \ + drivers/light_ws2811strip.c \ + drivers/serial_escserial.c \ + drivers/serial_softserial.c \ + drivers/sonar_hcsr04.c \ + flight/gtune.c \ + flight/navigation.c \ + flight/gps_conversion.c \ + io/dashboard.c \ + io/displayport_max7456.c \ + io/displayport_msp.c \ + io/displayport_oled.c \ + io/gps.c \ + io/ledstrip.c \ + io/osd.c \ + sensors/sonar.c \ + sensors/barometer.c \ + telemetry/telemetry.c \ + telemetry/crsf.c \ + telemetry/frsky.c \ + telemetry/hott.c \ + telemetry/smartport.c \ + telemetry/ltm.c \ + telemetry/mavlink.c \ + sensors/esc_sensor.c \ + +SPEED_OPTIMISED_SRC := "" +SIZE_OPTIMISED_SRC := "" + +ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +SPEED_OPTIMISED_SRC := $(SPEED_OPTIMISED_SRC) \ + common/encoding.c \ + common/filter.c \ + common/maths.c \ + common/typeconversion.c \ + drivers/adc.c \ + drivers/buf_writer.c \ + drivers/bus_i2c_soft.c \ + drivers/bus_spi.c \ + drivers/bus_spi_soft.c \ + drivers/exti.c \ + drivers/gyro_sync.c \ + drivers/io.c \ + drivers/light_led.c \ + drivers/resource.c \ + drivers/rx_nrf24l01.c \ + drivers/rx_spi.c \ + drivers/rx_xn297.c \ + drivers/pwm_output.c \ + drivers/pwm_rx.c \ + drivers/rcc.c \ + drivers/serial.c \ + drivers/serial_uart.c \ + drivers/sound_beeper.c \ + drivers/stack_check.c \ + drivers/system.c \ + drivers/timer.c \ + fc/fc_tasks.c \ + fc/mw.c \ + fc/rc_controls.c \ + fc/rc_curves.c \ + fc/runtime_config.c \ + flight/altitudehold.c \ + flight/failsafe.c \ + flight/imu.c \ + flight/mixer.c \ + flight/pid.c \ + flight/servos.c \ + io/beeper.c \ + io/serial.c \ + io/statusindicator.c \ + rx/ibus.c \ + rx/jetiexbus.c \ + rx/msp.c \ + rx/nrf24_cx10.c \ + rx/nrf24_inav.c \ + rx/nrf24_h8_3d.c \ + rx/nrf24_syma.c \ + rx/nrf24_v202.c \ + rx/pwm.c \ + rx/rx.c \ + rx/rx_spi.c \ + rx/crsf.c \ + rx/sbus.c \ + rx/spektrum.c \ + rx/sumd.c \ + rx/sumh.c \ + rx/xbus.c \ + scheduler/scheduler.c \ + sensors/acceleration.c \ + sensors/boardalignment.c \ + sensors/gyro.c \ + $(CMSIS_SRC) \ + $(DEVICE_STDPERIPH_SRC) \ + blackbox/blackbox.c \ + blackbox/blackbox_io.c \ + drivers/display_ug2864hsweg01.c \ + drivers/light_ws2811strip.c \ + drivers/serial_softserial.c \ + io/dashboard.c \ + io/displayport_max7456.c \ + io/displayport_msp.c \ + io/displayport_oled.c \ + io/ledstrip.c \ + io/osd.c \ + telemetry/telemetry.c \ + telemetry/crsf.c \ + telemetry/frsky.c \ + telemetry/hott.c \ + telemetry/smartport.c \ + telemetry/ltm.c \ + telemetry/mavlink.c \ + telemetry/esc_telemetry.c \ + +SIZE_OPTIMISED_SRC := $(SIZE_OPTIMISED_SRC) \ + drivers/serial_escserial.c \ + io/serial_cli.c \ + io/serial_4way.c \ + io/serial_4way_avrootloader.c \ + io/serial_4way_stk500v2.c \ + msp/msp_serial.c \ + cms/cms.c \ + cms/cms_menu_blackbox.c \ + cms/cms_menu_builtin.c \ + cms/cms_menu_imu.c \ + cms/cms_menu_ledstrip.c \ + cms/cms_menu_misc.c \ + cms/cms_menu_osd.c \ +<<<<<<< HEAD + cms/cms_menu_vtx.c \ + io/vtx_smartaudio.c +======= + cms/cms_menu_vtx.c +endif #F3 +>>>>>>> betaflight/master + +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 ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS))) +VCP_SRC = \ + vcp_hal/usbd_desc.c \ + vcp_hal/usbd_conf.c \ + vcp_hal/usbd_cdc_interface.c \ + drivers/serial_usb_vcp_hal.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 +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/light_ws2811strip_stm32f10x.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/pwm_output_stm32f3xx.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/bus_i2c_stm32f10x.c \ + drivers/dma_stm32f4xx.c \ + drivers/gpio_stm32f4xx.c \ + drivers/inverter.c \ + drivers/light_ws2811strip_stm32f4xx.c \ + drivers/pwm_output_stm32f4xx.c \ + drivers/serial_uart_stm32f4xx.c \ + drivers/system_stm32f4xx.c \ + drivers/timer_stm32f4xx.c + +STM32F7xx_COMMON_SRC = \ + startup_stm32f745xx.s \ + target/system_stm32f7xx.c \ + drivers/accgyro_mpu.c \ + drivers/adc_stm32f7xx.c \ + drivers/bus_i2c_hal.c \ + drivers/dma_stm32f7xx.c \ + drivers/gpio_stm32f7xx.c \ + drivers/inverter.c \ + drivers/bus_spi_hal.c \ + drivers/pwm_output_stm32f7xx.c \ + drivers/timer_hal.c \ + drivers/timer_stm32f7xx.c \ + drivers/pwm_output_hal.c \ + drivers/system_stm32f7xx.c \ + drivers/serial_uart_stm32f7xx.c \ + drivers/serial_uart_hal.c + +F7EXCLUDES = drivers/bus_spi.c \ + drivers/bus_i2c.c \ + drivers/timer.c \ + drivers/pwm_output.c \ + drivers/serial_uart.c + +# check if target.mk supplied +ifeq ($(TARGET),$(filter $(TARGET),$(F4_TARGETS))) +TARGET_SRC := $(STM32F4xx_COMMON_SRC) $(TARGET_SRC) +else ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS))) +TARGET_SRC := $(STM32F7xx_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 + +ifneq ($(filter ONBOARDFLASH,$(FEATURES)),) +TARGET_SRC += \ + drivers/flash_m25p16.c \ + io/flashfs.c +endif + +ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS) $(F4_TARGETS) $(F3_TARGETS))) +TARGET_SRC += $(HIGHEND_SRC) +else ifneq ($(filter HIGHEND,$(FEATURES)),) +TARGET_SRC += $(HIGHEND_SRC) +endif + +TARGET_SRC += $(COMMON_SRC) +#excludes +ifeq ($(TARGET),$(filter $(TARGET),$(F7_TARGETS))) +TARGET_SRC := $(filter-out ${F7EXCLUDES}, $(TARGET_SRC)) +endif + +ifneq ($(filter SDCARD,$(FEATURES)),) +TARGET_SRC += \ + drivers/sdcard.c \ + drivers/sdcard_standard.c \ + io/asyncfatfs/asyncfatfs.c \ + io/asyncfatfs/fat_standard.c +endif + +ifneq ($(filter VCP,$(FEATURES)),) +TARGET_SRC += $(VCP_SRC) +endif +# end target specific make file checks + + +# Search path and source files for the ST stdperiph library +VPATH := $(VPATH):$(STDPERIPH_DIR)/src + +############################################################################### +# Things that might need changing to use different tools +# + +# Find out if ccache is installed on the system +CCACHE := ccache +RESULT = $(shell (which $(CCACHE) > /dev/null 2>&1; echo $$?) ) +ifneq ($(RESULT),0) +CCACHE := +endif + +# Tool names +CROSS_CC := $(CCACHE) $(ARM_SDK_PREFIX)gcc +CROSS_CXX := $(CCACHE) $(ARM_SDK_PREFIX)g++ +OBJCOPY := $(ARM_SDK_PREFIX)objcopy +SIZE := $(ARM_SDK_PREFIX)size + +# +# Tool options. +# + +ifneq ($(DEBUG),GDB) +OPTIMISATION_BASE := -flto -fuse-linker-plugin -ffast-math +OPTIMISE_SPEED := "" +OPTIMISE_SIZE := "" + +ifeq ($(TARGET),$(filter $(TARGET),$(F1_TARGETS))) +OPTIMISE_DEFAULT := -Os + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) + +else ifeq ($(TARGET),$(filter $(TARGET),$(F3_TARGETS))) +OPTIMISE_DEFAULT := -O2 +OPTIMISE_SPEED := -Ofast +OPTIMISE_SIZE := -Os + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) + +else +OPTIMISE_DEFAULT := -Ofast + +LTO_FLAGS := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) + +endif #TARGETS + +CC_DEFAULT_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_DEFAULT) +CC_SPEED_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SPEED) +CC_SIZE_OPTIMISATION := $(OPTIMISATION_BASE) $(OPTIMISE_SIZE) + +else #DEBUG +OPTIMISE_DEFAULT := -O0 + +CC_DEBUG_OPTIMISATION := $(OPTIMISE_DEFAULT) + +LTO_FLAGS := $(OPTIMISE_DEFAULT) +endif #DEBUG + +DEBUG_FLAGS = -ggdb3 -DDEBUG + +CFLAGS += $(ARCH_FLAGS) \ + $(addprefix -D,$(OPTIONS)) \ + $(addprefix -I,$(INCLUDE_DIRS)) \ + $(DEBUG_FLAGS) \ + -std=gnu99 \ + -Wall -Wextra -Wunsafe-loop-optimizations -Wdouble-promotion \ + -ffunction-sections \ + -fdata-sections \ + -pedantic \ + $(DEVICE_FLAGS) \ + -DUSE_STDPERIPH_DRIVER \ + -D$(TARGET) \ + $(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 + +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 \ + -Wl,--no-wchar-size-warning \ + -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 + +# +# Things we will build +# +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_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map + + +CLEAN_ARTIFACTS := $(TARGET_BIN) +CLEAN_ARTIFACTS += $(TARGET_HEX) +CLEAN_ARTIFACTS += $(TARGET_ELF) $(TARGET_OBJS) $(TARGET_MAP) + +# Make sure build date and revision is updated on every incremental build +$(OBJECT_DIR)/$(TARGET)/build/version.o : $(TARGET_SRC) + +# List of buildable ELF files and their object dependencies. +# It would be nice to compute these lists, but that seems to be just beyond make. + +$(TARGET_HEX): $(TARGET_ELF) + $(V0) $(OBJCOPY) -O ihex --set-start 0x8000000 $< $@ + +$(TARGET_BIN): $(TARGET_ELF) + $(V0) $(OBJCOPY) -O binary $< $@ + +$(TARGET_ELF): $(TARGET_OBJS) + $(V1) echo Linking $(TARGET) + $(V1) $(CROSS_CC) -o $@ $^ $(LDFLAGS) + $(V0) $(SIZE) $(TARGET_ELF) + +# Compile +ifneq ($(DEBUG),GDB) +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(V1) mkdir -p $(dir $@) + $(V1) $(if $(findstring $(subst ./src/main/,,$<),$(SPEED_OPTIMISED_SRC)), \ + echo "%% (speed optimised) $(notdir $<)" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_SPEED_OPTIMISATION) $<, \ + $(if $(findstring $(subst ./src/main/,,$<),$(SIZE_OPTIMISED_SRC)), \ + echo "%% (size optimised) $(notdir $<)" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_SIZE_OPTIMISATION) $<, \ + echo "%% $(notdir $<)" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_DEFAULT_OPTIMISATION) $<)) +else +$(OBJECT_DIR)/$(TARGET)/%.o: %.c + $(V1) mkdir -p $(dir $@) + $(V1) echo "%% $(notdir $<)" "$(STDOUT)" && \ + $(CROSS_CC) -c -o $@ $(CFLAGS) $(CC_DEBUG_OPTIMISATION) $< +endif + +# Assemble +$(OBJECT_DIR)/$(TARGET)/%.o: %.s + $(V1) mkdir -p $(dir $@) + $(V1) echo "%% $(notdir $<)" "$(STDOUT)" + $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< + +$(OBJECT_DIR)/$(TARGET)/%.o: %.S + $(V1) mkdir -p $(dir $@) + $(V1) echo "%% $(notdir $<)" "$(STDOUT)" + $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< + +## sample : Build all sample (travis) targets +sample: $(SAMPLE_TARGETS) + +## all : Build all valid targets +all: $(VALID_TARGETS) + +$(VALID_TARGETS): + $(V0) echo "" && \ + echo "Building $@" && \ + $(MAKE) binary hex TARGET=$@ && \ + echo "Building $@ succeeded." + + + +CLEAN_TARGETS = $(addprefix clean_,$(VALID_TARGETS) ) +TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS) ) + +## clean : clean up temporary / machine-generated files +clean: + $(V0) echo "Cleaning $(TARGET)" + $(V0) rm -f $(CLEAN_ARTIFACTS) + $(V0) rm -rf $(OBJECT_DIR)/$(TARGET) + $(V0) echo "Cleaning $(TARGET) succeeded." + +## clean_test : clean up temporary / machine-generated files (tests) +clean_test: + $(V0) cd src/test && $(MAKE) clean || true + +## clean_ : clean up one specific target +$(CLEAN_TARGETS) : + $(V0) $(MAKE) -j TARGET=$(subst clean_,,$@) clean + +## _clean : clean up one specific target (alias for above) +$(TARGETS_CLEAN) : + $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean + +## clean_all : clean all valid targets +clean_all:$(CLEAN_TARGETS) + +## all_clean : clean all valid targets (alias for above) +all_clean:$(TARGETS_CLEAN) + + +flash_$(TARGET): $(TARGET_HEX) + $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + $(V0) echo -n 'R' >$(SERIAL_DEVICE) + $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +## flash : flash firmware (.hex) onto flight controller +flash: flash_$(TARGET) + +st-flash_$(TARGET): $(TARGET_BIN) + $(V0) st-flash --reset write $< 0x08000000 + +## st-flash : flash firmware (.bin) onto flight controller +st-flash: st-flash_$(TARGET) + +binary: + $(V0) $(MAKE) -j $(TARGET_BIN) + +hex: + $(V0) $(MAKE) -j $(TARGET_HEX) + +unbrick_$(TARGET): $(TARGET_HEX) + $(V0) stty -F $(SERIAL_DEVICE) raw speed 115200 -crtscts cs8 -parenb -cstopb -ixon + $(V0) stm32flash -w $(TARGET_HEX) -v -g 0x0 -b 115200 $(SERIAL_DEVICE) + +## unbrick : unbrick flight controller +unbrick: unbrick_$(TARGET) + +## cppcheck : run static analysis on C source code +cppcheck: $(CSOURCES) + $(V0) $(CPPCHECK) + +cppcheck-result.xml: $(CSOURCES) + $(V0) $(CPPCHECK) --xml-version=2 2> cppcheck-result.xml + +# mkdirs +$(DL_DIR): + mkdir -p $@ + +$(TOOLS_DIR): + mkdir -p $@ + +$(BUILD_DIR): + mkdir -p $@ + +## help : print this help message and exit +help: Makefile make/tools.mk + $(V0) @echo "" + $(V0) @echo "Makefile for the $(FORKNAME) firmware" + $(V0) @echo "" + $(V0) @echo "Usage:" + $(V0) @echo " make [V=] [TARGET=] [OPTIONS=\"\"]" + $(V0) @echo "Or:" + $(V0) @echo " make [V=] [OPTIONS=\"\"]" + $(V0) @echo "" + $(V0) @echo "Valid TARGET values are: $(VALID_TARGETS)" + $(V0) @echo "" + $(V0) @sed -n 's/^## //p' $? + +## targets : print a list of all valid target platforms (for consumption by scripts) +targets: + $(V0) @echo "Valid targets: $(VALID_TARGETS)" + $(V0) @echo "Target: $(TARGET)" + $(V0) @echo "Base target: $(BASE_TARGET)" + +## test : run the cleanflight test suite +## junittest : run the cleanflight test suite, producing Junit XML result files. +test junittest: + $(V0) cd src/test && $(MAKE) $@ + +# rebuild everything when makefile changes +$(TARGET_OBJS) : Makefile + +# include auto-generated dependencies +-include $(TARGET_DEPS) diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index dcae209230..9f74d479c8 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1201,7 +1201,7 @@ static bool blackboxWriteSysinfo() BLACKBOX_PRINT_HEADER_LINE("looptime:%d", gyro.targetLooptime); BLACKBOX_PRINT_HEADER_LINE("gyro_sync_denom:%d", gyroConfig()->gyro_sync_denom); - BLACKBOX_PRINT_HEADER_LINE("pid_process_denom:%d", masterConfig.pid_process_denom); + BLACKBOX_PRINT_HEADER_LINE("pid_process_denom:%d", pidConfig()->pid_process_denom); BLACKBOX_PRINT_HEADER_LINE("rcRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcRate8); BLACKBOX_PRINT_HEADER_LINE("rcExpo:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcExpo8); BLACKBOX_PRINT_HEADER_LINE("rcYawRate:%d", masterConfig.profile[masterConfig.current_profile_index].controlRateProfile[masterConfig.profile[masterConfig.current_profile_index].activeRateProfile].rcYawRate8); diff --git a/src/main/common/filter.c b/src/main/common/filter.c index 5b580a14e1..f3582f213e 100644 --- a/src/main/common/filter.c +++ b/src/main/common/filter.c @@ -46,11 +46,12 @@ void pt1FilterInit(pt1Filter_t *filter, uint8_t f_cut, float dT) { filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut ); filter->dT = dT; + filter->k = filter->dT / (filter->RC + filter->dT); } float pt1FilterApply(pt1Filter_t *filter, float input) { - filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state); + filter->state = filter->state + filter->k * (input - filter->state); return filter->state; } @@ -60,9 +61,10 @@ float pt1FilterApply4(pt1Filter_t *filter, float input, uint8_t f_cut, float dT) if (!filter->RC) { filter->RC = 1.0f / ( 2.0f * M_PI_FLOAT * f_cut ); filter->dT = dT; + filter->k = filter->dT / (filter->RC + filter->dT); } - filter->state = filter->state + filter->dT / (filter->RC + filter->dT) * (input - filter->state); + filter->state = filter->state + filter->k * (input - filter->state); return filter->state; } @@ -89,22 +91,22 @@ void biquadFilterInit(biquadFilter_t *filter, float filterFreq, uint32_t refresh float b0 = 0, b1 = 0, b2 = 0, a0 = 0, a1 = 0, a2 = 0; switch (filterType) { - case FILTER_LPF: - b0 = (1 - cs) / 2; - b1 = 1 - cs; - b2 = (1 - cs) / 2; - a0 = 1 + alpha; - a1 = -2 * cs; - a2 = 1 - alpha; - break; - case FILTER_NOTCH: - b0 = 1; - b1 = -2 * cs; - b2 = 1; - a0 = 1 + alpha; - a1 = -2 * cs; - a2 = 1 - alpha; - break; + case FILTER_LPF: + b0 = (1 - cs) / 2; + b1 = 1 - cs; + b2 = (1 - cs) / 2; + a0 = 1 + alpha; + a1 = -2 * cs; + a2 = 1 - alpha; + break; + case FILTER_NOTCH: + b0 = 1; + b1 = -2 * cs; + b2 = 1; + a0 = 1 + alpha; + a1 = -2 * cs; + a2 = 1 - alpha; + break; } // precompute the coefficients diff --git a/src/main/common/filter.h b/src/main/common/filter.h index 35b5ca8f15..4d86bc431e 100644 --- a/src/main/common/filter.h +++ b/src/main/common/filter.h @@ -25,6 +25,7 @@ typedef struct pt1Filter_s { float state; + float k; float RC; float dT; } pt1Filter_t; diff --git a/src/main/common/maths.h b/src/main/common/maths.h index 61675514ee..78fd819d77 100644 --- a/src/main/common/maths.h +++ b/src/main/common/maths.h @@ -20,6 +20,7 @@ #ifndef sq #define sq(x) ((x)*(x)) #endif +#define power3(x) ((x)*(x)*(x)) // Undefine this for use libc sinf/cosf. Keep this defined to use fast sin/cos approximations #define FAST_MATH // order 9 approximation diff --git a/src/main/config/config_master.h b/src/main/config/config_master.h index 45af459a73..1f80b79d4c 100644 --- a/src/main/config/config_master.h +++ b/src/main/config/config_master.h @@ -98,6 +98,7 @@ #define sdcardConfig(x) (&masterConfig.sdcardConfig) #define blackboxConfig(x) (&masterConfig.blackboxConfig) #define flashConfig(x) (&masterConfig.flashConfig) +#define pidConfig(x) (&masterConfig.pidConfig) // System-wide @@ -128,9 +129,8 @@ typedef struct master_s { imuConfig_t imuConfig; rollAndPitchTrims_t accelerometerTrims; // accelerometer trim - uint16_t max_angle_inclination; // max inclination allowed in angle (level) mode. default 500 (50 degrees). - uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate + pidConfig_t pidConfig; uint8_t debug_mode; // Processing denominator for PID controller vs gyro sampling rate @@ -154,7 +154,6 @@ typedef struct master_s { #endif rxConfig_t rxConfig; - inputFilteringMode_e inputFilteringMode; // Use hardware input filtering, e.g. for OrangeRX PPM/PWM receivers. armingConfig_t armingConfig; diff --git a/src/main/drivers/accgyro.h b/src/main/drivers/accgyro.h index 9dbd6f6dd2..746279a452 100644 --- a/src/main/drivers/accgyro.h +++ b/src/main/drivers/accgyro.h @@ -18,6 +18,7 @@ #pragma once #include "common/axis.h" +#include "drivers/exti.h" #include "drivers/sensor.h" #ifndef MPU_I2C_INSTANCE @@ -35,9 +36,10 @@ typedef struct gyroDev_s { sensorGyroInitFuncPtr init; // initialize function - sensorGyroReadFuncPtr read; // read 3 axis data function - sensorReadFuncPtr temperature; // read temperature if available + sensorGyroReadFuncPtr read; // read 3 axis data function + sensorGyroReadDataFuncPtr temperature; // read temperature if available sensorGyroInterruptStatusFuncPtr intStatus; + extiCallbackRec_t exti; float scale; // scalefactor volatile bool dataReady; uint16_t lpf; @@ -46,9 +48,10 @@ typedef struct gyroDev_s { } gyroDev_t; typedef struct accDev_s { - sensorAccInitFuncPtr init; // initialize function - sensorReadFuncPtr read; // read 3 axis data function + sensorAccInitFuncPtr init; // initialize function + sensorAccReadFuncPtr read; // read 3 axis data function uint16_t acc_1G; + int16_t ADCRaw[XYZ_AXIS_COUNT]; char revisionCode; // a revision code for the sensor, if known sensor_align_e accAlign; } accDev_t; diff --git a/src/main/drivers/accgyro_adxl345.c b/src/main/drivers/accgyro_adxl345.c index 122062318b..9e2b623b40 100644 --- a/src/main/drivers/accgyro_adxl345.c +++ b/src/main/drivers/accgyro_adxl345.c @@ -76,7 +76,7 @@ static void adxl345Init(accDev_t *acc) uint8_t acc_samples = 0; -static bool adxl345Read(int16_t *accelData) +static bool adxl345Read(accDev_t *acc) { uint8_t buf[8]; @@ -99,9 +99,9 @@ static bool adxl345Read(int16_t *accelData) z += (int16_t)(buf[4] + (buf[5] << 8)); samples_remaining = buf[7] & 0x7F; } while ((i < 32) && (samples_remaining > 0)); - accelData[0] = x / i; - accelData[1] = y / i; - accelData[2] = z / i; + acc->ADCRaw[0] = x / i; + acc->ADCRaw[1] = y / i; + acc->ADCRaw[2] = z / i; acc_samples = i; } else { @@ -109,9 +109,9 @@ static bool adxl345Read(int16_t *accelData) return false; } - accelData[0] = buf[0] + (buf[1] << 8); - accelData[1] = buf[2] + (buf[3] << 8); - accelData[2] = buf[4] + (buf[5] << 8); + acc->ADCRaw[0] = buf[0] + (buf[1] << 8); + acc->ADCRaw[1] = buf[2] + (buf[3] << 8); + acc->ADCRaw[2] = buf[4] + (buf[5] << 8); } return true; diff --git a/src/main/drivers/accgyro_bma280.c b/src/main/drivers/accgyro_bma280.c index 3c285a9428..f65b22286a 100644 --- a/src/main/drivers/accgyro_bma280.c +++ b/src/main/drivers/accgyro_bma280.c @@ -40,7 +40,7 @@ static void bma280Init(accDev_t *acc) acc->acc_1G = 512 * 8; } -static bool bma280Read(int16_t *accelData) +static bool bma280Read(accDev_t *acc) { uint8_t buf[6]; @@ -49,9 +49,9 @@ static bool bma280Read(int16_t *accelData) } // Data format is lsb<5:0> | msb<13:6> - accelData[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8)); - accelData[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8)); - accelData[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8)); + acc->ADCRaw[0] = (int16_t)((buf[0] >> 2) + (buf[1] << 8)); + acc->ADCRaw[1] = (int16_t)((buf[2] >> 2) + (buf[3] << 8)); + acc->ADCRaw[2] = (int16_t)((buf[4] >> 2) + (buf[5] << 8)); return true; } diff --git a/src/main/drivers/accgyro_fake.c b/src/main/drivers/accgyro_fake.c index c592f01846..9e661f55a6 100644 --- a/src/main/drivers/accgyro_fake.c +++ b/src/main/drivers/accgyro_fake.c @@ -51,9 +51,10 @@ static bool fakeGyroRead(gyroDev_t *gyro) return true; } -static bool fakeGyroReadTemperature(int16_t *tempData) +static bool fakeGyroReadTemperature(gyroDev_t *gyro, int16_t *temperatureData) { - UNUSED(tempData); + UNUSED(gyro); + UNUSED(temperatureData); return true; } @@ -91,11 +92,11 @@ void fakeAccSet(int16_t x, int16_t y, int16_t z) fakeAccData[Z] = z; } -static bool fakeAccRead(int16_t *accData) +static bool fakeAccRead(accDev_t *acc) { - accData[X] = fakeAccData[X]; - accData[Y] = fakeAccData[Y]; - accData[Z] = fakeAccData[Z]; + acc->ADCRaw[X] = fakeAccData[X]; + acc->ADCRaw[Y] = fakeAccData[Y]; + acc->ADCRaw[Z] = fakeAccData[Z]; return true; } diff --git a/src/main/drivers/accgyro_lsm303dlhc.c b/src/main/drivers/accgyro_lsm303dlhc.c index 71baf89f15..ade701a38f 100644 --- a/src/main/drivers/accgyro_lsm303dlhc.c +++ b/src/main/drivers/accgyro_lsm303dlhc.c @@ -133,7 +133,7 @@ void lsm303dlhcAccInit(accDev_t *acc) } // Read 3 gyro values into user-provided buffer. No overrun checking is done. -static bool lsm303dlhcAccRead(int16_t *gyroADC) +static bool lsm303dlhcAccRead(accDev_t *acc) { uint8_t buf[6]; @@ -144,9 +144,9 @@ static bool lsm303dlhcAccRead(int16_t *gyroADC) } // the values range from -8192 to +8191 - gyroADC[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2; - gyroADC[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2; - gyroADC[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2; + acc->ADCRaw[X] = (int16_t)((buf[1] << 8) | buf[0]) / 2; + acc->ADCRaw[Y] = (int16_t)((buf[3] << 8) | buf[2]) / 2; + acc->ADCRaw[Z] = (int16_t)((buf[5] << 8) | buf[4]) / 2; #if 0 debug[0] = (int16_t)((buf[1] << 8) | buf[0]); diff --git a/src/main/drivers/accgyro_mma845x.c b/src/main/drivers/accgyro_mma845x.c index 7dcb4ed194..96fed71c3b 100644 --- a/src/main/drivers/accgyro_mma845x.c +++ b/src/main/drivers/accgyro_mma845x.c @@ -111,7 +111,7 @@ static void mma8452Init(accDev_t *acc) acc->acc_1G = 256; } -static bool mma8452Read(int16_t *accelData) +static bool mma8452Read(accDev_t *acc) { uint8_t buf[6]; @@ -119,9 +119,9 @@ static bool mma8452Read(int16_t *accelData) return false; } - accelData[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4; - accelData[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4; - accelData[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4; + acc->ADCRaw[0] = ((int16_t)((buf[0] << 8) | buf[1]) >> 2) / 4; + acc->ADCRaw[1] = ((int16_t)((buf[2] << 8) | buf[3]) >> 2) / 4; + acc->ADCRaw[2] = ((int16_t)((buf[4] << 8) | buf[5]) >> 2) / 4; return true; } diff --git a/src/main/drivers/accgyro_mpu.c b/src/main/drivers/accgyro_mpu.c index 7c87b8fddd..d1ee898eec 100644 --- a/src/main/drivers/accgyro_mpu.c +++ b/src/main/drivers/accgyro_mpu.c @@ -221,21 +221,13 @@ static void mpu6050FindRevision(void) } } -typedef struct mpuIntRec_s { - extiCallbackRec_t exti; - gyroDev_t *gyro; -} mpuIntRec_t; - -mpuIntRec_t mpuIntRec; - /* * Gyro interrupt service routine */ #if defined(MPU_INT_EXTI) static void mpuIntExtiHandler(extiCallbackRec_t *cb) { - mpuIntRec_t *rec = container_of(cb, mpuIntRec_t, exti); - gyroDev_t *gyro = rec->gyro; + gyroDev_t *gyro = container_of(cb, gyroDev_t, exti); gyro->dataReady = true; #ifdef DEBUG_MPU_DATA_READY_INTERRUPT @@ -250,7 +242,6 @@ static void mpuIntExtiHandler(extiCallbackRec_t *cb) static void mpuIntExtiInit(gyroDev_t *gyro) { - mpuIntRec.gyro = gyro; #if defined(MPU_INT_EXTI) static bool mpuExtiInitDone = false; @@ -269,19 +260,21 @@ static void mpuIntExtiInit(gyroDev_t *gyro) #if defined (STM32F7) IOInit(mpuIntIO, OWNER_MPU_EXTI, 0); - EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler); - EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ? + EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler); + EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, IO_CONFIG(GPIO_MODE_INPUT,0,GPIO_NOPULL)); // TODO - maybe pullup / pulldown ? #else IOInit(mpuIntIO, OWNER_MPU_EXTI, 0); IOConfigGPIO(mpuIntIO, IOCFG_IN_FLOATING); // TODO - maybe pullup / pulldown ? - EXTIHandlerInit(&mpuIntRec.exti, mpuIntExtiHandler); - EXTIConfig(mpuIntIO, &mpuIntRec.exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); + EXTIHandlerInit(&gyro->exti, mpuIntExtiHandler); + EXTIConfig(mpuIntIO, &gyro->exti, NVIC_PRIO_MPU_INT_EXTI, EXTI_Trigger_Rising); EXTIEnable(mpuIntIO, true); #endif mpuExtiInitDone = true; +#else + UNUSED(gyro); #endif } @@ -297,7 +290,7 @@ static bool mpuWriteRegisterI2C(uint8_t reg, uint8_t data) return ack; } -bool mpuAccRead(int16_t *accData) +bool mpuAccRead(accDev_t *acc) { uint8_t data[6]; @@ -306,9 +299,9 @@ bool mpuAccRead(int16_t *accData) return false; } - accData[0] = (int16_t)((data[0] << 8) | data[1]); - accData[1] = (int16_t)((data[2] << 8) | data[3]); - accData[2] = (int16_t)((data[4] << 8) | data[5]); + acc->ADCRaw[X] = (int16_t)((data[0] << 8) | data[1]); + acc->ADCRaw[Y] = (int16_t)((data[2] << 8) | data[3]); + acc->ADCRaw[Z] = (int16_t)((data[4] << 8) | data[5]); return true; } diff --git a/src/main/drivers/accgyro_mpu.h b/src/main/drivers/accgyro_mpu.h index cb97af5cec..bca217fb21 100644 --- a/src/main/drivers/accgyro_mpu.h +++ b/src/main/drivers/accgyro_mpu.h @@ -186,7 +186,8 @@ extern mpuDetectionResult_t mpuDetectionResult; void mpuConfigureDataReadyInterruptHandling(void); struct gyroDev_s; void mpuGyroInit(struct gyroDev_s *gyro); -bool mpuAccRead(int16_t *accData); +struct accDev_s; +bool mpuAccRead(struct accDev_s *acc); bool mpuGyroRead(struct gyroDev_s *gyro); mpuDetectionResult_t *mpuDetect(const extiConfig_t *configToUse); bool mpuCheckDataReady(struct gyroDev_s *gyro); diff --git a/src/main/drivers/accgyro_mpu3050.c b/src/main/drivers/accgyro_mpu3050.c index fe4692c205..baf605e575 100644 --- a/src/main/drivers/accgyro_mpu3050.c +++ b/src/main/drivers/accgyro_mpu3050.c @@ -21,6 +21,7 @@ #include "platform.h" #include "common/maths.h" +#include "common/utils.h" #include "system.h" #include "exti.h" @@ -62,8 +63,9 @@ static void mpu3050Init(gyroDev_t *gyro) mpuConfiguration.write(MPU3050_PWR_MGM, MPU3050_CLK_SEL_PLL_GX); } -static bool mpu3050ReadTemperature(int16_t *tempData) +static bool mpu3050ReadTemperature(gyroDev_t *gyro, int16_t *tempData) { + UNUSED(gyro); uint8_t buf[2]; if (!mpuConfiguration.read(MPU3050_TEMP_OUT, 2, buf)) { return false; diff --git a/src/main/drivers/bus_i2c_stm32f10x.c b/src/main/drivers/bus_i2c_stm32f10x.c index 0849a03561..f31f05205d 100644 --- a/src/main/drivers/bus_i2c_stm32f10x.c +++ b/src/main/drivers/bus_i2c_stm32f10x.c @@ -79,7 +79,7 @@ static void i2cUnstick(IO_t scl, IO_t sda); #define I2C3_SCL PA8 #endif #ifndef I2C3_SDA -#define I2C3_SDA PB4 +#define I2C3_SDA PC9 #endif #endif diff --git a/src/main/drivers/compass_ak8963.c b/src/main/drivers/compass_ak8963.c index fb280f8ae3..53f72e202c 100644 --- a/src/main/drivers/compass_ak8963.c +++ b/src/main/drivers/compass_ak8963.c @@ -42,9 +42,6 @@ #include "accgyro_spi_mpu9250.h" #include "compass_ak8963.h" -void ak8963Init(void); -bool ak8963Read(int16_t *magData); - // This sensor is available in MPU-9250. // AK8963, mag sensor address @@ -110,7 +107,7 @@ typedef enum { static queuedReadState_t queuedRead = { false, 0, 0}; -bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) +static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) { verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_ | READ_FLAG); // set I2C slave address for read verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register @@ -122,7 +119,7 @@ bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len_, uint8_t *buf) return true; } -bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) { verifympu9250WriteRegister(MPU_RA_I2C_SLV0_ADDR, addr_); // set I2C slave address for write verifympu9250WriteRegister(MPU_RA_I2C_SLV0_REG, reg_); // set I2C slave register @@ -131,7 +128,7 @@ bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) return true; } -bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_) +static bool ak8963SensorStartRead(uint8_t addr_, uint8_t reg_, uint8_t len_) { if (queuedRead.waiting) { return false; @@ -166,7 +163,7 @@ static uint32_t ak8963SensorQueuedReadTimeRemaining(void) return timeRemaining; } -bool ak8963SensorCompleteRead(uint8_t *buf) +static bool ak8963SensorCompleteRead(uint8_t *buf) { uint32_t timeRemaining = ak8963SensorQueuedReadTimeRemaining(); @@ -180,47 +177,18 @@ bool ak8963SensorCompleteRead(uint8_t *buf) return true; } #else -bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) +static bool ak8963SensorRead(uint8_t addr_, uint8_t reg_, uint8_t len, uint8_t* buf) { return i2cRead(MAG_I2C_INSTANCE, addr_, reg_, len, buf); } -bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) +static bool ak8963SensorWrite(uint8_t addr_, uint8_t reg_, uint8_t data) { return i2cWrite(MAG_I2C_INSTANCE, addr_, reg_, data); } #endif -bool ak8963Detect(magDev_t *mag) -{ - uint8_t sig = 0; - -#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) - // initialze I2C master via SPI bus (MPU9250) - - verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR - delay(10); - - verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz - delay(10); - - verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only - delay(10); -#endif - - // check for AK8963 - bool ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); - if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' - { - mag->init = ak8963Init; - mag->read = ak8963Read; - - return true; - } - return false; -} - -void ak8963Init() +static bool ak8963Init() { uint8_t calibration[3]; uint8_t status; @@ -251,9 +219,10 @@ void ak8963Init() #else ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); #endif + return true; } -bool ak8963Read(int16_t *magData) +static bool ak8963Read(int16_t *magData) { bool ack = false; uint8_t buf[7]; @@ -339,3 +308,32 @@ restart: return ak8963SensorWrite(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_CNTL, CNTL_MODE_ONCE); // start reading again #endif } + +bool ak8963Detect(magDev_t *mag) +{ + uint8_t sig = 0; + +#if defined(USE_SPI) && defined(MPU9250_SPI_INSTANCE) + // initialze I2C master via SPI bus (MPU9250) + + verifympu9250WriteRegister(MPU_RA_INT_PIN_CFG, 0x10); // INT_ANYRD_2CLEAR + delay(10); + + verifympu9250WriteRegister(MPU_RA_I2C_MST_CTRL, 0x0D); // I2C multi-master / 400kHz + delay(10); + + verifympu9250WriteRegister(MPU_RA_USER_CTRL, 0x30); // I2C master mode, SPI mode only + delay(10); +#endif + + // check for AK8963 + bool ack = ak8963SensorRead(AK8963_MAG_I2C_ADDRESS, AK8963_MAG_REG_WHO_AM_I, 1, &sig); + if (ack && sig == AK8963_Device_ID) // 0x48 / 01001000 / 'H' + { + mag->init = ak8963Init; + mag->read = ak8963Read; + + return true; + } + return false; +} diff --git a/src/main/drivers/compass_ak8975.c b/src/main/drivers/compass_ak8975.c index 579c7118cb..d2856496f8 100644 --- a/src/main/drivers/compass_ak8975.c +++ b/src/main/drivers/compass_ak8975.c @@ -37,9 +37,6 @@ #include "compass_ak8975.h" -void ak8975Init(void); -bool ak8975Read(int16_t *magData); - // This sensor is available in MPU-9150. // AK8975, mag sensor address @@ -60,25 +57,11 @@ bool ak8975Read(int16_t *magData); #define AK8975_MAG_REG_CNTL 0x0a #define AK8975_MAG_REG_ASCT 0x0c // self test -bool ak8975Detect(magDev_t *mag) -{ - uint8_t sig = 0; - bool ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig); - - if (!ack || sig != 'H') // 0x48 / 01001000 / 'H' - return false; - - mag->init = ak8975Init; - mag->read = ak8975Read; - - return true; -} - #define AK8975A_ASAX 0x10 // Fuse ROM x-axis sensitivity adjustment value #define AK8975A_ASAY 0x11 // Fuse ROM y-axis sensitivity adjustment value #define AK8975A_ASAZ 0x12 // Fuse ROM z-axis sensitivity adjustment value -void ak8975Init() +static bool ak8975Init() { uint8_t buffer[3]; uint8_t status; @@ -101,6 +84,7 @@ void ak8975Init() // Trigger first measurement i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); + return true; } #define BIT_STATUS1_REG_DATA_READY (1 << 0) @@ -108,7 +92,7 @@ void ak8975Init() #define BIT_STATUS2_REG_DATA_ERROR (1 << 2) #define BIT_STATUS2_REG_MAG_SENSOR_OVERFLOW (1 << 3) -bool ak8975Read(int16_t *magData) +static bool ak8975Read(int16_t *magData) { bool ack; uint8_t status; @@ -142,4 +126,18 @@ bool ak8975Read(int16_t *magData) i2cWrite(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_CNTL, 0x01); // start reading again return true; } + +bool ak8975Detect(magDev_t *mag) +{ + uint8_t sig = 0; + bool ack = i2cRead(MAG_I2C_INSTANCE, AK8975_MAG_I2C_ADDRESS, AK8975_MAG_REG_WHO_AM_I, 1, &sig); + + if (!ack || sig != 'H') // 0x48 / 01001000 / 'H' + return false; + + mag->init = ak8975Init; + mag->read = ak8975Read; + + return true; +} #endif diff --git a/src/main/drivers/compass_fake.c b/src/main/drivers/compass_fake.c index 20b58b1a16..cb8098c77d 100644 --- a/src/main/drivers/compass_fake.c +++ b/src/main/drivers/compass_fake.c @@ -32,12 +32,13 @@ static int16_t fakeMagData[XYZ_AXIS_COUNT]; -static void fakeMagInit(void) +static bool fakeMagInit(void) { // initially point north fakeMagData[X] = 4096; fakeMagData[Y] = 0; fakeMagData[Z] = 0; + return true; } void fakeMagSet(int16_t x, int16_t y, int16_t z) diff --git a/src/main/drivers/compass_hmc5883l.c b/src/main/drivers/compass_hmc5883l.c index d4e802597b..ff0cd12d22 100644 --- a/src/main/drivers/compass_hmc5883l.c +++ b/src/main/drivers/compass_hmc5883l.c @@ -41,9 +41,6 @@ #include "compass_hmc5883l.h" -void hmc5883lInit(void); -bool hmc5883lRead(int16_t *magData); - //#define DEBUG_MAG_DATA_READY_INTERRUPT // HMC5883L, default address 0x1E @@ -129,7 +126,7 @@ static const hmc5883Config_t *hmc5883Config = NULL; static IO_t intIO; static extiCallbackRec_t hmc5883_extiCallbackRec; -void hmc5883_extiHandler(extiCallbackRec_t* cb) +static void hmc5883_extiHandler(extiCallbackRec_t* cb) { UNUSED(cb); #ifdef DEBUG_MAG_DATA_READY_INTERRUPT @@ -170,23 +167,24 @@ static void hmc5883lConfigureDataReadyInterruptHandling(void) #endif } -bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse) +static bool hmc5883lRead(int16_t *magData) { - hmc5883Config = hmc5883ConfigToUse; + uint8_t buf[6]; - uint8_t sig = 0; - bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig); - - if (!ack || sig != 'H') + bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); + if (!ack) { return false; - - mag->init = hmc5883lInit; - mag->read = hmc5883lRead; + } + // During calibration, magGain is 1.0, so the read returns normal non-calibrated values. + // After calibration is done, magGain is set to calculated gain values. + magData[X] = (int16_t)(buf[0] << 8 | buf[1]) * magGain[X]; + magData[Z] = (int16_t)(buf[2] << 8 | buf[3]) * magGain[Z]; + magData[Y] = (int16_t)(buf[4] << 8 | buf[5]) * magGain[Y]; return true; } -void hmc5883lInit(void) +static bool hmc5883lInit(void) { int16_t magADC[3]; int i; @@ -256,21 +254,21 @@ void hmc5883lInit(void) } hmc5883lConfigureDataReadyInterruptHandling(); + return true; } -bool hmc5883lRead(int16_t *magData) +bool hmc5883lDetect(magDev_t* mag, const hmc5883Config_t *hmc5883ConfigToUse) { - uint8_t buf[6]; + hmc5883Config = hmc5883ConfigToUse; - bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, MAG_DATA_REGISTER, 6, buf); - if (!ack) { + uint8_t sig = 0; + bool ack = i2cRead(MAG_I2C_INSTANCE, MAG_ADDRESS, 0x0A, 1, &sig); + + if (!ack || sig != 'H') return false; - } - // During calibration, magGain is 1.0, so the read returns normal non-calibrated values. - // After calibration is done, magGain is set to calculated gain values. - magData[X] = (int16_t)(buf[0] << 8 | buf[1]) * magGain[X]; - magData[Z] = (int16_t)(buf[2] << 8 | buf[3]) * magGain[Z]; - magData[Y] = (int16_t)(buf[4] << 8 | buf[5]) * magGain[Y]; + + mag->init = hmc5883lInit; + mag->read = hmc5883lRead; return true; } diff --git a/src/main/drivers/pwm_esc_detect.c b/src/main/drivers/pwm_esc_detect.c new file mode 100644 index 0000000000..012f912688 --- /dev/null +++ b/src/main/drivers/pwm_esc_detect.c @@ -0,0 +1,55 @@ +/* + * 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/build_config.h" + +#include "system.h" +#include "io.h" +#include "pwm_esc_detect.h" +#include "timer.h" + +#ifdef BRUSHED_ESC_AUTODETECT +uint8_t hardwareMotorType = MOTOR_UNKNOWN; + +void detectBrushedESC(void) +{ + int i = 0; + while (!(timerHardware[i].usageFlags & TIM_USE_MOTOR) && (i < USABLE_TIMER_CHANNEL_COUNT)) { + i++; + } + + IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag); + IOInit(MotorDetectPin, OWNER_SYSTEM, 0); + IOConfigGPIO(MotorDetectPin, IOCFG_IPU); + + delayMicroseconds(10); // allow configuration to settle + + // Check presence of brushed ESC's + if (IORead(MotorDetectPin)) { + hardwareMotorType = MOTOR_BRUSHLESS; + } else { + hardwareMotorType = MOTOR_BRUSHED; + } +} +#endif diff --git a/src/main/drivers/pwm_esc_detect.h b/src/main/drivers/pwm_esc_detect.h new file mode 100644 index 0000000000..b61dc0459a --- /dev/null +++ b/src/main/drivers/pwm_esc_detect.h @@ -0,0 +1,29 @@ +/* + * 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 + +#ifdef BRUSHED_ESC_AUTODETECT +typedef enum { + MOTOR_UNKNOWN = 0, + MOTOR_BRUSHED, + MOTOR_BRUSHLESS +} HardwareMotorTypes_e; + +extern uint8_t hardwareMotorType; + +void detectBrushedESC(void); +#endif diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 90ad21c900..ed58b25291 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -24,7 +24,6 @@ #include "io.h" #include "timer.h" #include "pwm_output.h" -#include "system.h" #define MULTISHOT_5US_PW (MULTISHOT_TIMER_MHZ * 5) #define MULTISHOT_20US_MULT (MULTISHOT_TIMER_MHZ * 20 / 1000.0f) @@ -281,28 +280,3 @@ void servoInit(const servoConfig_t *servoConfig) } #endif - -#ifdef BRUSHED_ESC_AUTODETECT -uint8_t hardwareMotorType = MOTOR_UNKNOWN; - -void detectBrushedESC(void) -{ - int i = 0; - while (!(timerHardware[i].usageFlags & TIM_USE_MOTOR) && (i < USABLE_TIMER_CHANNEL_COUNT)) { - i++; - } - - IO_t MotorDetectPin = IOGetByTag(timerHardware[i].tag); - IOInit(MotorDetectPin, OWNER_SYSTEM, 0); - IOConfigGPIO(MotorDetectPin, IOCFG_IPU); - - delayMicroseconds(10); // allow configuration to settle - - // Check presence of brushed ESC's - if (IORead(MotorDetectPin)) { - hardwareMotorType = MOTOR_BRUSHLESS; - } else { - hardwareMotorType = MOTOR_BRUSHED; - } -} -#endif diff --git a/src/main/drivers/pwm_output.h b/src/main/drivers/pwm_output.h index 8c6488298e..9d94a1d074 100644 --- a/src/main/drivers/pwm_output.h +++ b/src/main/drivers/pwm_output.h @@ -114,15 +114,3 @@ pwmOutputPort_t *pwmGetMotors(void); bool pwmIsSynced(void); void pwmDisableMotors(void); void pwmEnableMotors(void); - -#ifdef BRUSHED_ESC_AUTODETECT -typedef enum { - MOTOR_UNKNOWN = 0, - MOTOR_BRUSHED, - MOTOR_BRUSHLESS -} HardwareMotorTypes_e; - -extern uint8_t hardwareMotorType; - -void detectBrushedESC(void); -#endif diff --git a/src/main/drivers/pwm_rx.c b/src/main/drivers/pwm_rx.c index ed52ecaec6..a745fd0733 100644 --- a/src/main/drivers/pwm_rx.c +++ b/src/main/drivers/pwm_rx.c @@ -122,11 +122,6 @@ void resetPPMDataReceivedState(void) #define MIN_CHANNELS_BEFORE_PPM_FRAME_CONSIDERED_VALID 4 -void pwmRxSetInputFilteringMode(inputFilteringMode_e initialInputFilteringMode) -{ - inputFilteringMode = initialInputFilteringMode; -} - #ifdef DEBUG_PPM_ISR typedef enum { SOURCE_OVERFLOW = 0, @@ -366,6 +361,8 @@ void pwmICConfig(TIM_TypeDef *tim, uint8_t channel, uint16_t polarity) void pwmRxInit(const pwmConfig_t *pwmConfig) { + inputFilteringMode = pwmConfig->inputFilteringMode; + for (int channel = 0; channel < PWM_INPUT_PORT_COUNT; channel++) { pwmInputPort_t *port = &pwmInputPorts[channel]; diff --git a/src/main/drivers/pwm_rx.h b/src/main/drivers/pwm_rx.h index bcb0b60ec1..c16306a81e 100644 --- a/src/main/drivers/pwm_rx.h +++ b/src/main/drivers/pwm_rx.h @@ -33,6 +33,7 @@ typedef struct ppmConfig_s { typedef struct pwmConfig_s { ioTag_t ioTags[PWM_INPUT_PORT_COUNT]; + inputFilteringMode_e inputFilteringMode; } pwmConfig_t; void ppmRxInit(const ppmConfig_t *ppmConfig, uint8_t pwmProtocol); @@ -44,6 +45,4 @@ uint16_t ppmRead(uint8_t channel); bool isPPMDataBeingReceived(void); void resetPPMDataReceivedState(void); -void pwmRxSetInputFilteringMode(inputFilteringMode_e initialInputFilteringMode); - bool isPWMDataBeingReceived(void); diff --git a/src/main/drivers/sensor.h b/src/main/drivers/sensor.h index 480aca7dc2..b9763695c3 100644 --- a/src/main/drivers/sensor.h +++ b/src/main/drivers/sensor.h @@ -29,12 +29,14 @@ typedef enum { CW270_DEG_FLIP = 8 } sensor_align_e; -struct accDev_s; -typedef void (*sensorInitFuncPtr)(void); // sensor init prototype +typedef bool (*sensorInitFuncPtr)(void); // sensor init prototype typedef bool (*sensorReadFuncPtr)(int16_t *data); // sensor read and align prototype -typedef void (*sensorAccInitFuncPtr)(struct accDev_s *acc); // sensor init prototype +typedef bool (*sensorInterruptFuncPtr)(void); +struct accDev_s; +typedef void (*sensorAccInitFuncPtr)(struct accDev_s *acc); +typedef bool (*sensorAccReadFuncPtr)(struct accDev_s *acc); struct gyroDev_s; typedef void (*sensorGyroInitFuncPtr)(struct gyroDev_s *gyro); typedef bool (*sensorGyroReadFuncPtr)(struct gyroDev_s *gyro); +typedef bool (*sensorGyroReadDataFuncPtr)(struct gyroDev_s *gyro, int16_t *data); typedef bool (*sensorGyroInterruptStatusFuncPtr)(struct gyroDev_s *gyro); -typedef bool (*sensorInterruptFuncPtr)(void); diff --git a/src/main/drivers/serial_escserial.c b/src/main/drivers/serial_escserial.c index 351b2c98cc..76309c3bce 100644 --- a/src/main/drivers/serial_escserial.c +++ b/src/main/drivers/serial_escserial.c @@ -27,14 +27,6 @@ typedef enum { BAUDRATE_CASTLE = 18880 } escBaudRate_e; -typedef enum { - PROTOCOL_SIMONK = 0, - PROTOCOL_BLHELI = 1, - PROTOCOL_KISS = 2, - PROTOCOL_KISSALL = 3, - PROTOCOL_CASTLE = 4 -} escProtocol_e; - #if defined(USE_ESCSERIAL) #include "build/build_config.h" diff --git a/src/main/drivers/serial_escserial.h b/src/main/drivers/serial_escserial.h index 113ce1c2a1..41bbf07556 100644 --- a/src/main/drivers/serial_escserial.h +++ b/src/main/drivers/serial_escserial.h @@ -24,6 +24,15 @@ typedef enum { ESCSERIAL2 } escSerialPortIndex_e; +typedef enum { + PROTOCOL_SIMONK = 0, + PROTOCOL_BLHELI = 1, + PROTOCOL_KISS = 2, + PROTOCOL_KISSALL = 3, + PROTOCOL_CASTLE = 4, + PROTOCOL_COUNT +} escProtocol_e; + serialPort_t *openEscSerial(escSerialPortIndex_e portIndex, serialReceiveCallbackPtr callback, uint16_t output, uint32_t baud, portOptions_t options, uint8_t mode); // serialPort API diff --git a/src/main/drivers/timer_def.h b/src/main/drivers/timer_def.h index d32716b1a2..385955946a 100644 --- a/src/main/drivers/timer_def.h +++ b/src/main/drivers/timer_def.h @@ -82,6 +82,7 @@ #define DEF_TIM_DMA__TIM1_COM DMA1_CH4 #define DEF_TIM_DMA__TIM1_UP DMA1_CH5 #define DEF_TIM_DMA__TIM1_CH3 DMA1_CH6 +#define DEF_TIM_DMA__TIM1_CH3N DMA1_CH6 #define DEF_TIM_DMA__TIM2_CH3 DMA1_CH1 #define DEF_TIM_DMA__TIM2_UP DMA1_CH2 @@ -126,6 +127,7 @@ #endif #define DEF_TIM_DMA__TIM8_CH3 DMA2_CH1 +#define DEF_TIM_DMA__TIM8_CH3N DMA2_CH1 #define DEF_TIM_DMA__TIM8_UP DMA2_CH1 #define DEF_TIM_DMA__TIM8_CH4 DMA2_CH2 #define DEF_TIM_DMA__TIM8_TRIG DMA2_CH2 @@ -297,9 +299,8 @@ #define DEF_TIM_DMA_STR_0__TIM3_CH4 DMA1_ST2 #define DEF_TIM_DMA_STR_0__TIM4_CH1 DMA1_ST0 -#define DEF_TIM_DMA_STR_0__TIM4_CH2 DMA1_ST4 +#define DEF_TIM_DMA_STR_0__TIM4_CH2 DMA1_ST3 #define DEF_TIM_DMA_STR_0__TIM4_CH3 DMA1_ST7 -#define DEF_TIM_DMA_STR_0__TIM4_CH4 DMA1_ST3 #define DEF_TIM_DMA_STR_0__TIM5_CH1 DMA1_ST2 #define DEF_TIM_DMA_STR_0__TIM5_CH2 DMA1_ST4 @@ -321,6 +322,8 @@ #define DEF_TIM_DMA_STR_1__TIM8_CH3N DMA2_ST4 #define DEF_TIM_DMA_STR_0__TIM8_CH4 DMA2_ST7 +#define DEF_TIM_DMA_STR_0__TIM4_CH4 DMA_NONE + #define DEF_TIM_DMA_STR_0__TIM9_CH1 DMA_NONE #define DEF_TIM_DMA_STR_0__TIM9_CH2 DMA_NONE @@ -367,7 +370,6 @@ #define DEF_TIM_DMA_CHN_0__TIM4_CH1 DMA_Channel_2 #define DEF_TIM_DMA_CHN_0__TIM4_CH2 DMA_Channel_2 #define DEF_TIM_DMA_CHN_0__TIM4_CH3 DMA_Channel_2 -#define DEF_TIM_DMA_CHN_0__TIM4_CH4 DMA_Channel_2 #define DEF_TIM_DMA_CHN_0__TIM5_CH1 DMA_Channel_6 #define DEF_TIM_DMA_CHN_0__TIM5_CH2 DMA_Channel_6 @@ -389,6 +391,8 @@ #define DEF_TIM_DMA_CHN_1__TIM8_CH3N DMA_Channel_7 #define DEF_TIM_DMA_CHN_0__TIM8_CH4 DMA_Channel_7 +#define DEF_TIM_DMA_CHN_0__TIM4_CH4 0 + #define DEF_TIM_DMA_CHN_0__TIM9_CH1 0 #define DEF_TIM_DMA_CHN_0__TIM9_CH2 0 @@ -420,6 +424,290 @@ #define DMA2_ST6_STREAM DMA2_Stream6 #define DMA2_ST7_STREAM DMA2_Stream7 +#elif defined(STM32F7) +#define DEF_TIM(tim, chan, pin, flags, out, dmaopt) {\ + tim,\ + IO_TAG(pin),\ + EXPAND(DEF_CHAN_ ## chan),\ + flags,\ + (DEF_CHAN_ ## chan ## _OUTPUT | out),\ + EXPAND(GPIO_AF__ ## pin ## _ ## tim ## _ ## chan),\ + CONCAT(EXPAND(DEF_TIM_DMA_STR_ ## dmaopt ## __ ## tim ## _ ## chan), _STREAM),\ + EXPAND(DEF_TIM_DMA_CHN_ ## dmaopt ## __ ## tim ## _ ## chan),\ + CONCAT(EXPAND(DEF_TIM_DMA_STR_ ## dmaopt ## __ ## tim ## _ ## chan), _HANDLER)\ + } + +#define DEF_DMA_CHANNEL(tim, chan, dmaopt) EXPAND(DEF_TIM_DMA_CHN_ ## dmaopt ## __ ## tim ## _ ## chan) +#define DEF_DMA_STREAM(tim, chan, dmaopt) CONCAT(EXPAND(DEF_TIM_DMA_STR_ ## dmaopt ## __ ## tim ## _ ## chan), _STREAM) +#define DEF_DMA_HANDLER(tim, chan, dmaopt) CONCAT(EXPAND(DEF_TIM_DMA_STR_ ## dmaopt ## __ ## tim ## _ ## chan), _HANDLER) + +/* F7 Stream Mappings */ + +#define DEF_TIM_DMA_STR_0__TIM1_CH1 DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH1 DMA2_ST1 +#define DEF_TIM_DMA_STR_2__TIM1_CH1 DMA2_ST3 +#define DEF_TIM_DMA_STR_0__TIM1_CH1N DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH1N DMA2_ST1 +#define DEF_TIM_DMA_STR_2__TIM1_CH1N DMA2_ST3 +#define DEF_TIM_DMA_STR_0__TIM1_CH2 DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH2 DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM1_CH2N DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH2N DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM1_CH3 DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH3 DMA2_ST6 +#define DEF_TIM_DMA_STR_0__TIM1_CH3N DMA2_ST6 +#define DEF_TIM_DMA_STR_1__TIM1_CH3N DMA2_ST6 +#define DEF_TIM_DMA_STR_0__TIM1_CH4 DMA2_ST4 + +#define DEF_TIM_DMA_STR_0__TIM2_CH1 DMA1_ST5 +#define DEF_TIM_DMA_STR_0__TIM2_CH2 DMA1_ST6 +#define DEF_TIM_DMA_STR_0__TIM2_CH3 DMA1_ST1 +#define DEF_TIM_DMA_STR_0__TIM2_CH4 DMA1_ST7 +#define DEF_TIM_DMA_STR_1__TIM2_CH4 DMA1_ST6 + +#define DEF_TIM_DMA_STR_0__TIM3_CH1 DMA1_ST4 +#define DEF_TIM_DMA_STR_0__TIM3_CH2 DMA1_ST5 +#define DEF_TIM_DMA_STR_0__TIM3_CH3 DMA1_ST7 +#define DEF_TIM_DMA_STR_0__TIM3_CH4 DMA1_ST2 + +#define DEF_TIM_DMA_STR_0__TIM4_CH1 DMA1_ST0 +#define DEF_TIM_DMA_STR_0__TIM4_CH2 DMA1_ST3 +#define DEF_TIM_DMA_STR_0__TIM4_CH3 DMA1_ST7 + +#define DEF_TIM_DMA_STR_0__TIM5_CH1 DMA1_ST2 +#define DEF_TIM_DMA_STR_0__TIM5_CH2 DMA1_ST4 +#define DEF_TIM_DMA_STR_0__TIM5_CH3 DMA1_ST0 +#define DEF_TIM_DMA_STR_0__TIM5_CH4 DMA1_ST1 +#define DEF_TIM_DMA_STR_1__TIM5_CH4 DMA1_ST3 + +#define DEF_TIM_DMA_STR_0__TIM8_CH1 DMA2_ST2 +#define DEF_TIM_DMA_STR_1__TIM8_CH1 DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH1N DMA2_ST2 +#define DEF_TIM_DMA_STR_1__TIM8_CH1N DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH2 DMA2_ST3 +#define DEF_TIM_DMA_STR_1__TIM8_CH2 DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH2N DMA2_ST3 +#define DEF_TIM_DMA_STR_1__TIM8_CH2N DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH3 DMA2_ST4 +#define DEF_TIM_DMA_STR_1__TIM8_CH3 DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH3N DMA2_ST4 +#define DEF_TIM_DMA_STR_1__TIM8_CH3N DMA2_ST2 +#define DEF_TIM_DMA_STR_0__TIM8_CH4 DMA2_ST7 + +#define DEF_TIM_DMA_STR_0__TIM4_CH4 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM9_CH1 DMA_NONE +#define DEF_TIM_DMA_STR_0__TIM9_CH2 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM10_CH1 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM11_CH1 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM12_CH1 DMA_NONE +#define DEF_TIM_DMA_STR_0__TIM12_CH2 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM13_CH1 DMA_NONE + +#define DEF_TIM_DMA_STR_0__TIM14_CH1 DMA_NONE + +/* F7 Channel Mappings */ + +#define DEF_TIM_DMA_CHN_0__TIM1_CH1 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH1 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_2__TIM1_CH1 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH1N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH1N DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_2__TIM1_CH1N DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH2 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH2 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH2N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH2N DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH3 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH3 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH3N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_1__TIM1_CH3N DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM1_CH4 DMA_CHANNEL_6 + +#define DEF_TIM_DMA_CHN_0__TIM2_CH1 DMA_CHANNEL_3 +#define DEF_TIM_DMA_CHN_0__TIM2_CH2 DMA_CHANNEL_3 +#define DEF_TIM_DMA_CHN_0__TIM2_CH3 DMA_CHANNEL_3 +#define DEF_TIM_DMA_CHN_0__TIM2_CH4 DMA_CHANNEL_3 +#define DEF_TIM_DMA_CHN_1__TIM2_CH4 DMA_CHANNEL_3 + +#define DEF_TIM_DMA_CHN_0__TIM3_CH1 DMA_CHANNEL_5 +#define DEF_TIM_DMA_CHN_0__TIM3_CH2 DMA_CHANNEL_5 +#define DEF_TIM_DMA_CHN_0__TIM3_CH3 DMA_CHANNEL_5 +#define DEF_TIM_DMA_CHN_0__TIM3_CH4 DMA_CHANNEL_5 + +#define DEF_TIM_DMA_CHN_0__TIM4_CH1 DMA_CHANNEL_2 +#define DEF_TIM_DMA_CHN_0__TIM4_CH2 DMA_CHANNEL_2 +#define DEF_TIM_DMA_CHN_0__TIM4_CH3 DMA_CHANNEL_2 + +#define DEF_TIM_DMA_CHN_0__TIM5_CH1 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM5_CH2 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM5_CH3 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_0__TIM5_CH4 DMA_CHANNEL_6 +#define DEF_TIM_DMA_CHN_1__TIM5_CH4 DMA_CHANNEL_6 + +#define DEF_TIM_DMA_CHN_0__TIM8_CH1 DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH1 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH1N DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH1N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH2 DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH2 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH2N DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH2N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH3 DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH3 DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH3N DMA_CHANNEL_7 +#define DEF_TIM_DMA_CHN_1__TIM8_CH3N DMA_CHANNEL_0 +#define DEF_TIM_DMA_CHN_0__TIM8_CH4 DMA_CHANNEL_7 + +#define DEF_TIM_DMA_CHN_0__TIM4_CH4 0 + +#define DEF_TIM_DMA_CHN_0__TIM9_CH1 0 +#define DEF_TIM_DMA_CHN_0__TIM9_CH2 0 + +#define DEF_TIM_DMA_CHN_0__TIM10_CH1 0 + +#define DEF_TIM_DMA_CHN_0__TIM11_CH1 0 + +#define DEF_TIM_DMA_CHN_0__TIM12_CH1 0 +#define DEF_TIM_DMA_CHN_0__TIM12_CH2 0 + +#define DEF_TIM_DMA_CHN_0__TIM13_CH1 0 + +#define DEF_TIM_DMA_CHN_0__TIM14_CH1 0 + +#define DMA1_ST0_STREAM DMA1_Stream0 +#define DMA1_ST1_STREAM DMA1_Stream1 +#define DMA1_ST2_STREAM DMA1_Stream2 +#define DMA1_ST3_STREAM DMA1_Stream3 +#define DMA1_ST4_STREAM DMA1_Stream4 +#define DMA1_ST5_STREAM DMA1_Stream5 +#define DMA1_ST6_STREAM DMA1_Stream6 +#define DMA1_ST7_STREAM DMA1_Stream7 +#define DMA2_ST0_STREAM DMA2_Stream0 +#define DMA2_ST1_STREAM DMA2_Stream1 +#define DMA2_ST2_STREAM DMA2_Stream2 +#define DMA2_ST3_STREAM DMA2_Stream3 +#define DMA2_ST4_STREAM DMA2_Stream4 +#define DMA2_ST5_STREAM DMA2_Stream5 +#define DMA2_ST6_STREAM DMA2_Stream6 +#define DMA2_ST7_STREAM DMA2_Stream7 + +#define GPIO_AF(p, t) CONCAT(GPIO_AF__, p, _, t) + +//PORTA +#define GPIO_AF__PA0_TIM2_CH1 GPIO_AF1_TIM2 +#define GPIO_AF__PA1_TIM2_CH2 GPIO_AF1_TIM2 +#define GPIO_AF__PA2_TIM2_CH3 GPIO_AF1_TIM2 +#define GPIO_AF__PA3_TIM2_CH4 GPIO_AF1_TIM2 +#define GPIO_AF__PA5_TIM2_CH1 GPIO_AF1_TIM2 +#define GPIO_AF__PA7_TIM1_CH1N GPIO_AF1_TIM1 +#define GPIO_AF__PA8_TIM1_CH1 GPIO_AF1_TIM1 +#define GPIO_AF__PA9_TIM1_CH2 GPIO_AF1_TIM1 +#define GPIO_AF__PA10_TIM1_CH3 GPIO_AF1_TIM1 +#define GPIO_AF__PA11_TIM1_CH1N GPIO_AF1_TIM1 +#define GPIO_AF__PA15_TIM2_CH1 GPIO_AF1_TIM2 + +#define GPIO_AF__PA0_TIM5_CH1 GPIO_AF2_TIM5 +#define GPIO_AF__PA1_TIM5_CH2 GPIO_AF2_TIM5 +#define GPIO_AF__PA3_TIM5_CH3 GPIO_AF2_TIM5 +#define GPIO_AF__PA4_TIM5_CH4 GPIO_AF2_TIM5 +#define GPIO_AF__PA6_TIM3_CH1 GPIO_AF2_TIM3 +#define GPIO_AF__PA7_TIM3_CH2 GPIO_AF2_TIM3 + +#define GPIO_AF__PA2_TIM9_CH1 GPIO_AF3_TIM9 +#define GPIO_AF__PA3_TIM9_CH2 GPIO_AF3_TIM9 +#define GPIO_AF__PA5_TIM8_CH1N GPIO_AF3_TIM8 +#define GPIO_AF__PA7_TIM8_CH1N GPIO_AF3_TIM8 + +#define GPIO_AF__PA6_TIM13_CH1 GPIO_AF9_TIM13 +#define GPIO_AF__PA7_TIM14_CH1 GPIO_AF9_TIM14 + +//PORTB +#define GPIO_AF__PB0_TIM1_CH2N GPIO_AF1_TIM1 +#define GPIO_AF__PB1_TIM1_CH2N GPIO_AF1_TIM1 +#define GPIO_AF__PB3_TIM2_CH2 GPIO_AF1_TIM2 +#define GPIO_AF__PB10_TIM2_CH3 GPIO_AF1_TIM2 +#define GPIO_AF__PB11_TIM2_CH4 GPIO_AF1_TIM2 +#define GPIO_AF__PB13_TIM1_CH1N GPIO_AF1_TIM1 +#define GPIO_AF__PB14_TIM1_CH2N GPIO_AF1_TIM1 +#define GPIO_AF__PB15_TIM1_CH3N GPIO_AF1_TIM1 + +#define GPIO_AF__PB0_TIM3_CH3 GPIO_AF2_TIM3 +#define GPIO_AF__PB1_TIM3_CH4 GPIO_AF2_TIM3 +#define GPIO_AF__PB4_TIM3_CH1 GPIO_AF2_TIM3 +#define GPIO_AF__PB5_TIM3_CH2 GPIO_AF2_TIM3 +#define GPIO_AF__PB6_TIM4_CH1 GPIO_AF2_TIM4 +#define GPIO_AF__PB7_TIM4_CH2 GPIO_AF2_TIM4 +#define GPIO_AF__PB8_TIM4_CH3 GPIO_AF2_TIM4 +#define GPIO_AF__PB9_TIM4_CH4 GPIO_AF2_TIM4 + +#define GPIO_AF__PB0_TIM8_CH2N GPIO_AF3_TIM8 +#define GPIO_AF__PB1_TIM8_CH3N GPIO_AF3_TIM8 +#define GPIO_AF__PB8_TIM10_CH1 GPIO_AF3_TIM10 +#define GPIO_AF__PB9_TIM11_CH1 GPIO_AF3_TIM11 +#define GPIO_AF__PB14_TIM8_CH2N GPIO_AF3_TIM8 +#define GPIO_AF__PB15_TIM8_CH3N GPIO_AF3_TIM8 + +#define GPIO_AF__PB14_TIM12_CH1 GPIO_AF9_TIM12 +#define GPIO_AF__PB15_TIM12_CH2 GPIO_AF9_TIM12 + +//PORTC +#define GPIO_AF__PC6_TIM3_CH1 GPIO_AF2_TIM3 +#define GPIO_AF__PC7_TIM3_CH2 GPIO_AF2_TIM3 +#define GPIO_AF__PC8_TIM3_CH3 GPIO_AF2_TIM3 +#define GPIO_AF__PC9_TIM3_CH4 GPIO_AF2_TIM3 + +#define GPIO_AF__PC6_TIM8_CH1 GPIO_AF3_TIM8 +#define GPIO_AF__PC7_TIM8_CH2 GPIO_AF3_TIM8 +#define GPIO_AF__PC8_TIM8_CH3 GPIO_AF3_TIM8 +#define GPIO_AF__PC9_TIM8_CH4 GPIO_AF3_TIM8 + +//PORTD +#define GPIO_AF__PD12_TIM4_CH1 GPIO_AF2_TIM4 +#define GPIO_AF__PD13_TIM4_CH2 GPIO_AF2_TIM4 +#define GPIO_AF__PD14_TIM4_CH3 GPIO_AF2_TIM4 +#define GPIO_AF__PD15_TIM4_CH4 GPIO_AF2_TIM4 + +//PORTE +#define GPIO_AF__PE8_TIM1_CH1N GPIO_AF1_TIM1 +#define GPIO_AF__PE9_TIM1_CH1 GPIO_AF1_TIM1 +#define GPIO_AF__PE10_TIM1_CH2N GPIO_AF1_TIM1 +#define GPIO_AF__PE11_TIM1_CH2 GPIO_AF1_TIM1 +#define GPIO_AF__PE12_TIM1_CH3N GPIO_AF1_TIM1 +#define GPIO_AF__PE13_TIM1_CH3 GPIO_AF1_TIM1 +#define GPIO_AF__PE14_TIM1_CH4 GPIO_AF1_TIM1 + +#define GPIO_AF__PE5_TIM9_CH1 GPIO_AF3_TIM9 +#define GPIO_AF__PE6_TIM9_CH2 GPIO_AF3_TIM9 + +//PORTF +#define GPIO_AF__PF6_TIM10_CH1 GPIO_AF3_TIM10 +#define GPIO_AF__PF7_TIM11_CH1 GPIO_AF3_TIM11 + +//PORTH +#define GPIO_AF__PH10_TIM5_CH1 GPIO_AF2_TIM5 +#define GPIO_AF__PH11_TIM5_CH2 GPIO_AF2_TIM5 +#define GPIO_AF__PH12_TIM5_CH3 GPIO_AF2_TIM5 + +#define GPIO_AF__PH13_TIM8_CH1N GPIO_AF3_TIM8 +#define GPIO_AF__PH14_TIM8_CH2N GPIO_AF3_TIM8 +#define GPIO_AF__PH15_TIM8_CH3N GPIO_AF3_TIM8 + +#define GPIO_AF__PH6_TIM12_CH1 GPIO_AF9_TIM12 +#define GPIO_AF__PH9_TIM12_CH2 GPIO_AF9_TIM12 + +//PORTI +#define GPIO_AF__PI0_TIM5_CH4 GPIO_AF2_TIM5 + +#define GPIO_AF__PI2_TIM8_CH4 GPIO_AF3_TIM8 +#define GPIO_AF__PI5_TIM8_CH1 GPIO_AF3_TIM8 +#define GPIO_AF__PI6_TIM8_CH2 GPIO_AF3_TIM8 +#define GPIO_AF__PI7_TIM8_CH3 GPIO_AF3_TIM8 + #endif /**** Common Defines across all targets ****/ @@ -432,6 +720,16 @@ #define DMA_NONE_HANDLER 0 +#if defined(STM32F7) +#define DEF_CHAN_CH1 TIM_CHANNEL_1 +#define DEF_CHAN_CH2 TIM_CHANNEL_2 +#define DEF_CHAN_CH3 TIM_CHANNEL_3 +#define DEF_CHAN_CH4 TIM_CHANNEL_4 +#define DEF_CHAN_CH1N TIM_CHANNEL_1 +#define DEF_CHAN_CH2N TIM_CHANNEL_2 +#define DEF_CHAN_CH3N TIM_CHANNEL_3 +#define DEF_CHAN_CH4N TIM_CHANNEL_4 +#else #define DEF_CHAN_CH1 TIM_Channel_1 #define DEF_CHAN_CH2 TIM_Channel_2 #define DEF_CHAN_CH3 TIM_Channel_3 @@ -440,6 +738,7 @@ #define DEF_CHAN_CH2N TIM_Channel_2 #define DEF_CHAN_CH3N TIM_Channel_3 #define DEF_CHAN_CH4N TIM_Channel_4 +#endif #define DEF_CHAN_CH1_OUTPUT TIMER_OUTPUT_NONE #define DEF_CHAN_CH2_OUTPUT TIMER_OUTPUT_NONE @@ -463,4 +762,4 @@ #define DMA2_CH4_CHANNEL DMA2_Channel4 #define DMA2_CH5_CHANNEL DMA2_Channel5 #define DMA2_CH6_CHANNEL DMA2_Channel6 -#define DMA2_CH7_CHANNEL DMA2_Channel7 \ No newline at end of file +#define DMA2_CH7_CHANNEL DMA2_Channel7 diff --git a/src/main/fc/config.c b/src/main/fc/config.c index 4359fcd2b4..eaa40a7ed6 100755 --- a/src/main/fc/config.c +++ b/src/main/fc/config.c @@ -41,6 +41,7 @@ #include "drivers/pwm_rx.h" #include "drivers/rx_spi.h" #include "drivers/serial.h" +#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" #include "drivers/vcd.h" #include "drivers/max7456.h" @@ -613,14 +614,15 @@ void createDefaultConfig(master_t *config) config->gyroConfig.gyro_lpf = GYRO_LPF_256HZ; // 256HZ default #ifdef STM32F10X config->gyroConfig.gyro_sync_denom = 8; - config->pid_process_denom = 1; + config->pidConfig.pid_process_denom = 1; #elif defined(USE_GYRO_SPI_MPU6000) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_ICM20689) config->gyroConfig.gyro_sync_denom = 1; - config->pid_process_denom = 4; + config->pidConfig.pid_process_denom = 4; #else config->gyroConfig.gyro_sync_denom = 4; - config->pid_process_denom = 2; + config->pidConfig.pid_process_denom = 2; #endif + config->pidConfig.max_angle_inclination = 700; // 70 degrees config->gyroConfig.gyro_soft_lpf_type = FILTER_PT1; config->gyroConfig.gyro_soft_lpf_hz = 90; config->gyroConfig.gyro_soft_notch_hz_1 = 400; @@ -640,7 +642,6 @@ void createDefaultConfig(master_t *config) config->boardAlignment.pitchDegrees = 0; config->boardAlignment.yawDegrees = 0; config->accelerometerConfig.acc_hardware = ACC_DEFAULT; // default/autodetect - config->max_angle_inclination = 700; // 70 degrees config->rcControlsConfig.yaw_control_direction = 1; config->gyroConfig.gyroMovementCalibrationThreshold = 32; @@ -709,7 +710,9 @@ void createDefaultConfig(master_t *config) resetAllRxChannelRangeConfigurations(config->rxConfig.channelRanges); - config->inputFilteringMode = INPUT_FILTERING_DISABLED; +#ifdef USE_PWM + config->pwmConfig.inputFilteringMode = INPUT_FILTERING_DISABLED; +#endif config->armingConfig.gyro_cal_on_first_arm = 0; // TODO - Cleanup retarded arm support config->armingConfig.disarm_kill_switch = 1; @@ -1050,7 +1053,7 @@ void validateAndFixGyroConfig(void) } if (gyroConfig()->gyro_lpf != GYRO_LPF_256HZ && gyroConfig()->gyro_lpf != GYRO_LPF_NONE) { - masterConfig.pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed + pidConfig()->pid_process_denom = 1; // When gyro set to 1khz always set pid speed 1:1 to sampling speed gyroConfig()->gyro_sync_denom = 1; } } diff --git a/src/main/fc/fc_msp.c b/src/main/fc/fc_msp.c index bbc0651459..79c01a0476 100755 --- a/src/main/fc/fc_msp.c +++ b/src/main/fc/fc_msp.c @@ -46,6 +46,7 @@ #include "drivers/max7456.h" #include "drivers/vtx_soft_spi_rtc6705.h" #include "drivers/pwm_output.h" +#include "drivers/serial_escserial.h" #include "fc/config.h" #include "fc/mw.h" @@ -182,14 +183,61 @@ typedef enum { #define RATEPROFILE_MASK (1 << 7) #ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE -static void msp4WayIfFn(serialPort_t *serialPort) +#define ESC_4WAY 0xff + +uint8_t escMode; +uint8_t escPortIndex = 0; + +#ifdef USE_ESCSERIAL +static void mspEscPassthroughFn(serialPort_t *serialPort) { - // rem: App: Wait at least appx. 500 ms for BLHeli to jump into - // bootloader mode before try to connect any ESC - // Start to activate here - esc4wayProcess(serialPort); - // former used MSP uart is still active - // proceed as usual with MSP commands + escEnablePassthrough(serialPort, escPortIndex, escMode); +} +#endif + +static void mspFc4waySerialCommand(sbuf_t *dst, sbuf_t *src, mspPostProcessFnPtr *mspPostProcessFn) +{ + const unsigned int dataSize = sbufBytesRemaining(src); + if (dataSize == 0) { + // Legacy format + + escMode = ESC_4WAY; + } else { + escMode = sbufReadU8(src); + escPortIndex = sbufReadU8(src); + } + + switch(escMode) { + case ESC_4WAY: + // get channel number + // switch all motor lines HI + // reply with the count of ESC found + sbufWriteU8(dst, esc4wayInit()); + + if (mspPostProcessFn) { + *mspPostProcessFn = esc4wayProcess; + } + + break; +#ifdef USE_ESCSERIAL + case PROTOCOL_SIMONK: + case PROTOCOL_BLHELI: + case PROTOCOL_KISS: + case PROTOCOL_KISSALL: + case PROTOCOL_CASTLE: + if (escPortIndex < USABLE_TIMER_CHANNEL_COUNT || (escMode == PROTOCOL_KISS && escPortIndex == 255)) { + sbufWriteU8(dst, 1); + + if (mspPostProcessFn) { + *mspPostProcessFn = mspEscPassthroughFn; + } + + break; + } +#endif + default: + sbufWriteU8(dst, 0); + } } #endif @@ -431,21 +479,24 @@ static void serializeSDCardSummaryReply(sbuf_t *dst) state = MSP_SDCARD_STATE_FATAL; } else { switch (afatfs_getFilesystemState()) { - case AFATFS_FILESYSTEM_STATE_READY: - state = MSP_SDCARD_STATE_READY; - break; - case AFATFS_FILESYSTEM_STATE_INITIALIZATION: - if (sdcard_isInitialized()) { - state = MSP_SDCARD_STATE_FS_INIT; - } else { - state = MSP_SDCARD_STATE_CARD_INIT; - } - break; - case AFATFS_FILESYSTEM_STATE_FATAL: - case AFATFS_FILESYSTEM_STATE_UNKNOWN: - default: - state = MSP_SDCARD_STATE_FATAL; - break; + case AFATFS_FILESYSTEM_STATE_READY: + state = MSP_SDCARD_STATE_READY; + + break; + case AFATFS_FILESYSTEM_STATE_INITIALIZATION: + if (sdcard_isInitialized()) { + state = MSP_SDCARD_STATE_FS_INIT; + } else { + state = MSP_SDCARD_STATE_CARD_INIT; + } + + break; + case AFATFS_FILESYSTEM_STATE_FATAL: + case AFATFS_FILESYSTEM_STATE_UNKNOWN: + default: + state = MSP_SDCARD_STATE_FATAL; + + break; } } @@ -1093,7 +1144,7 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn sbufWriteU8(dst, 1); } else { sbufWriteU8(dst, gyroConfig()->gyro_sync_denom); - sbufWriteU8(dst, masterConfig.pid_process_denom); + sbufWriteU8(dst, pidConfig()->pid_process_denom); } sbufWriteU8(dst, motorConfig()->useUnsyncedPwm); sbufWriteU8(dst, motorConfig()->motorPwmProtocol); @@ -1139,18 +1190,6 @@ static bool mspFcProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst, mspPostProcessFn } break; -#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE - case MSP_SET_4WAY_IF: - // get channel number - // switch all motor lines HI - // reply with the count of ESC found - sbufWriteU8(dst, esc4wayInit()); - if (mspPostProcessFn) { - *mspPostProcessFn = msp4WayIfFn; - } - break; -#endif - default: return false; } @@ -1442,7 +1481,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src) case MSP_SET_ADVANCED_CONFIG: gyroConfig()->gyro_sync_denom = sbufReadU8(src); - masterConfig.pid_process_denom = sbufReadU8(src); + pidConfig()->pid_process_denom = sbufReadU8(src); motorConfig()->useUnsyncedPwm = sbufReadU8(src); #ifdef USE_DSHOT motorConfig()->motorPwmProtocol = constrain(sbufReadU8(src), 0, PWM_TYPE_MAX - 1); @@ -1468,7 +1507,7 @@ static mspResult_e mspFcProcessInCommand(uint8_t cmdMSP, sbuf_t *src) } // reinitialize the gyro filters with the new values validateAndFixGyroConfig(); - gyroInit(&masterConfig.gyroConfig); + gyroInitFilters(); // reinitialize the PID filters with the new values pidInitFilters(¤tProfile->pidProfile); break; @@ -1842,6 +1881,11 @@ mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostPro if (mspFcProcessOutCommand(cmdMSP, dst, mspPostProcessFn)) { ret = MSP_RESULT_ACK; +#ifdef USE_SERIAL_4WAY_BLHELI_INTERFACE + } else if (cmdMSP == MSP_SET_4WAY_IF) { + mspFc4waySerialCommand(dst, src, mspPostProcessFn); + ret = MSP_RESULT_ACK; +#endif #ifdef GPS } else if (cmdMSP == MSP_WP) { mspFcWpCommand(dst, src); diff --git a/src/main/fc/mw.c b/src/main/fc/mw.c index 0743b6cff8..cfcf30fd2f 100644 --- a/src/main/fc/mw.c +++ b/src/main/fc/mw.c @@ -147,7 +147,6 @@ bool isCalibrating() } #define RC_RATE_INCREMENTAL 14.54f -#define RC_EXPO_POWER 3 void calculateSetpointRate(int axis, int16_t rc) { float angleRate, rcRate, rcSuperfactor, rcCommandf; @@ -167,7 +166,7 @@ void calculateSetpointRate(int axis, int16_t rc) { if (rcExpo) { float expof = rcExpo / 100.0f; - rcCommandf = rcCommandf * powerf(rcInput[axis], RC_EXPO_POWER) * expof + rcCommandf * (1-expof); + rcCommandf = rcCommandf * power3(rcInput[axis]) * expof + rcCommandf * (1-expof); } angleRate = 200.0f * rcRate * rcCommandf; @@ -212,16 +211,16 @@ void processRcCommand(void) if (isRXDataNew) { // Set RC refresh rate for sampling and channels to filter switch (rxConfig()->rcInterpolation) { - case(RC_SMOOTHING_AUTO): - rxRefreshRate = constrain(getTaskDeltaTime(TASK_RX), 1000, 20000) + 1000; // Add slight overhead to prevent ramps - break; - case(RC_SMOOTHING_MANUAL): - rxRefreshRate = 1000 * rxConfig()->rcInterpolationInterval; - break; - case(RC_SMOOTHING_OFF): - case(RC_SMOOTHING_DEFAULT): - default: - rxRefreshRate = rxGetRefreshRate(); + case(RC_SMOOTHING_AUTO): + rxRefreshRate = constrain(getTaskDeltaTime(TASK_RX), 1000, 20000) + 1000; // Add slight overhead to prevent ramps + break; + case(RC_SMOOTHING_MANUAL): + rxRefreshRate = 1000 * rxConfig()->rcInterpolationInterval; + break; + case(RC_SMOOTHING_OFF): + case(RC_SMOOTHING_DEFAULT): + default: + rxRefreshRate = rxGetRefreshRate(); } rcInterpolationFactor = rxRefreshRate / targetPidLooptime + 1; @@ -290,7 +289,7 @@ void updateRcCommands(void) tmp = 0; } rcCommand[axis] = tmp; - } else if (axis == YAW) { + } else { if (tmp > rcControlsConfig()->yaw_deadband) { tmp -= rcControlsConfig()->yaw_deadband; } else { @@ -679,7 +678,7 @@ void subTaskPidController(void) // PID - note this is function pointer set by setPIDController() pidController( ¤tProfile->pidProfile, - masterConfig.max_angle_inclination, + pidConfig()->max_angle_inclination, &masterConfig.accelerometerTrims, rxConfig()->midrc ); @@ -693,74 +692,74 @@ void subTaskMainSubprocesses(void) // Read out gyro temperature. can use it for something somewhere. maybe get MCU temperature instead? lots of fun possibilities. if (gyro.dev.temperature) { - gyro.dev.temperature(&telemTemperature1); + gyro.dev.temperature(&gyro.dev, &telemTemperature1); } - #ifdef MAG - if (sensors(SENSOR_MAG)) { - updateMagHold(); - } - #endif - - #ifdef GTUNE - updateGtuneState(); - #endif - - #if defined(BARO) || defined(SONAR) - // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState - updateRcCommands(); - if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { - if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { - applyAltHold(&masterConfig.airplaneConfig); - } - } - #endif - - // If we're armed, at minimum throttle, and we do arming via the - // sticks, do not process yaw input from the rx. We do this so the - // motors do not spin up while we are trying to arm or disarm. - // Allow yaw control for tricopters if the user wants the servo to move even when unarmed. - if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck - #ifndef USE_QUAD_MIXER_ONLY - #ifdef USE_SERVOS - && !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoMixerConfig()->tri_unarmed_servo) - #endif - && mixerConfig()->mixerMode != MIXER_AIRPLANE - && mixerConfig()->mixerMode != MIXER_FLYING_WING - #endif - ) { - rcCommand[YAW] = 0; - setpointRate[YAW] = 0; +#ifdef MAG + if (sensors(SENSOR_MAG)) { + updateMagHold(); } +#endif - if (throttleCorrectionConfig()->throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) { - rcCommand[THROTTLE] += calculateThrottleAngleCorrection(throttleCorrectionConfig()->throttle_correction_value); - } +#ifdef GTUNE + updateGtuneState(); +#endif - processRcCommand(); - - #ifdef GPS - if (sensors(SENSOR_GPS)) { - if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) { - updateGpsStateForHomeAndHoldMode(); +#if defined(BARO) || defined(SONAR) + // updateRcCommands sets rcCommand, which is needed by updateAltHoldState and updateSonarAltHoldState + updateRcCommands(); + if (sensors(SENSOR_BARO) || sensors(SENSOR_SONAR)) { + if (FLIGHT_MODE(BARO_MODE) || FLIGHT_MODE(SONAR_MODE)) { + applyAltHold(&masterConfig.airplaneConfig); } } - #endif +#endif - #ifdef USE_SDCARD - afatfs_poll(); - #endif + // If we're armed, at minimum throttle, and we do arming via the + // sticks, do not process yaw input from the rx. We do this so the + // motors do not spin up while we are trying to arm or disarm. + // Allow yaw control for tricopters if the user wants the servo to move even when unarmed. + if (isUsingSticksForArming() && rcData[THROTTLE] <= rxConfig()->mincheck +#ifndef USE_QUAD_MIXER_ONLY +#ifdef USE_SERVOS + && !((mixerConfig()->mixerMode == MIXER_TRI || mixerConfig()->mixerMode == MIXER_CUSTOM_TRI) && servoMixerConfig()->tri_unarmed_servo) +#endif + && mixerConfig()->mixerMode != MIXER_AIRPLANE + && mixerConfig()->mixerMode != MIXER_FLYING_WING +#endif + ) { + rcCommand[YAW] = 0; + setpointRate[YAW] = 0; + } - #ifdef BLACKBOX - if (!cliMode && feature(FEATURE_BLACKBOX)) { - handleBlackbox(startTime); + if (throttleCorrectionConfig()->throttle_correction_value && (FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE))) { + rcCommand[THROTTLE] += calculateThrottleAngleCorrection(throttleCorrectionConfig()->throttle_correction_value); + } + + processRcCommand(); + +#ifdef GPS + if (sensors(SENSOR_GPS)) { + if ((FLIGHT_MODE(GPS_HOME_MODE) || FLIGHT_MODE(GPS_HOLD_MODE)) && STATE(GPS_FIX_HOME)) { + updateGpsStateForHomeAndHoldMode(); } - #endif + } +#endif - #ifdef TRANSPONDER - transponderUpdate(startTime); - #endif - DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime); +#ifdef USE_SDCARD + afatfs_poll(); +#endif + +#ifdef BLACKBOX + if (!cliMode && feature(FEATURE_BLACKBOX)) { + handleBlackbox(startTime); + } +#endif + +#ifdef TRANSPONDER + transponderUpdate(startTime); +#endif + DEBUG_SET(DEBUG_PIDLOOP, 2, micros() - startTime); } void subTaskMotorUpdate(void) @@ -778,9 +777,11 @@ void subTaskMotorUpdate(void) #ifdef USE_SERVOS // motor outputs are used as sources for servo mixing, so motors must be calculated using mixTable() before servos. - servoTable(); - filterServos(); - writeServos(); + if (isMixerUsingServos()) { + servoTable(); + filterServos(); + writeServos(); + } #endif if (motorControlEnable) { @@ -792,7 +793,7 @@ void subTaskMotorUpdate(void) uint8_t setPidUpdateCountDown(void) { if (gyroConfig()->gyro_soft_lpf_hz) { - return masterConfig.pid_process_denom - 1; + return pidConfig()->pid_process_denom - 1; } else { return 1; } diff --git a/src/main/flight/pid.c b/src/main/flight/pid.c index 80bbf9b2fb..a534223850 100644 --- a/src/main/flight/pid.c +++ b/src/main/flight/pid.c @@ -163,8 +163,7 @@ void pidInitConfig(const pidProfile_t *pidProfile) { // Betaflight pid controller, which will be maintained in the future with additional features specialised for current (mini) multirotor usage. // Based on 2DOF reference design (matlab) -void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, - const rollAndPitchTrims_t *angleTrim, uint16_t midrc) +void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const rollAndPitchTrims_t *angleTrim, uint16_t midrc) { static float previousRateError[2]; static float previousSetpoint[3]; @@ -217,13 +216,12 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio // Yaw control is GYRO based, direct sticks control is applied to rate PID if ((FLIGHT_MODE(ANGLE_MODE) || FLIGHT_MODE(HORIZON_MODE)) && axis != YAW) { // calculate error angle and limit the angle to the max inclination + float errorAngle = pidProfile->levelSensitivity * rcCommand[axis]; #ifdef GPS - const float errorAngle = (constrainf(pidProfile->levelSensitivity * rcCommand[axis] + GPS_angle[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here -#else - const float errorAngle = (constrainf(pidProfile->levelSensitivity * rcCommand[axis], -((int) max_angle_inclination), - +max_angle_inclination) - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; // 16 bits is ok here + errorAngle += GPS_angle[axis]; #endif + errorAngle = constrainf(errorAngle, -max_angle_inclination, max_angle_inclination); + errorAngle = (errorAngle - attitude.raw[axis] + angleTrim->raw[axis]) / 10.0f; if (FLIGHT_MODE(ANGLE_MODE)) { // ANGLE mode - control is angle based, so control loop is needed setpointRate[axis] = errorAngle * pidProfile->P8[PIDLEVEL] / 10.0f; @@ -265,10 +263,10 @@ void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclinatio dynC = c[axis]; if (setpointRate[axis] > 0) { if ((setpointRate[axis] - previousSetpoint[axis]) < previousSetpoint[axis]) - dynC = dynC * powerf(rcInput[axis], 2) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); + dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); } else if (setpointRate[axis] < 0) { if ((setpointRate[axis] - previousSetpoint[axis]) > previousSetpoint[axis]) - dynC = dynC * powerf(rcInput[axis], 2) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); + dynC = dynC * sq(rcInput[axis]) * relaxFactor[axis] + dynC * (1-relaxFactor[axis]); } } const float rD = dynC * setpointRate[axis] - PVRate; // cr - y diff --git a/src/main/flight/pid.h b/src/main/flight/pid.h index 8ecd833e09..27387afbb5 100644 --- a/src/main/flight/pid.h +++ b/src/main/flight/pid.h @@ -90,9 +90,13 @@ typedef struct pidProfile_s { #endif } pidProfile_t; +typedef struct pidConfig_s { + uint8_t pid_process_denom; // Processing denominator for PID controller vs gyro sampling rate + uint16_t max_angle_inclination; +} pidConfig_t; + union rollAndPitchTrims_u; -void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, - const union rollAndPitchTrims_u *angleTrim, uint16_t midrc); +void pidController(const pidProfile_t *pidProfile, uint16_t max_angle_inclination, const union rollAndPitchTrims_u *angleTrim, uint16_t midrc); extern float axisPIDf[3]; extern int32_t axisPID_P[3], axisPID_I[3], axisPID_D[3]; diff --git a/src/main/flight/servos.c b/src/main/flight/servos.c index 707957aa54..314857d427 100755 --- a/src/main/flight/servos.c +++ b/src/main/flight/servos.c @@ -269,50 +269,50 @@ void writeServos(void) uint8_t servoIndex = 0; switch (currentMixerMode) { - case MIXER_BICOPTER: - pwmWriteServo(servoIndex++, servo[SERVO_BICOPTER_LEFT]); - pwmWriteServo(servoIndex++, servo[SERVO_BICOPTER_RIGHT]); - break; + case MIXER_BICOPTER: + pwmWriteServo(servoIndex++, servo[SERVO_BICOPTER_LEFT]); + pwmWriteServo(servoIndex++, servo[SERVO_BICOPTER_RIGHT]); + break; - case MIXER_TRI: - case MIXER_CUSTOM_TRI: - if (servoMixerConfig->tri_unarmed_servo) { - // if unarmed flag set, we always move servo + case MIXER_TRI: + case MIXER_CUSTOM_TRI: + if (servoMixerConfig->tri_unarmed_servo) { + // if unarmed flag set, we always move servo + pwmWriteServo(servoIndex++, servo[SERVO_RUDDER]); + } else { + // otherwise, only move servo when copter is armed + if (ARMING_FLAG(ARMED)) pwmWriteServo(servoIndex++, servo[SERVO_RUDDER]); - } else { - // otherwise, only move servo when copter is armed - if (ARMING_FLAG(ARMED)) - pwmWriteServo(servoIndex++, servo[SERVO_RUDDER]); - else - pwmWriteServo(servoIndex++, 0); // kill servo signal completely. - } - break; + else + pwmWriteServo(servoIndex++, 0); // kill servo signal completely. + } + break; - case MIXER_FLYING_WING: - pwmWriteServo(servoIndex++, servo[SERVO_FLAPPERON_1]); - pwmWriteServo(servoIndex++, servo[SERVO_FLAPPERON_2]); - break; + case MIXER_FLYING_WING: + pwmWriteServo(servoIndex++, servo[SERVO_FLAPPERON_1]); + pwmWriteServo(servoIndex++, servo[SERVO_FLAPPERON_2]); + break; - case MIXER_DUALCOPTER: - pwmWriteServo(servoIndex++, servo[SERVO_DUALCOPTER_LEFT]); - pwmWriteServo(servoIndex++, servo[SERVO_DUALCOPTER_RIGHT]); - break; + case MIXER_DUALCOPTER: + pwmWriteServo(servoIndex++, servo[SERVO_DUALCOPTER_LEFT]); + pwmWriteServo(servoIndex++, servo[SERVO_DUALCOPTER_RIGHT]); + break; - case MIXER_CUSTOM_AIRPLANE: - case MIXER_AIRPLANE: - for (int i = SERVO_PLANE_INDEX_MIN; i <= SERVO_PLANE_INDEX_MAX; i++) { - pwmWriteServo(servoIndex++, servo[i]); - } - break; + case MIXER_CUSTOM_AIRPLANE: + case MIXER_AIRPLANE: + for (int i = SERVO_PLANE_INDEX_MIN; i <= SERVO_PLANE_INDEX_MAX; i++) { + pwmWriteServo(servoIndex++, servo[i]); + } + break; - case MIXER_SINGLECOPTER: - for (int i = SERVO_SINGLECOPTER_INDEX_MIN; i <= SERVO_SINGLECOPTER_INDEX_MAX; i++) { - pwmWriteServo(servoIndex++, servo[i]); - } - break; + case MIXER_SINGLECOPTER: + for (int i = SERVO_SINGLECOPTER_INDEX_MIN; i <= SERVO_SINGLECOPTER_INDEX_MAX; i++) { + pwmWriteServo(servoIndex++, servo[i]); + } + break; - default: - break; + default: + break; } // Two servos for SERVO_TILT, if enabled @@ -410,27 +410,27 @@ void servoTable(void) { // airplane / servo mixes switch (currentMixerMode) { - case MIXER_CUSTOM_AIRPLANE: - case MIXER_FLYING_WING: - case MIXER_AIRPLANE: - case MIXER_BICOPTER: - case MIXER_CUSTOM_TRI: - case MIXER_TRI: - case MIXER_DUALCOPTER: - case MIXER_SINGLECOPTER: - case MIXER_GIMBAL: - servoMixer(); - break; + case MIXER_CUSTOM_AIRPLANE: + case MIXER_FLYING_WING: + case MIXER_AIRPLANE: + case MIXER_BICOPTER: + case MIXER_CUSTOM_TRI: + case MIXER_TRI: + case MIXER_DUALCOPTER: + case MIXER_SINGLECOPTER: + case MIXER_GIMBAL: + servoMixer(); + break; - /* - case MIXER_GIMBAL: - servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); - servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); - break; - */ + /* + case MIXER_GIMBAL: + servo[SERVO_GIMBAL_PITCH] = (((int32_t)servoConf[SERVO_GIMBAL_PITCH].rate * attitude.values.pitch) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_PITCH); + servo[SERVO_GIMBAL_ROLL] = (((int32_t)servoConf[SERVO_GIMBAL_ROLL].rate * attitude.values.roll) / 50) + determineServoMiddleOrForwardFromChannel(SERVO_GIMBAL_ROLL); + break; + */ - default: - break; + default: + break; } // camera stabilization diff --git a/src/main/io/serial_4way.c b/src/main/io/serial_4way.c index 3166e3af9b..f2d0563608 100644 --- a/src/main/io/serial_4way.c +++ b/src/main/io/serial_4way.c @@ -807,6 +807,8 @@ void esc4wayProcess(serialPort_t *mspPort) i=O_PARAM_LEN; do { + while (!serialTxBytesFree(port)); + WriteByteCrc(*O_PARAM); O_PARAM++; i--; diff --git a/src/main/io/serial_cli.c b/src/main/io/serial_cli.c index 0845abb093..9abcb6b125 100755 --- a/src/main/io/serial_cli.c +++ b/src/main/io/serial_cli.c @@ -701,7 +701,9 @@ const clivalue_t valueTable[] = { { "rc_interpolation", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->rcInterpolation, .config.lookup = { TABLE_RC_INTERPOLATION } }, { "rc_interpolation_interval", VAR_UINT8 | MASTER_VALUE, &rxConfig()->rcInterpolationInterval, .config.minmax = { 1, 50 } }, { "rssi_ppm_invert", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &rxConfig()->rssi_ppm_invert, .config.lookup = { TABLE_OFF_ON } }, - { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.inputFilteringMode, .config.lookup = { TABLE_OFF_ON } }, +#if defined(USE_PWM) + { "input_filtering_mode", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &pwmConfig()->inputFilteringMode, .config.lookup = { TABLE_OFF_ON } }, +#endif { "roll_yaw_cam_mix_degrees", VAR_UINT8 | MASTER_VALUE, &rxConfig()->fpvCamAngleDegrees, .config.minmax = { 0, 50 } }, { "max_aux_channels", VAR_UINT8 | MASTER_VALUE, &rxConfig()->max_aux_channel, .config.minmax = { 0, 13 } }, { "debug_mode", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &masterConfig.debug_mode, .config.lookup = { TABLE_DEBUG } }, @@ -818,7 +820,6 @@ const clivalue_t valueTable[] = { { "align_board_pitch", VAR_INT16 | MASTER_VALUE, &boardAlignment()->pitchDegrees, .config.minmax = { -180, 360 } }, { "align_board_yaw", VAR_INT16 | MASTER_VALUE, &boardAlignment()->yawDegrees, .config.minmax = { -180, 360 } }, - { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &masterConfig.max_angle_inclination, .config.minmax = { 100, 900 } }, { "gyro_lpf", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gyroConfig()->gyro_lpf, .config.lookup = { TABLE_GYRO_LPF } }, { "gyro_sync_denom", VAR_UINT8 | MASTER_VALUE, &gyroConfig()->gyro_sync_denom, .config.minmax = { 1, 8 } }, { "gyro_lowpass_type", VAR_UINT8 | MASTER_VALUE | MODE_LOOKUP, &gyroConfig()->gyro_soft_lpf_type, .config.lookup = { TABLE_LOWPASS_TYPE } }, @@ -844,6 +845,7 @@ const clivalue_t valueTable[] = { { "yaw_motor_direction", VAR_INT8 | MASTER_VALUE, &mixerConfig()->yaw_motor_direction, .config.minmax = { -1, 1 } }, { "yaw_p_limit", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_p_limit, .config.minmax = { YAW_P_LIMIT_MIN, YAW_P_LIMIT_MAX } }, { "pidsum_limit", VAR_FLOAT | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.pidSumLimit, .config.minmax = { 0.1, 1.0 } }, + { "max_angle_inclination", VAR_UINT16 | MASTER_VALUE, &pidConfig()->max_angle_inclination, .config.minmax = { 100, 900 } }, #ifdef USE_SERVOS { "servo_center_pulse", VAR_UINT16 | MASTER_VALUE, &servoConfig()->servoCenterPulse, .config.minmax = { PWM_RANGE_ZERO, PWM_RANGE_MAX } }, { "tri_unarmed_servo", VAR_INT8 | MASTER_VALUE | MODE_LOOKUP, &servoMixerConfig()->tri_unarmed_servo, .config.lookup = { TABLE_OFF_ON } }, @@ -911,7 +913,7 @@ const clivalue_t valueTable[] = { { "accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.rollPitchItermIgnoreRate, .config.minmax = {15, 1000 } }, { "yaw_accum_threshold", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yawItermIgnoreRate, .config.minmax = {15, 1000 } }, { "yaw_lowpass", VAR_UINT16 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.yaw_lpf_hz, .config.minmax = {0, 500 } }, - { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &masterConfig.pid_process_denom, .config.minmax = { 1, 8 } }, + { "pid_process_denom", VAR_UINT8 | MASTER_VALUE, &pidConfig()->pid_process_denom, .config.minmax = { 1, 8 } }, { "p_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.P8[PITCH], .config.minmax = { 0, 200 } }, { "i_pitch", VAR_UINT8 | PROFILE_VALUE, &masterConfig.profile[0].pidProfile.I8[PITCH], .config.minmax = { 0, 200 } }, @@ -3658,8 +3660,8 @@ static void cliTasks(char *cmdline) int subTaskFrequency; if (taskId == TASK_GYROPID) { subTaskFrequency = (int)(1000000.0f / ((float)cycleTime)); - taskFrequency = subTaskFrequency / masterConfig.pid_process_denom; - if (masterConfig.pid_process_denom > 1) { + taskFrequency = subTaskFrequency / pidConfig()->pid_process_denom; + if (pidConfig()->pid_process_denom > 1) { cliPrintf("%02d - (%13s) ", taskId, taskInfo.taskName); } else { taskFrequency = subTaskFrequency; @@ -3678,7 +3680,7 @@ static void cliTasks(char *cmdline) cliPrintf("%6d %7d %7d %4d.%1d%% %4d.%1d%% %9d\r\n", taskFrequency, taskInfo.maxExecutionTime, taskInfo.averageExecutionTime, maxLoad/10, maxLoad%10, averageLoad/10, averageLoad%10, taskInfo.totalExecutionTime / 1000); - if (taskId == TASK_GYROPID && masterConfig.pid_process_denom > 1) { + if (taskId == TASK_GYROPID && pidConfig()->pid_process_denom > 1) { cliPrintf(" - (%13s) %6d\r\n", taskInfo.subTaskName, subTaskFrequency); } } diff --git a/src/main/main.c b/src/main/main.c index 591acc3b71..a4cd068421 100644 --- a/src/main/main.c +++ b/src/main/main.c @@ -45,6 +45,7 @@ #include "drivers/serial_uart.h" #include "drivers/accgyro.h" #include "drivers/compass.h" +#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_rx.h" #include "drivers/pwm_output.h" #include "drivers/adc.h" @@ -283,11 +284,10 @@ void init(void) #if defined(USE_PWM) || defined(USE_PPM) if (feature(FEATURE_RX_PPM)) { - ppmRxInit(&masterConfig.ppmConfig, motorConfig()->motorPwmProtocol); + ppmRxInit(ppmConfig(), motorConfig()->motorPwmProtocol); } else if (feature(FEATURE_RX_PARALLEL_PWM)) { - pwmRxInit(&masterConfig.pwmConfig); + pwmRxInit(pwmConfig()); } - pwmRxSetInputFilteringMode(masterConfig.inputFilteringMode); #endif systemState |= SYSTEM_STATE_MOTORS_READY; @@ -416,7 +416,7 @@ void init(void) LED1_OFF; // gyro.targetLooptime set in sensorsAutodetect(), so we are ready to call pidSetTargetLooptime() - pidSetTargetLooptime((gyro.targetLooptime + LOOPTIME_SUSPEND_TIME) * masterConfig.pid_process_denom); // Initialize pid looptime + pidSetTargetLooptime((gyro.targetLooptime + LOOPTIME_SUSPEND_TIME) * pidConfig()->pid_process_denom); // Initialize pid looptime pidInitFilters(¤tProfile->pidProfile); pidInitConfig(¤tProfile->pidProfile); diff --git a/src/main/scheduler/scheduler.c b/src/main/scheduler/scheduler.c index 623b8aed14..12c6419521 100755 --- a/src/main/scheduler/scheduler.c +++ b/src/main/scheduler/scheduler.c @@ -176,9 +176,10 @@ void setTaskEnabled(cfTaskId_e taskId, bool enabled) uint32_t getTaskDeltaTime(cfTaskId_e taskId) { - if (taskId == TASK_SELF || taskId < TASK_COUNT) { - cfTask_t *task = taskId == TASK_SELF ? currentTask : &cfTasks[taskId]; - return task->taskLatestDeltaTime; + if (taskId == TASK_SELF) { + return currentTask->taskLatestDeltaTime; + } else if (taskId < TASK_COUNT) { + return cfTasks[taskId].taskLatestDeltaTime; } else { return 0; } diff --git a/src/main/sensors/acceleration.c b/src/main/sensors/acceleration.c index 6061341630..0b2017d3db 100644 --- a/src/main/sensors/acceleration.c +++ b/src/main/sensors/acceleration.c @@ -17,6 +17,7 @@ #include #include +#include #include #include "platform.h" @@ -226,8 +227,12 @@ retry: return true; } -void accInit(uint32_t gyroSamplingInverval) +bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroSamplingInverval) { + memset(&acc, 0, sizeof(acc)); + if (!accDetect(&acc.dev, accelerometerConfig->acc_hardware)) { + return false; + } acc.dev.acc_1G = 256; // set default acc.dev.init(&acc.dev); // driver initialisation // set the acc sampling interval according to the gyro sampling interval @@ -251,6 +256,7 @@ void accInit(uint32_t gyroSamplingInverval) biquadFilterInitLPF(&accFilter[axis], accLpfCutHz, acc.accSamplingInterval); } } + return true; } void accSetCalibrationCycles(uint16_t calibrationCyclesRequired) @@ -373,15 +379,13 @@ static void applyAccelerationTrims(const flightDynamicsTrims_t *accelerationTrim void updateAccelerationReadings(rollAndPitchTrims_t *rollAndPitchTrims) { - int16_t accADCRaw[XYZ_AXIS_COUNT]; - - if (!acc.dev.read(accADCRaw)) { + if (!acc.dev.read(&acc.dev)) { return; } for (int axis = 0; axis < XYZ_AXIS_COUNT; axis++) { - DEBUG_SET(DEBUG_ACCELEROMETER, axis, accADCRaw[axis]); - acc.accSmooth[axis] = accADCRaw[axis]; + DEBUG_SET(DEBUG_ACCELEROMETER, axis, acc.dev.ADCRaw[axis]); + acc.accSmooth[axis] = acc.dev.ADCRaw[axis]; } if (accLpfCutHz) { diff --git a/src/main/sensors/acceleration.h b/src/main/sensors/acceleration.h index 1a4b05b3f3..e936ca2035 100644 --- a/src/main/sensors/acceleration.h +++ b/src/main/sensors/acceleration.h @@ -61,8 +61,7 @@ typedef struct accelerometerConfig_s { flightDynamicsTrims_t accZero; } accelerometerConfig_t; -bool accDetect(accDev_t *dev, accelerationSensor_e accHardwareToUse); -void accInit(uint32_t gyroTargetLooptime); +bool accInit(const accelerometerConfig_t *accelerometerConfig, uint32_t gyroTargetLooptime); bool isAccelerationCalibrationComplete(void); void accSetCalibrationCycles(uint16_t calibrationCyclesRequired); void resetRollAndPitchTrims(rollAndPitchTrims_t *rollAndPitchTrims); diff --git a/src/main/sensors/gyro.c b/src/main/sensors/gyro.c index 691597a5b6..deea9ba348 100644 --- a/src/main/sensors/gyro.c +++ b/src/main/sensors/gyro.c @@ -17,6 +17,7 @@ #include #include +#include #include #include "platform.h" @@ -39,12 +40,13 @@ #include "drivers/accgyro_mpu6500.h" #include "drivers/accgyro_l3gd20.h" #include "drivers/accgyro_lsm303dlhc.h" -#include "drivers/bus_spi.h" #include "drivers/accgyro_spi_icm20689.h" #include "drivers/accgyro_spi_mpu6000.h" #include "drivers/accgyro_spi_mpu6500.h" #include "drivers/accgyro_spi_mpu9250.h" +#include "drivers/bus_spi.h" #include "drivers/gyro_sync.h" +#include "drivers/io.h" #include "drivers/system.h" #include "fc/runtime_config.h" @@ -56,6 +58,10 @@ #include "sensors/boardalignment.h" #include "sensors/gyro.h" +#ifdef USE_HARDWARE_REVISION_DETECTION +#include "hardware_revision.h" +#endif + gyro_t gyro; // gyro access functions static int32_t gyroADC[XYZ_AXIS_COUNT]; @@ -71,7 +77,19 @@ static void *notchFilter1[3]; static filterApplyFnPtr notchFilter2ApplyFn; static void *notchFilter2[3]; -bool gyroDetect(gyroDev_t *dev) +static const extiConfig_t *selectMPUIntExtiConfig(void) +{ +#if defined(MPU_INT_EXTI) + static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; + return &mpuIntExtiConfig; +#elif defined(USE_HARDWARE_REVISION_DETECTION) + return selectMPUIntExtiConfigByHardwareRevision(); +#else + return NULL; +#endif +} + +static bool gyroDetect(gyroDev_t *dev) { gyroSensor_e gyroHardware = GYRO_DEFAULT; @@ -208,7 +226,26 @@ case GYRO_MPU9250: return true; } -void gyroInit(const gyroConfig_t *gyroConfigToUse) +bool gyroInit(const gyroConfig_t *gyroConfigToUse) +{ + gyroConfig = gyroConfigToUse; + memset(&gyro, 0, sizeof(gyro)); +#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689) + const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); + mpuDetect(extiConfig); +#endif + + if (!gyroDetect(&gyro.dev)) { + return false; + } + gyro.targetLooptime = gyroSetSampleRate(gyroConfig->gyro_lpf, gyroConfig->gyro_sync_denom); // Set gyro sample rate before initialisation + gyro.dev.lpf = gyroConfig->gyro_lpf; + gyro.dev.init(&gyro.dev); + gyroInitFilters(); + return true; +} + +void gyroInitFilters(void) { static biquadFilter_t gyroFilterLPF[XYZ_AXIS_COUNT]; static pt1Filter_t gyroFilterPt1[XYZ_AXIS_COUNT]; @@ -216,11 +253,6 @@ void gyroInit(const gyroConfig_t *gyroConfigToUse) static biquadFilter_t gyroFilterNotch_1[XYZ_AXIS_COUNT]; static biquadFilter_t gyroFilterNotch_2[XYZ_AXIS_COUNT]; - gyroConfig = gyroConfigToUse; - gyro.targetLooptime = gyroSetSampleRate(gyroConfig->gyro_lpf, gyroConfig->gyro_sync_denom); // Set gyro sample rate before initialisation - gyro.dev.lpf = gyroConfig->gyro_lpf; - gyro.dev.init(&gyro.dev); - softLpfFilterApplyFn = nullFilterApply; notchFilter1ApplyFn = nullFilterApply; notchFilter2ApplyFn = nullFilterApply; diff --git a/src/main/sensors/gyro.h b/src/main/sensors/gyro.h index 656ec47f53..1cd410f147 100644 --- a/src/main/sensors/gyro.h +++ b/src/main/sensors/gyro.h @@ -55,9 +55,8 @@ typedef struct gyroConfig_s { uint16_t gyro_soft_notch_cutoff_2; } gyroConfig_t; -bool gyroDetect(gyroDev_t *dev); void gyroSetCalibrationCycles(void); -void gyroInit(const gyroConfig_t *gyroConfigToUse); +bool gyroInit(const gyroConfig_t *gyroConfigToUse); +void gyroInitFilters(void); void gyroUpdate(void); bool isGyroCalibrationComplete(void); - diff --git a/src/main/sensors/initialisation.c b/src/main/sensors/initialisation.c index 341ca113eb..01b396b2c1 100755 --- a/src/main/sensors/initialisation.c +++ b/src/main/sensors/initialisation.c @@ -14,28 +14,17 @@ * 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/build_config.h" - -#include "common/axis.h" +#include "common/utils.h" #include "config/feature.h" -#include "drivers/accgyro_mpu.h" -#include "drivers/io.h" -#include "drivers/system.h" -#include "drivers/exti.h" -#include "drivers/sensor.h" -#include "drivers/accgyro.h" -#include "drivers/barometer.h" -#include "drivers/compass.h" -#include "drivers/sonar_hcsr04.h" - #include "fc/config.h" #include "fc/runtime_config.h" @@ -47,26 +36,9 @@ #include "sensors/sonar.h" #include "sensors/initialisation.h" -#ifdef USE_HARDWARE_REVISION_DETECTION -#include "hardware_revision.h" -#endif - - uint8_t detectedSensors[SENSOR_INDEX_COUNT] = { GYRO_NONE, ACC_NONE, BARO_NONE, MAG_NONE }; -const extiConfig_t *selectMPUIntExtiConfig(void) -{ -#if defined(MPU_INT_EXTI) - static const extiConfig_t mpuIntExtiConfig = { .tag = IO_TAG(MPU_INT_EXTI) }; - return &mpuIntExtiConfig; -#elif defined(USE_HARDWARE_REVISION_DETECTION) - return selectMPUIntExtiConfigByHardwareRevision(); -#else - return NULL; -#endif -} - #ifdef SONAR static bool sonarDetect(void) { @@ -86,26 +58,12 @@ bool sensorsAutodetect(const gyroConfig_t *gyroConfig, const barometerConfig_t *barometerConfig, const sonarConfig_t *sonarConfig) { - -#if defined(USE_GYRO_MPU6050) || defined(USE_GYRO_MPU3050) || defined(USE_GYRO_MPU6500) || defined(USE_GYRO_SPI_MPU6500) || defined(USE_GYRO_SPI_MPU6000) || defined(USE_ACC_MPU6050) || defined(USE_GYRO_SPI_MPU9250) || defined(USE_GYRO_SPI_ICM20689) - - const extiConfig_t *extiConfig = selectMPUIntExtiConfig(); - - mpuDetectionResult_t *mpuDetectionResult = mpuDetect(extiConfig); - UNUSED(mpuDetectionResult); -#endif - - memset(&gyro, 0, sizeof(gyro)); - if (!gyroDetect(&gyro.dev)) { + // gyro must be initialised before accelerometer + if (!gyroInit(gyroConfig)) { return false; } - // gyro must be initialised before accelerometer - gyroInit(gyroConfig); - memset(&acc, 0, sizeof(acc)); - if (accDetect(&acc.dev, accelerometerConfig->acc_hardware)) { - accInit(gyro.targetLooptime); - } + accInit(accelerometerConfig, gyro.targetLooptime); mag.magneticDeclination = 0.0f; // TODO investigate if this is actually needed if there is no mag sensor or if the value stored in the config should be used. #ifdef MAG diff --git a/src/main/target/ALIENFLIGHTF1/config.c b/src/main/target/ALIENFLIGHTF1/config.c index 89bf61ecbb..109d2ff41a 100644 --- a/src/main/target/ALIENFLIGHTF1/config.c +++ b/src/main/target/ALIENFLIGHTF1/config.c @@ -20,6 +20,7 @@ #include +#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" #include "fc/rc_controls.h" diff --git a/src/main/target/ALIENFLIGHTF3/config.c b/src/main/target/ALIENFLIGHTF3/config.c index c14ed47be5..e1d7b9e33f 100644 --- a/src/main/target/ALIENFLIGHTF3/config.c +++ b/src/main/target/ALIENFLIGHTF3/config.c @@ -24,6 +24,7 @@ #include "drivers/sensor.h" #include "drivers/compass.h" +#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" #include "fc/rc_controls.h" @@ -81,7 +82,7 @@ void targetConfiguration(master_t *config) if (hardwareMotorType == MOTOR_BRUSHED) { config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - config->pid_process_denom = 2; + config->pidConfig.pid_process_denom = 2; } config->profile[0].pidProfile.P8[ROLL] = 90; diff --git a/src/main/target/ALIENFLIGHTF3/target.c b/src/main/target/ALIENFLIGHTF3/target.c index 213ce7114b..267b2c658d 100644 --- a/src/main/target/ALIENFLIGHTF3/target.c +++ b/src/main/target/ALIENFLIGHTF3/target.c @@ -24,8 +24,12 @@ #include "drivers/timer.h" #include "drivers/timer_def.h" +// DSHOT is working for motor 1-8 +// Motor 7 is only working if battery monitoring is disabled + const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { // up to 10 Motor Outputs +/* DEF_TIM(TIM15, CH2, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM1 - PB15 - DMA_NONE - TIM1_CH3N, TIM15_CH1N, *TIM15_CH2 DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1 DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR @@ -37,5 +41,17 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM9 - PA4 - DMA_NONE - *TIM3_CH2 DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM10 - PA1 - DMA1_CH7 - *TIM2_CH2, TIM15_CH1N DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED ), // PPM - PA3 - TIM2_CH4, TIM15_CH2 - PWM13 +*/ + DEF_TIM(TIM1, CH3N, PB15, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED ), // PWM1 - PB15 - DMA1_CH6 - *TIM1_CH3N, TIM15_CH1N, TIM15_CH2 + DEF_TIM(TIM15, CH1, PB14, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM2 - PB14 - DMA1_CH5 - TIM1_CH2N, *TIM15_CH1 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM3 - PA8 - DMA1_CH2 - *TIM1_CH1, TIM4_ETR + DEF_TIM(TIM8, CH2N, PB0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED ), // PWM4 - PB0 - DMA2_CH5 - TIM3_CH3, TIM1_CH2N, *TIM8_CH2N + DEF_TIM(TIM16, CH1, PA6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM5 - PA6 - DMA1_CH3 - TIM3_CH1, TIM8_BKIN, TIM1_BKIN, *TIM16_CH1 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM6 - PA2 - DMA1_CH1 - *TIM2_CH3, !TIM15_CH1 + DEF_TIM(TIM8, CH3N, PB1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED | TIMER_OUTPUT_INVERTED ), // PWM7 - PB1 - DMA2_CH1 - TIM3_CH4, TIM1_CH3N, *TIM8_CH3N + DEF_TIM(TIM17, CH1, PA7, TIM_USE_MOTOR | TIM_USE_LED, TIMER_OUTPUT_ENABLED ), // PWM8 - PA7 - DMA1_CH7 - !TIM3_CH2, *TIM17_CH1, TIM1_CH1N, TIM8_CH1 + DEF_TIM(TIM3, CH2, PA4, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM9 - PA4 - DMA_NONE - *TIM3_CH2 + DEF_TIM(TIM2, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED ), // PWM10 - PA1 - DMA1_CH7 - *TIM2_CH2, TIM15_CH1N + DEF_TIM(TIM2, CH4, PA3, TIM_USE_PPM, TIMER_INPUT_ENABLED ), // PPM - PA3 - DMA1_CH7 - TIM2_CH4, TIM15_CH2 }; diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 0f091017da..6f8d943584 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -20,6 +20,7 @@ #define TARGET_BOARD_IDENTIFIER "AFF3" // AlienFlight F3. #define TARGET_CONFIG #define TARGET_BUS_INIT +#define REMAP_TIM17_DMA #define CONFIG_FASTLOOP_PREFERRED_ACC ACC_DEFAULT @@ -122,6 +123,8 @@ #define SERIALRX_UART SERIAL_PORT_USART2 #define RX_CHANNELS_TAER +#define LED_STRIP + #define USE_SERIAL_4WAY_BLHELI_INTERFACE // IO - stm32f303cc in 48pin package diff --git a/src/main/target/ALIENFLIGHTF4/config.c b/src/main/target/ALIENFLIGHTF4/config.c index 7a9b8bc54d..510dbe8927 100644 --- a/src/main/target/ALIENFLIGHTF4/config.c +++ b/src/main/target/ALIENFLIGHTF4/config.c @@ -24,6 +24,7 @@ #include "drivers/sensor.h" #include "drivers/compass.h" +#include "drivers/pwm_esc_detect.h" #include "drivers/pwm_output.h" #include "drivers/serial.h" @@ -62,7 +63,7 @@ void targetConfiguration(master_t *config) if (hardwareMotorType == MOTOR_BRUSHED) { config->motorConfig.motorPwmRate = BRUSHED_MOTORS_PWM_RATE; - config->pid_process_denom = 1; + config->pidConfig.pid_process_denom = 1; } if (hardwareRevision == AFF4_REV_1) { diff --git a/src/main/target/ALIENFLIGHTF4/target.c b/src/main/target/ALIENFLIGHTF4/target.c index 10a23f8986..8bc3031767 100644 --- a/src/main/target/ALIENFLIGHTF4/target.c +++ b/src/main/target/ALIENFLIGHTF4/target.c @@ -24,7 +24,13 @@ #include "drivers/timer.h" #include "drivers/timer_def.h" +// DSHOT will work for motor 1,3,4,5,6,7 and 8. +// Motor 2 pin timers have no DMA channel assigned in the hardware. +// If the ADC is used motor 7 will not work. +// If UART1 is used motor 8 will not work. + const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { +/* DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 0), // PWM1 - PA8 RC1 DEF_TIM(TIM1, CH2, PB0, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM2 - PB0 RC2 DEF_TIM(TIM1, CH3, PB1, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM3 - PB1 RC3 @@ -38,4 +44,18 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM3, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM11 - PC7 OUT6 - DMA1_ST5 DEF_TIM(TIM3, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM13 - PC8 OUT7 - (DMA1_ST7) DEF_TIM(TIM3, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM13 - PC9 OUT8 - (DMA1_ST2) +*/ + DEF_TIM(TIM1, CH1, PA8, TIM_USE_PWM | TIM_USE_PPM, TIMER_INPUT_ENABLED, 1), // PWM1 - PA8 RC1 - DMA2_ST6, *DMA2_ST1, DMA2_ST3 + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM2 - PB0 RC2 - DMA1_ST5 + DEF_TIM(TIM3, CH4, PB1, TIM_USE_PWM, TIMER_INPUT_ENABLED, 0), // PWM3 - PB1 RC3 - DMA1_ST7 + DEF_TIM(TIM1, CH2, PB14, TIM_USE_PWM, TIMER_INPUT_ENABLED, 1), // PWM4 - PA14 RC4 - DMA2_ST6, *DMA2_ST2 + DEF_TIM(TIM1, CH3, PB15, TIM_USE_PWM | TIM_USE_LED, TIMER_INPUT_ENABLED, 0), // PWM5 - PA15 RC5 - DMA2_ST6, DMA2_ST6 + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM6 - PB8 OUT1 - DMA1_ST7 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM7 - PB9 OUT2 - DMA_NONE + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM8 - PA0 OUT3 - DMA1_ST2 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM9 - PA1 OUT4 - DMA1_ST4 + DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM10 - PC6 OUT5 - DMA2_ST2, DMA2_ST2 + DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM11 - PC7 OUT6 - DMA2_ST3, DMA2_ST2 + DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1), // PWM13 - PC8 OUT7 - DMA2_ST2, *DMA2_ST4 + DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0), // PWM13 - PC9 OUT8 - DMA2_ST7 }; diff --git a/src/main/target/ALIENFLIGHTF4/target.h b/src/main/target/ALIENFLIGHTF4/target.h index b85db3d9a1..1744475fac 100644 --- a/src/main/target/ALIENFLIGHTF4/target.h +++ b/src/main/target/ALIENFLIGHTF4/target.h @@ -151,7 +151,7 @@ #define EXTERNAL1_ADC_GPIO_PIN PC5 // LED strip configuration using RC5 pin. -//#define LED_STRIP +#define LED_STRIP #define SPEKTRUM_BIND // USART2, PA3 diff --git a/src/main/target/ANYFCF7/target.c b/src/main/target/ANYFCF7/target.c index f05f3ceeae..b2a5a909a3 100644 --- a/src/main/target/ANYFCF7/target.c +++ b/src/main/target/ANYFCF7/target.c @@ -19,72 +19,72 @@ #include #include "drivers/io.h" -#include "drivers/dma.h" +#include "drivers/dma.h" #include "drivers/timer.h" +#include "drivers/timer_def.h" #if defined(USE_DSHOT) // DSHOT TEST const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM_USE_PPM | TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN - { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN - { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN - { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN - { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S6_IN - { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, DMA1_Stream7, DMA_CHANNEL_2, DMA1_ST7_HANDLER }, // S10_OUT 1 - { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream1, DMA_CHANNEL_3, DMA1_ST1_HANDLER }, // S6_OUT 2 - { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, DMA1_Stream6, DMA_CHANNEL_3, DMA1_ST6_HANDLER }, // S1_OUT 4 - { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, DMA1_ST4_HANDLER }, // S2_OUT - { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, DMA1_Stream5, DMA_CHANNEL_5, DMA1_ST5_HANDLER }, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, DMA1_Stream2, DMA_CHANNEL_6, DMA1_ST2_HANDLER }, // S7_OUT - { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3 - { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT - { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT - { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 1, 0 ), // S10_OUT 1 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0 ), // S6_OUT 2 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 0 ), // S1_OUT 4 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0 ), // S2_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 1, 0 ), // S4_OUT + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0 ), // S7_OUT + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 1, 0 ), // S5_OUT 3 + DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 1, 0 ), // S3_OUT + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 1, 0 ), // S8_OUT + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 1, 0 ), // S9_OUT }; #else // STANDARD LAYOUT const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM_USE_PWM | TIM_USE_PPM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S1_IN - { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF9_TIM12, NULL, 0, 0 }, // S2_IN - { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S3_IN - { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S4_IN - { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S5_IN - { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM_USE_PWM, 0, GPIO_AF3_TIM8, NULL, 0, 0 }, // S6_IN + DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN + DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN + DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN + DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN + DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN + DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S6_IN - { TIM4, IO_TAG(PB8), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S10_OUT 1 - { TIM2, IO_TAG(PA2), TIM_CHANNEL_3, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S6_OUT 2 - { TIM4, IO_TAG(PB9), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF2_TIM4, NULL, 0, 0 }, // S5_OUT 3 - { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S1_OUT 4 - { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM_USE_MOTOR | TIM_USE_LED, 1, GPIO_AF2_TIM5, DMA1_Stream4, DMA_CHANNEL_6, 0 }, // S2_OUT - { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF3_TIM9, NULL, 0, 0 }, // S3_OUT - { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S4_OUT - { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM5, NULL, 0, 0 }, // S7_OUT - { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM_USE_MOTOR, 1, GPIO_AF1_TIM2, NULL, 0, 0 }, // S8_OUT - { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM_USE_MOTOR, 1, GPIO_AF2_TIM3, NULL, 0, 0 }, // S9_OUT + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 1, 0 ), // S10_OUT 1 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0 ), // S6_OUT 2 + DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 1, 0 ), // S5_OUT 3 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 0 ), // S1_OUT 4 + DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0 ), // S2_OUT + DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 1, 0 ), // S3_OUT + DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 1, 0 ), // S4_OUT + DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0 ), // S7_OUT + DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 1, 0 ), // S8_OUT + DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 1, 0 ), // S9_OUT }; #endif - // ALTERNATE LAYOUT //const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { -// { TIM12, IO_TAG(PB14), TIM_CHANNEL_1, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S1_IN -// { TIM12, IO_TAG(PB15), TIM_CHANNEL_2, TIM8_BRK_TIM12_IRQn, 0, IOCFG_AF_PP , GPIO_AF9_TIM12}, // S2_IN -// { TIM8, IO_TAG(PC6), TIM_CHANNEL_1, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S3_IN -// { TIM8, IO_TAG(PC7), TIM_CHANNEL_2, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S4_IN -// { TIM8, IO_TAG(PC9), TIM_CHANNEL_4, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S5_IN -// { TIM8, IO_TAG(PC8), TIM_CHANNEL_3, TIM8_CC_IRQn, 0, IOCFG_AF_PP , GPIO_AF3_TIM8}, // S6_IN +// DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // S1_IN +// DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S2_IN +// DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0 ), // S3_IN +// DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0 ), // S4_IN +// DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN +// DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S6_IN // -// { TIM10, IO_TAG(PB8), TIM_CHANNEL_1, TIM1_UP_TIM10_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM10}, // S10_OUT -// { TIM9, IO_TAG(PA2), TIM_CHANNEL_1, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9}, // S6_OUT -// { TIM2, IO_TAG(PA3), TIM_CHANNEL_4, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S1_OUT -// { TIM11, IO_TAG(PB9), TIM_CHANNEL_1, TIM1_TRG_COM_TIM11_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM11}, // S5_OUT -// { TIM5, IO_TAG(PA1), TIM_CHANNEL_2, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S2_OUT -// { TIM9, IO_TAG(PE6), TIM_CHANNEL_2, TIM1_BRK_TIM9_IRQn, 1, IOCFG_AF_PP , GPIO_AF3_TIM9}, // S3_OUT -// { TIM3, IO_TAG(PB5), TIM_CHANNEL_2, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S4_OUT -// { TIM5, IO_TAG(PA0), TIM_CHANNEL_1, TIM5_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM5}, // S7_OUT -// { TIM2, IO_TAG(PB3), TIM_CHANNEL_2, TIM2_IRQn, 1, IOCFG_AF_PP , GPIO_AF1_TIM2}, // S8_OUT -// { TIM3, IO_TAG(PB4), TIM_CHANNEL_1, TIM3_IRQn, 1, IOCFG_AF_PP , GPIO_AF2_TIM3}, // S9_OUT +// DEF_TIM(TIM10, CH1, PB8, TIM_USE_MOTOR, 1, 0 ), // S10_OUT 1 +// DEF_TIM(TIM9, CH1, PA2, TIM_USE_MOTOR, 1, 0 ), // S6_OUT 2 +// DEF_TIM(TIM11, CH1, PB9, TIM_USE_MOTOR, 1, 0 ), // S5_OUT 3 +// DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 0 ), // S1_OUT 4 +// DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0 ), // S2_OUT +// DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 1, 0 ), // S3_OUT +// DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 1, 0 ), // S4_OUT +// DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0 ), // S7_OUT +// DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 1, 0 ), // S8_OUT +// DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 1, 0 ), // S9_OUT //}; diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index bfd47caef8..0330f92095 100755 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -44,7 +44,6 @@ #define MPU_INT_EXTI PC13 #define USE_EXTI -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM16_DMA #define REMAP_TIM17_DMA diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index 5ab4925f4e..750ebf7ab5 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -144,7 +144,6 @@ #define USE_ADC #define VBAT_ADC_PIN PC3 -#define USE_DSHOT #define USE_ESC_SENSOR #define LED_STRIP diff --git a/src/main/target/CC3D/target.h b/src/main/target/CC3D/target.h index e57b5cbfa8..9ac157feca 100644 --- a/src/main/target/CC3D/target.h +++ b/src/main/target/CC3D/target.h @@ -107,7 +107,6 @@ //#define SONAR_TRIGGER_PIN PB5 #undef GPS -#define CLI_MINIMAL_VERBOSITY #undef MAG #ifdef CC3D_OPBL diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index 1f10fcb0f4..9d324d058b 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -125,7 +125,6 @@ #define ENSURE_MPU_DATA_READY_IS_LOW #define LED_STRIP -#define USE_DSHOT #define USE_ESC_SENSOR #define DEFAULT_RX_FEATURE FEATURE_RX_PPM diff --git a/src/main/target/FURYF3/target.h b/src/main/target/FURYF3/target.h index 5497f9021f..5be6abb6b3 100644 --- a/src/main/target/FURYF3/target.h +++ b/src/main/target/FURYF3/target.h @@ -161,7 +161,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM17_DMA diff --git a/src/main/target/FURYF4/target.h b/src/main/target/FURYF4/target.h index 4d35a98fbd..eb83dec47d 100644 --- a/src/main/target/FURYF4/target.h +++ b/src/main/target/FURYF4/target.h @@ -175,7 +175,6 @@ #define USE_SERIAL_4WAY_BLHELI_INTERFACE -#define USE_DSHOT #define USE_ESC_SENSOR #define TARGET_IO_PORTA 0xffff diff --git a/src/main/target/FishDroneF4/target.c b/src/main/target/FishDroneF4/target.c new file mode 100644 index 0000000000..299ecdc2eb --- /dev/null +++ b/src/main/target/FishDroneF4/target.c @@ -0,0 +1,36 @@ +/* + * 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 "drivers/io.h" + +#include "drivers/dma.h" +#include "drivers/timer.h" +#include "drivers/timer_def.h" + +const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { + DEF_TIM(TIM3, CH3, PB0, TIM_USE_PPM, TIMER_INPUT_ENABLED, 0 ), // PPM IN + + DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S1_OUT - DMA1_ST7 + DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S2_OUT - DMA1_ST1 + DEF_TIM(TIM2, CH1, PA15,TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 0 ), // S3_OUT - DMA1_ST5 + DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, TIMER_OUTPUT_ENABLED, 1 ), // S4_OUT - DMA1_ST6 + + DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, TIMER_OUTPUT_ENABLED, 0 ), // LED_STRIP - DMA1_ST2 +}; diff --git a/src/main/target/FishDroneF4/target.h b/src/main/target/FishDroneF4/target.h new file mode 100644 index 0000000000..4d8c5f3a41 --- /dev/null +++ b/src/main/target/FishDroneF4/target.h @@ -0,0 +1,148 @@ +/* + * 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 "FDF4" +#define CONFIG_START_FLASH_ADDRESS (0x08080000) //0x08080000 to 0x080A0000 (FLASH_Sector_8) + +#define USBD_PRODUCT_STRING "FishDroneF4" + +#define LED0 PC13 +#define LED1 PC14 + +#define BEEPER PC15 +#define BEEPER_INVERTED + +#define INVERTER PC8 +#define INVERTER_USART USART6 + +#define USE_EXTI +#define MPU_INT_EXTI PC4 +#define USE_MPU_DATA_READY_SIGNAL + +// *************** Gyro & ACC ********************** +#define USE_SPI +#define USE_SPI_DEVICE_1 + +#define MPU6500_CS_PIN PA4 +#define MPU6500_SPI_INSTANCE SPI1 + +#define GYRO +#define USE_GYRO_SPI_MPU6500 +#define GYRO_MPU6500_ALIGN CW90_DEG + +#define ACC +#define USE_ACC_SPI_MPU6500 +#define ACC_MPU6500_ALIGN CW90_DEG + +// *************** UART ***************************** +#define USE_VCP +#define VBUS_SENSING_PIN PA8 +#define VBUS_SENSING_ENABLED + +#define USE_UART1 +#define UART1_RX_PIN PA10 +#define UART1_TX_PIN PA9 + +#define USE_UART3 +#define UART3_RX_PIN PB11 +#define UART3_TX_PIN PB10 + +#define USE_UART6 +#define UART6_RX_PIN PC7 +#define UART6_TX_PIN PC6 + +#define SERIAL_PORT_COUNT 4 // VCP, USART1, USART3, USART6 + +// *************** OSD ***************************** +#define USE_SPI_DEVICE_2 +#define SPI2_NSS_PIN PB12 +#define SPI2_SCK_PIN PB13 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 + +#define OSD +#define USE_MAX7456 +#define MAX7456_SPI_INSTANCE SPI2 +#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN + +// *************** FLASH ***************************** +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PC10 +#define SPI3_MISO_PIN PC11 +#define SPI3_MOSI_PIN PC12 + +#define USE_FLASH_M25P16 +#define USE_FLASHFS +#define M25P16_CS_PIN PD2 +#define M25P16_SPI_INSTANCE SPI3 + +// *************** SDCARD ***************************** +#define USE_SDCARD + +#define SDCARD_DETECT_INVERTED + +#define SDCARD_DETECT_PIN PB7 +#define SDCARD_SPI_INSTANCE SPI3 +#define SDCARD_SPI_CS_PIN PB9 + +// SPI3 is on the APB1 bus whose clock runs at 84MHz. Divide to under 400kHz for init: +#define SDCARD_SPI_INITIALIZATION_CLOCK_DIVIDER 256 // 328kHz +// Divide to under 25MHz for normal operation: +#define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 4 // 21MHz + +#define SDCARD_DMA_CHANNEL_TX DMA1_Stream5 +#define SDCARD_DMA_CHANNEL_TX_COMPLETE_FLAG DMA_FLAG_TCIF5 +#define SDCARD_DMA_CLK RCC_AHB1Periph_DMA1 +#define SDCARD_DMA_CHANNEL DMA_Channel_0 + +// *************** RTC6705 ************************* +#define USE_RTC6705 +#define RTC6705_SPILE_PIN PB3 +#define RTC6705_SPICLK_PIN PB4 +#define RTC6705_SPIDATA_PIN PB5 + +// *************** ADC ***************************** +#define USE_ADC +#define VBAT_ADC_PIN PC0 +#define RSSI_ADC_PIN PC1 + +// *************** FEATURES ************************ +#define DEFAULT_FEATURES (FEATURE_VBAT | FEATURE_OSD | FEATURE_BLACKBOX | FEATURE_VTX) +#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL +#define SERIALRX_PROVIDER SERIALRX_SBUS +#define SERIALRX_UART SERIAL_PORT_USART3 + +// *************** Others ************************** +#define DISPLAY +#define LED_STRIP +#define OSD + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define USE_SERIAL_4WAY_BLHELI_INTERFACE + +#define USE_ESC_TELEMETRY + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB 0xffff +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (BIT(2)) + +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) ) diff --git a/src/main/target/FishDroneF4/target.mk b/src/main/target/FishDroneF4/target.mk new file mode 100644 index 0000000000..0fd79b1f82 --- /dev/null +++ b/src/main/target/FishDroneF4/target.mk @@ -0,0 +1,8 @@ +F405_TARGETS += $(TARGET) +FEATURES += SDCARD VCP ONBOARDFLASH + +TARGET_SRC = \ + drivers/accgyro_spi_mpu6500.c \ + drivers/accgyro_mpu6500.c \ + drivers/max7456.c \ + drivers/vtx_soft_spi_rtc6705.c \ No newline at end of file diff --git a/src/main/target/IMPULSERCF3/target.h b/src/main/target/IMPULSERCF3/target.h index 79382b81c3..f6649fa5e5 100644 --- a/src/main/target/IMPULSERCF3/target.h +++ b/src/main/target/IMPULSERCF3/target.h @@ -46,7 +46,6 @@ #define USE_FLASHFS #define USE_FLASH_M25P16 -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM17_DMA diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index b7a523d9c2..1064e34e28 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -23,7 +23,6 @@ #define SBUS_PORT_OPTIONS (SERIAL_STOPBITS_2 | SERIAL_PARITY_EVEN | SERIAL_INVERTED | SERIAL_BIDIR) -#define USE_DSHOT #define USE_ESC_SENSOR #define USE_ESCSERIAL diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index a6ca94cd77..52b772e268 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -46,7 +46,6 @@ #define USE_MPU_DATA_READY_SIGNAL #define ENSURE_MPU_DATA_READY_IS_LOW -#define USE_DSHOT #define USE_ESC_SENSOR #define USE_SPI diff --git a/src/main/target/MOTOLAB/config.c b/src/main/target/MOTOLAB/config.c index 94a217a364..daee3f7f34 100755 --- a/src/main/target/MOTOLAB/config.c +++ b/src/main/target/MOTOLAB/config.c @@ -27,5 +27,5 @@ void targetConfiguration(master_t *config) { config->gyroConfig.gyro_sync_denom = 4; - config->pid_process_denom = 1; + config->pidConfig.pid_process_denom = 1; } diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 52a6bebefe..b413253f46 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -95,7 +95,6 @@ #define RSSI_ADC_PIN PB2 #define LED_STRIP -#define USE_DSHOT #define USE_ESC_SENSOR #define SPEKTRUM_BIND diff --git a/src/main/target/MULTIFLITEPICO/config.c b/src/main/target/MULTIFLITEPICO/config.c index dfbe0a8fea..54a609b484 100755 --- a/src/main/target/MULTIFLITEPICO/config.c +++ b/src/main/target/MULTIFLITEPICO/config.c @@ -72,7 +72,7 @@ void targetConfiguration(master_t *config) config->motorConfig.motorPwmRate = 17000; config->gyroConfig.gyro_sync_denom = 4; - config->pid_process_denom = 1; + config->pidConfig.pid_process_denom = 1; config->profile[0].pidProfile.P8[ROLL] = 70; config->profile[0].pidProfile.I8[ROLL] = 62; diff --git a/src/main/target/MULTIFLITEPICO/target.h b/src/main/target/MULTIFLITEPICO/target.h index 7e5a0f0453..6ebc86e4e7 100755 --- a/src/main/target/MULTIFLITEPICO/target.h +++ b/src/main/target/MULTIFLITEPICO/target.h @@ -105,7 +105,6 @@ #define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PB2 -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM17_DMA diff --git a/src/main/target/NAZE/target.h b/src/main/target/NAZE/target.h index 2272a55520..56ff4d9f51 100644 --- a/src/main/target/NAZE/target.h +++ b/src/main/target/NAZE/target.h @@ -21,8 +21,6 @@ #define USE_HARDWARE_REVISION_DETECTION #define TARGET_BUS_INIT -#define CLI_MINIMAL_VERBOSITY - #define BOARD_HAS_VOLTAGE_DIVIDER #define LED0 PB3 diff --git a/src/main/target/NERO7/NERO7.md b/src/main/target/NERO7/NERO7.md new file mode 100644 index 0000000000..fef9761fb3 --- /dev/null +++ b/src/main/target/NERO7/NERO7.md @@ -0,0 +1,5 @@ +# NERO7 + +Placeholder for NERO7 (an STM32F722RE target) - in both 30.5x30.5 and 20x20 (mini) formats. + +Samples are being made now, with production run expected once STM32 release the 722RE in production quantities. \ No newline at end of file diff --git a/src/main/target/OMNIBUS/target.c b/src/main/target/OMNIBUS/target.c index 58be31b640..b542523faf 100644 --- a/src/main/target/OMNIBUS/target.c +++ b/src/main/target/OMNIBUS/target.c @@ -38,5 +38,5 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { //{ TIM2, IO_TAG(PB11), TIM_Channel_4, TIM_USE_MOTOR, 1, GPIO_AF_1, NULL, 0 }, // PWM6 - PB11 - TIM2_CH4 / UART3_RX (AF7) { TIM4, IO_TAG(PB7), TIM_Channel_2, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM7 - PB7 { TIM4, IO_TAG(PB6), TIM_Channel_1, TIM_USE_MOTOR, 1, GPIO_AF_2, NULL, 0 }, // PWM8 - PB6 - { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP + { TIM1, IO_TAG(PA8), TIM_Channel_1, TIM_USE_LED|TIM_USE_TRANSPONDER, 1, GPIO_AF_6, DMA1_Channel2, DMA1_CH2_HANDLER }, // GPIO_TIMER / LED_STRIP }; diff --git a/src/main/target/OMNIBUS/target.h b/src/main/target/OMNIBUS/target.h index 238579fd8b..a4f5d57560 100644 --- a/src/main/target/OMNIBUS/target.h +++ b/src/main/target/OMNIBUS/target.h @@ -133,7 +133,6 @@ // Divide to under 25MHz for normal operation: #define SDCARD_SPI_FULL_SPEED_CLOCK_DIVIDER 2 -#define USE_DSHOT #define USE_ESC_SENSOR // DSHOT output 4 uses DMA1_Channel5, so don't use it for the SDCARD until we find an alternative @@ -157,18 +156,6 @@ #define LED_STRIP #define TRANSPONDER -#define TRANSPONDER_GPIO GPIOA -#define TRANSPONDER_GPIO_AHB_PERIPHERAL RCC_AHBPeriph_GPIOA -#define TRANSPONDER_GPIO_AF GPIO_AF_6 -#define TRANSPONDER_PIN GPIO_Pin_8 -#define TRANSPONDER_PIN_SOURCE GPIO_PinSource8 -#define TRANSPONDER_TIMER TIM1 -#define TRANSPONDER_TIMER_APB2_PERIPHERAL RCC_APB2Periph_TIM1 -#define TRANSPONDER_DMA_CHANNEL DMA1_Channel2 -#define TRANSPONDER_IRQ DMA1_Channel2_IRQn -#define TRANSPONDER_DMA_TC_FLAG DMA1_FLAG_TC2 -#define TRANSPONDER_DMA_HANDLER_IDENTIFER DMA1_CH2_HANDLER - #define REDUCE_TRANSPONDER_CURRENT_DRAW_WHEN_USB_CABLE_PRESENT #define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT diff --git a/src/main/target/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index abc338b68c..84094838bc 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -160,7 +160,6 @@ #define VBAT_ADC_PIN PC2 //#define RSSI_ADC_PIN PA0 -#define USE_DSHOT #define USE_ESC_SENSOR #define LED_STRIP diff --git a/src/main/target/REVO/target.c b/src/main/target/REVO/target.c index 310ee9807f..36d9708128 100644 --- a/src/main/target/REVO/target.c +++ b/src/main/target/REVO/target.c @@ -43,6 +43,10 @@ const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 1, 1), // S3_OUT D1_ST6 DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 1, 0), // S4_OUT D1_ST1 DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR | TIM_USE_LED, 1, 0), // S5_OUT / LED for REVO D1_ST4 +#ifdef AIRBOTF4 + DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 1, 0), // S6_OUT +#else DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 1, 0), // S6_OUT D1_ST2 #endif +#endif }; diff --git a/src/main/target/REVO/target.h b/src/main/target/REVO/target.h index 82d0217de1..fae6ef0b7c 100644 --- a/src/main/target/REVO/target.h +++ b/src/main/target/REVO/target.h @@ -41,7 +41,6 @@ #endif -#define USE_DSHOT #define USE_ESC_SENSOR #define LED0 PB5 diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h index f404c6ac43..1dc7083849 100644 --- a/src/main/target/SPARKY2/target.h +++ b/src/main/target/SPARKY2/target.h @@ -35,7 +35,6 @@ #define INVERTER PC6 #define INVERTER_USART USART6 -#define USE_DSHOT #define USE_ESC_SENSOR // MPU9250 interrupt diff --git a/src/main/target/SPRACINGF3/target.h b/src/main/target/SPRACINGF3/target.h index e1b9bd4199..dbe2ae9c61 100644 --- a/src/main/target/SPRACINGF3/target.h +++ b/src/main/target/SPRACINGF3/target.h @@ -116,7 +116,6 @@ #define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PB2 -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM17_DMA diff --git a/src/main/target/SPRACINGF3EVO/target.h b/src/main/target/SPRACINGF3EVO/target.h index 40f8af637f..7d379d57da 100755 --- a/src/main/target/SPRACINGF3EVO/target.h +++ b/src/main/target/SPRACINGF3EVO/target.h @@ -37,7 +37,6 @@ #define USE_MAG_DATA_READY_SIGNAL #define ENSURE_MAG_DATA_READY_IS_HIGH -#define USE_DSHOT #define USE_ESC_SENSOR #define GYRO diff --git a/src/main/target/STM32F3DISCOVERY/target.h b/src/main/target/STM32F3DISCOVERY/target.h index 1e7670eb3b..28a4dc7518 100644 --- a/src/main/target/STM32F3DISCOVERY/target.h +++ b/src/main/target/STM32F3DISCOVERY/target.h @@ -169,7 +169,6 @@ #define RSSI_ADC_PIN PC2 #define EXTERNAL1_ADC_PIN PC3 -#define USE_DSHOT #define USE_ESC_SENSOR #define LED_STRIP diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 5e5ae8f66e..f62d0ff86a 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -101,7 +101,6 @@ #define CURRENT_METER_ADC_PIN PA5 #define RSSI_ADC_PIN PB2 -#define USE_DSHOT #define USE_ESC_SENSOR #define REMAP_TIM17_DMA diff --git a/src/main/target/common.h b/src/main/target/common.h index 36a7333e96..86d53c9dd1 100644 --- a/src/main/target/common.h +++ b/src/main/target/common.h @@ -45,6 +45,8 @@ // Using RX DMA disables the use of receive callbacks #define USE_UART1_RX_DMA #define USE_UART1_TX_DMA + +#define CLI_MINIMAL_VERBOSITY #endif #define SERIAL_RX diff --git a/src/main/telemetry/crsf.h b/src/main/telemetry/crsf.h index cbdb437f82..1b5fa6b95b 100644 --- a/src/main/telemetry/crsf.h +++ b/src/main/telemetry/crsf.h @@ -1,6 +1,4 @@ /* - * ltm.h - * * This file is part of Cleanflight. * * Cleanflight is free software: you can redistribute it and/or modify