diff --git a/Makefile b/Makefile index 1dde7cc6ef..cfe682b138 100644 --- a/Makefile +++ b/Makefile @@ -16,8 +16,9 @@ # # The target to build, see VALID_TARGETS below -TARGET ?= STM32F405 -BOARD ?= +DEFAULT_TARGET ?= STM32F405 +TARGET ?= +CONFIG ?= # Compile-time options OPTIONS ?= @@ -80,8 +81,9 @@ include $(ROOT)/make/system-id.mk include $(ROOT)/make/checks.mk # configure some directories that are relative to wherever ROOT_DIR is located -TOOLS_DIR ?= $(ROOT)/tools -DL_DIR := $(ROOT)/downloads +TOOLS_DIR ?= $(ROOT)/tools +DL_DIR := $(ROOT)/downloads +CONFIG_DIR ?= $(ROOT)/src/config export RM := rm @@ -97,13 +99,35 @@ HSE_VALUE ?= 8000000 # used for turning on features like VCP and SDCARD FEATURES = -ifneq ($(BOARD),) -# silently ignore if the file is not present. Allows for target defaults. --include $(ROOT)/src/main/board/$(BOARD)/board.mk +ifneq ($(CONFIG),) + +ifneq ($(TARGET),) +$(error TARGET or CONFIG should be specified. Not both.) endif +INCLUDE_DIRS += $(CONFIG_DIR)/$(CONFIG) +CONFIG_FILE := $(CONFIG_DIR)/$(CONFIG)/config.h + +ifeq ($(wildcard $(CONFIG_FILE)),) +$(error Config file not found: $(CONFIG_FILE)) +endif + +TARGET := $(shell grep " FC_TARGET_MCU" $(CONFIG_FILE) | awk '{print $$3}' ) + +ifeq ($(TARGET),) +$(error No TARGET identified. Is the config.h valid for $(CONFIG)?) +endif + +else +ifeq ($(TARGET),) +TARGET := $(DEFAULT_TARGET) +endif +endif #CONFIG + include $(ROOT)/make/targets.mk +BASE_CONFIGS = $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/config/*/config.h))))) + REVISION := norevision ifeq ($(shell git diff --shortstat),) REVISION := $(shell git log -1 --format="%h") @@ -151,6 +175,10 @@ VPATH := $(VPATH):$(ROOT)/make # start specific includes include $(ROOT)/make/mcu/$(TARGET_MCU).mk +ifneq ($(CONFIG),) +TARGET_FLAGS += -DUSE_CONFIG +endif + # openocd specific includes include $(ROOT)/make/openocd.mk @@ -283,28 +311,38 @@ CPPCHECK = cppcheck $(CSOURCES) --enable=all --platform=unix64 \ $(addprefix -I,$(INCLUDE_DIRS)) \ -I/usr/include -I/usr/include/linux -TARGET_BASENAME = $(BIN_DIR)/$(FORKNAME)_$(FC_VER)_$(TARGET) +TARGET_NAME := $(TARGET) + +ifneq ($(CONFIG),) +TARGET_NAME := $(TARGET_NAME)_$(CONFIG) +endif + +ifeq ($(REV),yes) +TARGET_NAME := $(TARGET_NAME)_$(REVISION) +endif + +TARGET_FULLNAME = $(FORKNAME)_$(FC_VER)_$(TARGET_NAME) # # Things we will build # -TARGET_BIN = $(TARGET_BASENAME).bin -TARGET_HEX = $(TARGET_BASENAME).hex -TARGET_HEX_REV = $(TARGET_BASENAME)_$(REVISION).hex -TARGET_DFU = $(TARGET_BASENAME).dfu -TARGET_ZIP = $(TARGET_BASENAME).zip -TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).elf -TARGET_EXST_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_EXST.elf -TARGET_UNPATCHED_BIN = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET)_UNPATCHED.bin -TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).lst -TARGET_OBJS = $(addsuffix .o,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC)))) -TARGET_DEPS = $(addsuffix .d,$(addprefix $(OBJECT_DIR)/$(TARGET)/,$(basename $(SRC)))) -TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET).map +TARGET_BIN = $(BIN_DIR)/$(TARGET_FULLNAME).bin +TARGET_HEX = $(BIN_DIR)/$(TARGET_FULLNAME).hex +TARGET_DFU = $(BIN_DIR)/$(TARGET_FULLNAME).dfu +TARGET_ZIP = $(BIN_DIR)/$(TARGET_FULLNAME).zip +TARGET_OBJ_DIR = $(OBJECT_DIR)/$(TARGET_NAME) +TARGET_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).elf +TARGET_EXST_ELF = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_EXST.elf +TARGET_UNPATCHED_BIN = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME)_UNPATCHED.bin +TARGET_LST = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).lst +TARGET_OBJS = $(addsuffix .o,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_DEPS = $(addsuffix .d,$(addprefix $(TARGET_OBJ_DIR)/,$(basename $(SRC)))) +TARGET_MAP = $(OBJECT_DIR)/$(FORKNAME)_$(TARGET_NAME).map -TARGET_EXST_HASH_SECTION_FILE = $(OBJECT_DIR)/$(TARGET)/exst_hash_section.bin +TARGET_EXST_HASH_SECTION_FILE = $(TARGET_OBJ_DIR)/exst_hash_section.bin TARGET_EF_HASH := $(shell echo -n "$(EXTRA_FLAGS)" | openssl dgst -md5 | awk '{print $$2;}') -TARGET_EF_HASH_FILE := $(OBJECT_DIR)/$(TARGET)/.efhash_$(TARGET_EF_HASH) +TARGET_EF_HASH_FILE := $(TARGET_OBJ_DIR)/.efhash_$(TARGET_EF_HASH) CLEAN_ARTIFACTS := $(TARGET_BIN) CLEAN_ARTIFACTS += $(TARGET_HEX_REV) $(TARGET_HEX) @@ -313,7 +351,7 @@ CLEAN_ARTIFACTS += $(TARGET_LST) CLEAN_ARTIFACTS += $(TARGET_DFU) # Make sure build date and revision is updated on every incremental build -$(OBJECT_DIR)/$(TARGET)/build/version.o : $(SRC) +$(TARGET_OBJ_DIR)/build/version.o : $(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. @@ -367,11 +405,8 @@ $(TARGET_BIN): $(TARGET_UNPATCHED_BIN) @echo "Patching MD5 hash into HASH section" "$(STDOUT)" $(V1) cat $(TARGET_UNPATCHED_BIN).md5 | awk '{printf("%08x: %s",64-16,$$2);}' | xxd -r - $(TARGET_EXST_HASH_SECTION_FILE) -# For some currently unknown reason, OBJCOPY, with only input/output files, will generate a file around 2GB for the H730 unless we remove an unused-section -# As a workaround drop the ._user_heap_stack section, which is only used during build to show errors if there's not enough space for the heap/stack. -# The issue can be seen with `readelf -S $(TARGET_EXST_ELF)' vs `readelf -S $(TARGET_ELF)` $(V1) @echo "Patching updated HASH section into $(TARGET_EXST_ELF)" "$(STDOUT)" - $(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --remove-section ._user_heap_stack --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE) + $(OBJCOPY) $(TARGET_ELF) $(TARGET_EXST_ELF) --update-section .exst_hash=$(TARGET_EXST_HASH_SECTION_FILE) $(V1) $(READELF) -S $(TARGET_EXST_ELF) $(V1) $(READELF) -l $(TARGET_EXST_ELF) @@ -385,7 +420,7 @@ $(TARGET_HEX): $(TARGET_BIN) endif $(TARGET_ELF): $(TARGET_OBJS) $(LD_SCRIPT) $(LD_SCRIPTS) - @echo "Linking $(TARGET)" "$(STDOUT)" + @echo "Linking $(TARGET_NAME)" "$(STDOUT)" $(V1) $(CROSS_CC) -o $@ $(filter-out %.ld,$^) $(LD_FLAGS) $(V1) $(SIZE) $(TARGET_ELF) @@ -398,7 +433,7 @@ define compile_file endef ifeq ($(DEBUG),GDB) -$(OBJECT_DIR)/$(TARGET)/%.o: %.c +$(TARGET_OBJ_DIR)/%.o: %.c $(V1) mkdir -p $(dir $@) $(V1) $(if $(findstring $<,$(NOT_OPTIMISED_SRC)), \ $(call compile_file,not optimised, $(CC_NO_OPTIMISATION)) \ @@ -406,7 +441,7 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.c $(call compile_file,debug,$(CC_DEBUG_OPTIMISATION)) \ ) else -$(OBJECT_DIR)/$(TARGET)/%.o: %.c +$(TARGET_OBJ_DIR)/%.o: %.c $(V1) mkdir -p $(dir $@) $(V1) $(if $(findstring $<,$(NOT_OPTIMISED_SRC)), \ $(call compile_file,not optimised,$(CC_NO_OPTIMISATION)) \ @@ -424,12 +459,12 @@ $(OBJECT_DIR)/$(TARGET)/%.o: %.c endif # Assemble -$(OBJECT_DIR)/$(TARGET)/%.o: %.s +$(TARGET_OBJ_DIR)/%.o: %.s $(V1) mkdir -p $(dir $@) @echo "%% $(notdir $<)" "$(STDOUT)" $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< -$(OBJECT_DIR)/$(TARGET)/%.o: %.S +$(TARGET_OBJ_DIR)/%.o: %.S $(V1) mkdir -p $(dir $@) @echo "%% $(notdir $<)" "$(STDOUT)" $(V1) $(CROSS_CC) -c -o $@ $(ASFLAGS) $< @@ -441,22 +476,28 @@ all: $(CI_TARGETS) ## all_all : Build all targets (including legacy / unsupported) all_all: $(VALID_TARGETS) -$(VALID_TARGETS): +$(BASE_TARGETS): $(V0) @echo "Building $@" && \ $(MAKE) hex TARGET=$@ && \ echo "Building $@ succeeded." +$(BASE_CONFIGS): + $(V0) @echo "Building config $@" && \ + $(MAKE) hex CONFIG=$@ && \ + echo "Building config $@ succeeded." + $(NOBUILD_TARGETS): $(MAKE) TARGET=$@ TARGETS_CLEAN = $(addsuffix _clean,$(VALID_TARGETS)) +CONFIGS_CLEAN = $(addsuffix _clean,$(BASE_CONFIGS)) ## clean : clean up temporary / machine-generated files clean: - @echo "Cleaning $(TARGET)" + @echo "Cleaning $(TARGET_NAME)" $(V0) rm -f $(CLEAN_ARTIFACTS) - $(V0) rm -rf $(OBJECT_DIR)/$(TARGET) - @echo "Cleaning $(TARGET) succeeded." + $(V0) rm -rf $(TARGET_OBJ_DIR) + @echo "Cleaning $(TARGET_NAME) succeeded." ## test_clean : clean up temporary / machine-generated files (tests) test-%_clean: @@ -469,6 +510,10 @@ test_clean: $(TARGETS_CLEAN): $(V0) $(MAKE) -j TARGET=$(subst _clean,,$@) clean +## _clean : clean up one specific config (alias for above) +$(CONFIGS_CLEAN): + $(V0) $(MAKE) -j CONFIG=$(subst _clean,,$@) clean + ## clean_all : clean all valid targets clean_all: $(TARGETS_CLEAN) test_clean @@ -529,10 +574,7 @@ hex: TARGETS_REVISION = $(addsuffix _rev,$(VALID_TARGETS)) ## _rev : build target and add revision to filename $(TARGETS_REVISION): - $(V0) $(MAKE) hex_rev TARGET=$(subst _rev,,$@) - -hex_rev: hex - $(V0) mv -f $(TARGET_HEX) $(TARGET_HEX_REV) + $(V0) $(MAKE) hex REV=yes TARGET=$(subst _rev,,$@) all_rev: $(addsuffix _rev,$(CI_TARGETS)) @@ -581,6 +623,9 @@ targets: @echo "Built targets: $(CI_TARGETS)" @echo "Default target: $(TARGET)" +configs: + @echo "Valid configs: $(BASE_CONFIGS)" + targets-ci-print: @echo $(CI_TARGETS) @@ -648,12 +693,12 @@ test_%: $(TARGET_EF_HASH_FILE): $(V1) mkdir -p $(dir $@) - $(V0) rm -f $(OBJECT_DIR)/$(TARGET)/.efhash_* + $(V0) rm -f $(TARGET_OBJ_DIR)/.efhash_* @echo "EF HASH -> $(TARGET_EF_HASH_FILE)" $(V1) touch $(TARGET_EF_HASH_FILE) # rebuild everything when makefile changes or the extra flags have changed -$(TARGET_OBJS): $(TARGET_EF_HASH_FILE) Makefile $(TARGET_DIR)/target.mk $(wildcard make/*) +$(TARGET_OBJS): $(TARGET_EF_HASH_FILE) Makefile $(TARGET_DIR)/target.mk $(wildcard make/*) $(CONFIG_FILE) # include auto-generated dependencies -include $(TARGET_DEPS) diff --git a/make/mcu/STM32H7.mk b/make/mcu/STM32H7.mk index 5649818ecb..69f5fd2cc1 100644 --- a/make/mcu/STM32H7.mk +++ b/make/mcu/STM32H7.mk @@ -207,9 +207,22 @@ else ifeq ($(TARGET),$(filter $(TARGET),$(H723xG_TARGETS))) DEVICE_FLAGS += -DSTM32H723xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld STARTUP_SRC = startup_stm32h723xx.s -MCU_FLASH_SIZE := 1024 +DEFAULT_TARGET_FLASH := 1024 DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 +ifeq ($(TARGET_FLASH),) +MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH) +endif + +ifeq ($(EXST),yes) +FIRMWARE_SIZE := 1024 +# TARGET_FLASH now becomes the amount of MEMORY-MAPPED address space that is occupied by the firmware +# and the maximum size of the data stored on the external flash device. +MCU_FLASH_SIZE := FIRMWARE_SIZE +DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_ram_h723_exst.ld +LD_SCRIPTS = $(LINKER_DIR)/stm32_h723_common.ld $(LINKER_DIR)/stm32_h723_common_post.ld +endif + else ifeq ($(TARGET),$(filter $(TARGET),$(H725xG_TARGETS))) DEVICE_FLAGS += -DSTM32H725xx DEFAULT_LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h723_1m.ld @@ -226,7 +239,7 @@ DEVICE_FLAGS += -DMAX_MPU_REGIONS=16 ifeq ($(TARGET_FLASH),) -MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH) +MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH) endif ifeq ($(EXST),yes) @@ -246,7 +259,7 @@ STARTUP_SRC = startup_stm32h743xx.s DEFAULT_TARGET_FLASH := 128 ifeq ($(TARGET_FLASH),) -MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH) +MCU_FLASH_SIZE := $(DEFAULT_TARGET_FLASH) endif ifeq ($(EXST),yes) @@ -281,7 +294,7 @@ LD_SCRIPT = $(DEFAULT_LD_SCRIPT) endif ifneq ($(FIRMWARE_SIZE),) -DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE) +DEVICE_FLAGS += -DFIRMWARE_SIZE=$(FIRMWARE_SIZE) endif DEVICE_FLAGS += -DHSE_VALUE=$(HSE_VALUE) -DHSE_STARTUP_TIMEOUT=1000 @@ -304,6 +317,7 @@ MCU_COMMON_SRC = \ drivers/serial_uart_hal.c \ drivers/serial_uart_stm32h7xx.c \ drivers/bus_quadspi_hal.c \ + drivers/bus_octospi_stm32h7xx.c \ drivers/bus_spi_ll.c \ drivers/dma_stm32h7xx.c \ drivers/dshot_bitbang.c \ diff --git a/make/source.mk b/make/source.mk index 1590e1b486..e2c897cb25 100644 --- a/make/source.mk +++ b/make/source.mk @@ -20,6 +20,7 @@ COMMON_SRC = \ drivers/bus_i2c_config.c \ drivers/bus_i2c_busdev.c \ drivers/bus_i2c_soft.c \ + drivers/bus_octospi.c \ drivers/bus_quadspi.c \ drivers/bus_spi.c \ drivers/bus_spi_config.c \ @@ -450,12 +451,6 @@ SRC += $(MSC_SRC) endif # end target specific make file checks -ifneq ($(BOARD),) -SRC += board/$(BOARD)/board.c -INCLUDE_DIRS += $(ROOT)/src/main/board/$(BOARD) -TARGET_FLAGS := -D'__BOARD__="$(BOARD)"' $(TARGET_FLAGS) -endif - # Search path and source files for the ST stdperiph library VPATH := $(VPATH):$(STDPERIPH_DIR)/src diff --git a/src/config/AG3XF4/config.h b/src/config/AG3XF4/config.h new file mode 100644 index 0000000000..5c3bb8f834 --- /dev/null +++ b/src/config/AG3XF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AG3XF4 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/AG3XF7/config.h b/src/config/AG3XF7/config.h new file mode 100644 index 0000000000..af7fe94a40 --- /dev/null +++ b/src/config/AG3XF7/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AG3XF7 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/AIKONF4/config.h b/src/config/AIKONF4/config.h new file mode 100644 index 0000000000..ad005bad89 --- /dev/null +++ b/src/config/AIKONF4/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AIKONF4 +#define MANUFACTURER_ID AIKO + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_ICM20602 +#define USE_GYRO_SPI_ICM20602 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/AIKONF7/config.h b/src/config/AIKONF7/config.h new file mode 100644 index 0000000000..a486b99ba7 --- /dev/null +++ b/src/config/AIKONF7/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AIKONF7 +#define MANUFACTURER_ID AIKO + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_BARO_SPI_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/AIRBOTF4/config.h b/src/config/AIRBOTF4/config.h new file mode 100644 index 0000000000..c3aed07c25 --- /dev/null +++ b/src/config/AIRBOTF4/config.h @@ -0,0 +1,48 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AIRBOTF4 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_BARO_BMP280 +#define USE_BARO_BMP280 +#define USE_BARO_BMP085 +#define USE_BARO_MS5611 + diff --git a/src/config/AIRBOTF4SD/config.h b/src/config/AIRBOTF4SD/config.h new file mode 100644 index 0000000000..74f8525ce0 --- /dev/null +++ b/src/config/AIRBOTF4SD/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AIRBOTF4SD +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_BARO_BMP280 +#define USE_BARO_BMP085 +#define USE_BARO_MS5611 +#define USE_BARO_SPI_BMP280 + diff --git a/src/config/AIRBOTF4V2/config.h b/src/config/AIRBOTF4V2/config.h new file mode 100644 index 0000000000..db0a5c3141 --- /dev/null +++ b/src/config/AIRBOTF4V2/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AIRBOTF4V2 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/AIRBOTF7/config.h b/src/config/AIRBOTF7/config.h new file mode 100644 index 0000000000..29d57249cc --- /dev/null +++ b/src/config/AIRBOTF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AIRBOTF7 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/AIRBOTF7HDV/config.h b/src/config/AIRBOTF7HDV/config.h new file mode 100644 index 0000000000..eb91082383 --- /dev/null +++ b/src/config/AIRBOTF7HDV/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AIRBOTF7HDV +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/AIRF7/config.h b/src/config/AIRF7/config.h new file mode 100644 index 0000000000..018adf84bd --- /dev/null +++ b/src/config/AIRF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AIRF7 +#define MANUFACTURER_ID RAST + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/ALIENFLIGHTF4/config.h b/src/config/ALIENFLIGHTF4/config.h new file mode 100644 index 0000000000..bd079f902c --- /dev/null +++ b/src/config/ALIENFLIGHTF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME ALIENFLIGHTF4 +#define MANUFACTURER_ID AFNG + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_MAG_SPI_AK8963 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/ALIENFLIGHTNGF7/config.h b/src/config/ALIENFLIGHTNGF7/config.h new file mode 100644 index 0000000000..823ad3ddf6 --- /dev/null +++ b/src/config/ALIENFLIGHTNGF7/config.h @@ -0,0 +1,49 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ALIENFLIGHTNGF7 +#define MANUFACTURER_ID AFNG + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20602 +#define USE_ACC_SPI_ICM20602 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAG_MPU925X_AK8963 +#define USE_MAG_SPI_AK8963 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_SDCARD + diff --git a/src/config/ALIENFLIGHTNGF7_DUAL/config.h b/src/config/ALIENFLIGHTNGF7_DUAL/config.h new file mode 100644 index 0000000000..3e4aa4813e --- /dev/null +++ b/src/config/ALIENFLIGHTNGF7_DUAL/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ALIENFLIGHTNGF7_DUAL +#define MANUFACTURER_ID AFNG + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20602 +#define USE_ACC_SPI_ICM20602 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/ALIENFLIGHTNGF7_ELRS/config.h b/src/config/ALIENFLIGHTNGF7_ELRS/config.h new file mode 100644 index 0000000000..cc0f1a5e34 --- /dev/null +++ b/src/config/ALIENFLIGHTNGF7_ELRS/config.h @@ -0,0 +1,57 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ALIENFLIGHTNGF7_ELRS +#define MANUFACTURER_ID AFNG + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20602 +#define USE_ACC_SPI_ICM20602 +#define USE_MAG_SPI_AK8963 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB6 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PB7 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PB15 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PB9 + diff --git a/src/config/ALIENFLIGHTNGF7_RX/config.h b/src/config/ALIENFLIGHTNGF7_RX/config.h new file mode 100644 index 0000000000..00fb8951c2 --- /dev/null +++ b/src/config/ALIENFLIGHTNGF7_RX/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ALIENFLIGHTNGF7_RX +#define MANUFACTURER_ID AFNG + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20602 +#define USE_ACC_SPI_ICM20602 +#define USE_MAG_SPI_AK8963 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_RX_CC2500 + diff --git a/src/config/ALIENWHOOPF4/config.h b/src/config/ALIENWHOOPF4/config.h new file mode 100644 index 0000000000..ca14a613e5 --- /dev/null +++ b/src/config/ALIENWHOOPF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME ALIENWHOOPF4 +#define MANUFACTURER_ID ALWH + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/ANYFCF7/config.h b/src/config/ANYFCF7/config.h new file mode 100644 index 0000000000..af7aea540d --- /dev/null +++ b/src/config/ANYFCF7/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME ANYFCF7 +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/ANYFCM7/config.h b/src/config/ANYFCM7/config.h new file mode 100644 index 0000000000..11476c6c01 --- /dev/null +++ b/src/config/ANYFCM7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ANYFCM7 +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_MAX7456 + diff --git a/src/config/AOCODAF405/config.h b/src/config/AOCODAF405/config.h new file mode 100644 index 0000000000..836e589d94 --- /dev/null +++ b/src/config/AOCODAF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AOCODAF405 +#define MANUFACTURER_ID SJET + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AOCODAF405V2MPU6000/config.h b/src/config/AOCODAF405V2MPU6000/config.h new file mode 100644 index 0000000000..03bcda07a8 --- /dev/null +++ b/src/config/AOCODAF405V2MPU6000/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AOCODAF405V2MPU6000 +#define MANUFACTURER_ID SJET + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AOCODAF405V2MPU6500/config.h b/src/config/AOCODAF405V2MPU6500/config.h new file mode 100644 index 0000000000..cb800ff9ac --- /dev/null +++ b/src/config/AOCODAF405V2MPU6500/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME AOCODAF405V2MPU6500 +#define MANUFACTURER_ID SJET + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AOCODAF722BLE/config.h b/src/config/AOCODAF722BLE/config.h new file mode 100644 index 0000000000..f3ac7a8f31 --- /dev/null +++ b/src/config/AOCODAF722BLE/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AOCODAF722BLE +#define MANUFACTURER_ID SJET + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AOCODAF722MINI/config.h b/src/config/AOCODAF722MINI/config.h new file mode 100644 index 0000000000..e57fcef535 --- /dev/null +++ b/src/config/AOCODAF722MINI/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AOCODAF722MINI +#define MANUFACTURER_ID SJET + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_BMP280 + diff --git a/src/config/AOCODARCF411_AIO/config.h b/src/config/AOCODARCF411_AIO/config.h new file mode 100644 index 0000000000..5387c19efe --- /dev/null +++ b/src/config/AOCODARCF411_AIO/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME AOCODARCF411_AIO +#define MANUFACTURER_ID SJET + +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/AOCODARCF7DUAL/config.h b/src/config/AOCODARCF7DUAL/config.h new file mode 100644 index 0000000000..4cb8e3ac41 --- /dev/null +++ b/src/config/AOCODARCF7DUAL/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AOCODARCF7DUAL +#define MANUFACTURER_ID SJET + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AOCODARCH7DUAL/config.h b/src/config/AOCODARCH7DUAL/config.h new file mode 100644 index 0000000000..c6656147ec --- /dev/null +++ b/src/config/AOCODARCH7DUAL/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME AOCODARCH7DUAL +#define MANUFACTURER_ID SJET + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/APEXF7/config.h b/src/config/APEXF7/config.h new file mode 100644 index 0000000000..40e754267b --- /dev/null +++ b/src/config/APEXF7/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME APEXF7 +#define MANUFACTURER_ID APEX + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/ARESF7/config.h b/src/config/ARESF7/config.h new file mode 100644 index 0000000000..75dbd99071 --- /dev/null +++ b/src/config/ARESF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ARESF7 +#define MANUFACTURER_ID RCTI + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/ATOMRCF405/config.h b/src/config/ATOMRCF405/config.h new file mode 100644 index 0000000000..058b485de8 --- /dev/null +++ b/src/config/ATOMRCF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME ATOMRCF405 +#define MANUFACTURER_ID SKZO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/ATOMRCF411/config.h b/src/config/ATOMRCF411/config.h new file mode 100644 index 0000000000..43ece95d80 --- /dev/null +++ b/src/config/ATOMRCF411/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME ATOMRCF411 +#define MANUFACTURER_ID SKZO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/ATOMRCF722/config.h b/src/config/ATOMRCF722/config.h new file mode 100644 index 0000000000..9029bcd82d --- /dev/null +++ b/src/config/ATOMRCF722/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ATOMRCF722 +#define MANUFACTURER_ID SKZO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AXISFLYINGF7/config.h b/src/config/AXISFLYINGF7/config.h new file mode 100644 index 0000000000..ded488f7bb --- /dev/null +++ b/src/config/AXISFLYINGF7/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AXISFLYINGF7 +#define MANUFACTURER_ID AXFL + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_QMP6988 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/AXISFLYINGF7PRO/config.h b/src/config/AXISFLYINGF7PRO/config.h new file mode 100644 index 0000000000..945faf841b --- /dev/null +++ b/src/config/AXISFLYINGF7PRO/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME AXISFLYINGF7PRO +#define MANUFACTURER_ID AXFL + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/BEEROTORF4/config.h b/src/config/BEEROTORF4/config.h new file mode 100644 index 0000000000..2eede4690b --- /dev/null +++ b/src/config/BEEROTORF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME BEEROTORF4 +#define MANUFACTURER_ID RCTI + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/BETAFLIGHTF4/config.h b/src/config/BETAFLIGHTF4/config.h new file mode 100644 index 0000000000..783cabd927 --- /dev/null +++ b/src/config/BETAFLIGHTF4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME BETAFLIGHTF4 +#define MANUFACTURER_ID FPVM + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/BETAFPVF405/config.h b/src/config/BETAFPVF405/config.h new file mode 100644 index 0000000000..cc58f2cd7c --- /dev/null +++ b/src/config/BETAFPVF405/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME BETAFPVF405 +#define MANUFACTURER_ID BEFH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/BETAFPVF411/config.h b/src/config/BETAFPVF411/config.h new file mode 100644 index 0000000000..8b4f46f688 --- /dev/null +++ b/src/config/BETAFPVF411/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME BETAFPVF411 +#define MANUFACTURER_ID BEFH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/BETAFPVF411RX/config.h b/src/config/BETAFPVF411RX/config.h new file mode 100644 index 0000000000..a5f078e4e2 --- /dev/null +++ b/src/config/BETAFPVF411RX/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME BETAFPVF411RX +#define MANUFACTURER_ID BEFH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_RX_CC2500 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/BETAFPVF4SX1280/config.h b/src/config/BETAFPVF4SX1280/config.h new file mode 100644 index 0000000000..09de174ce0 --- /dev/null +++ b/src/config/BETAFPVF4SX1280/config.h @@ -0,0 +1,54 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME BETAFPVF4SX1280 +#define MANUFACTURER_ID BEFH + +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB9 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC13 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/BETAFPVF722/config.h b/src/config/BETAFPVF722/config.h new file mode 100644 index 0000000000..1a13347af4 --- /dev/null +++ b/src/config/BETAFPVF722/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME BETAFPVF722 +#define MANUFACTURER_ID BEFH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_MAX7456 + diff --git a/src/config/BETAFPVH743/config.h b/src/config/BETAFPVH743/config.h new file mode 100644 index 0000000000..7c02e4bf6f --- /dev/null +++ b/src/config/BETAFPVH743/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME BETAFPVH743 +#define MANUFACTURER_ID BEFH + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/BLADE_F7/config.h b/src/config/BLADE_F7/config.h new file mode 100644 index 0000000000..56a3d1f1d1 --- /dev/null +++ b/src/config/BLADE_F7/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME BLADE_F7 +#define MANUFACTURER_ID RUSH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/BLADE_F7_HD/config.h b/src/config/BLADE_F7_HD/config.h new file mode 100644 index 0000000000..d16b691387 --- /dev/null +++ b/src/config/BLADE_F7_HD/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME BLADE_F7_HD +#define MANUFACTURER_ID RUSH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_BMP280 +#define USE_BARO_QMP6988 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/BLUEJAYF4/config.h b/src/config/BLUEJAYF4/config.h new file mode 100644 index 0000000000..1ac82f8e1e --- /dev/null +++ b/src/config/BLUEJAYF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME BLUEJAYF4 +#define MANUFACTURER_ID BKMN + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_W25P16 + diff --git a/src/config/CLRACINGF4/config.h b/src/config/CLRACINGF4/config.h new file mode 100644 index 0000000000..bb2212ff35 --- /dev/null +++ b/src/config/CLRACINGF4/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME CLRACINGF4 +#define MANUFACTURER_ID CLRA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/CLRACINGF7/config.h b/src/config/CLRACINGF7/config.h new file mode 100644 index 0000000000..23a70d552b --- /dev/null +++ b/src/config/CLRACINGF7/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME CLRACINGF7 +#define MANUFACTURER_ID CLRA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/COLIBRI/config.h b/src/config/COLIBRI/config.h new file mode 100644 index 0000000000..e5038663ac --- /dev/null +++ b/src/config/COLIBRI/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME COLIBRI +#define MANUFACTURER_ID TEBS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/CRAZYBEEF4DX/config.h b/src/config/CRAZYBEEF4DX/config.h new file mode 100644 index 0000000000..7295073fee --- /dev/null +++ b/src/config/CRAZYBEEF4DX/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME CRAZYBEEF4DX +#define MANUFACTURER_ID HAMO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/CRAZYBEEF4DXS/config.h b/src/config/CRAZYBEEF4DXS/config.h new file mode 100644 index 0000000000..7ceb5691da --- /dev/null +++ b/src/config/CRAZYBEEF4DXS/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME CRAZYBEEF4DXS +#define MANUFACTURER_ID HAMO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/CRAZYBEEF4FR/config.h b/src/config/CRAZYBEEF4FR/config.h new file mode 100644 index 0000000000..1b0783b247 --- /dev/null +++ b/src/config/CRAZYBEEF4FR/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME CRAZYBEEF4FR +#define MANUFACTURER_ID HAMO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_RX_CC2500 +#define USE_MAX7456 + diff --git a/src/config/CRAZYBEEF4FS/config.h b/src/config/CRAZYBEEF4FS/config.h new file mode 100644 index 0000000000..7e608b0666 --- /dev/null +++ b/src/config/CRAZYBEEF4FS/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME CRAZYBEEF4FS +#define MANUFACTURER_ID HAMO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_RX_CC2500 +#define USE_MAX7456 + diff --git a/src/config/CRAZYBEEF4SX1280/config.h b/src/config/CRAZYBEEF4SX1280/config.h new file mode 100644 index 0000000000..50d9893f8c --- /dev/null +++ b/src/config/CRAZYBEEF4SX1280/config.h @@ -0,0 +1,58 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME CRAZYBEEF4SX1280 +#define MANUFACTURER_ID HAMO + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM3 +#define RX_EXPRESSLRS_SPI_RESET_PIN PA8 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC14 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PB9 + diff --git a/src/config/CYCLONEF405_PRO/config.h b/src/config/CYCLONEF405_PRO/config.h new file mode 100644 index 0000000000..7e97c3f184 --- /dev/null +++ b/src/config/CYCLONEF405_PRO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME CYCLONEF405_PRO +#define MANUFACTURER_ID CYCL + diff --git a/src/config/CYCLONEF722_PRO/config.h b/src/config/CYCLONEF722_PRO/config.h new file mode 100644 index 0000000000..22d2d497ae --- /dev/null +++ b/src/config/CYCLONEF722_PRO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME CYCLONEF722_PRO +#define MANUFACTURER_ID CYCL + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25P16 +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/DAKEFPVF405/config.h b/src/config/DAKEFPVF405/config.h new file mode 100644 index 0000000000..d948a1def1 --- /dev/null +++ b/src/config/DAKEFPVF405/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME DAKEFPVF405 +#define MANUFACTURER_ID DAKE + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/DAKEFPVF411/config.h b/src/config/DAKEFPVF411/config.h new file mode 100644 index 0000000000..e04de6a5b3 --- /dev/null +++ b/src/config/DAKEFPVF411/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME DAKEFPVF411 +#define MANUFACTURER_ID DAKE + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/DAKEFPVF722/config.h b/src/config/DAKEFPVF722/config.h new file mode 100644 index 0000000000..afb3fb72d6 --- /dev/null +++ b/src/config/DAKEFPVF722/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME DAKEFPVF722 +#define MANUFACTURER_ID DAKE + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/DALRCF405/config.h b/src/config/DALRCF405/config.h new file mode 100644 index 0000000000..1176a3c603 --- /dev/null +++ b/src/config/DALRCF405/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME DALRCF405 +#define MANUFACTURER_ID DALR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/DALRCF722DUAL/config.h b/src/config/DALRCF722DUAL/config.h new file mode 100644 index 0000000000..0185de8e1b --- /dev/null +++ b/src/config/DALRCF722DUAL/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME DALRCF722DUAL +#define MANUFACTURER_ID DALR + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/DARWINF411/config.h b/src/config/DARWINF411/config.h new file mode 100644 index 0000000000..0a61a4342d --- /dev/null +++ b/src/config/DARWINF411/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME DARWINF411 +#define MANUFACTURER_ID DAFP + +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/DARWINF4SX1280HD/config.h b/src/config/DARWINF4SX1280HD/config.h new file mode 100644 index 0000000000..6584c51649 --- /dev/null +++ b/src/config/DARWINF4SX1280HD/config.h @@ -0,0 +1,61 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME DARWINF4SX1280HD +#define MANUFACTURER_ID DAFP + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB9 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC13 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/DARWINF722HD/config.h b/src/config/DARWINF722HD/config.h new file mode 100644 index 0000000000..39605ba0f9 --- /dev/null +++ b/src/config/DARWINF722HD/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME DARWINF722HD +#define MANUFACTURER_ID DAFP + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/DFR_F722_DUAL_HD/config.h b/src/config/DFR_F722_DUAL_HD/config.h new file mode 100644 index 0000000000..32863bf10d --- /dev/null +++ b/src/config/DFR_F722_DUAL_HD/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME DFR_F722_DUAL_HD +#define MANUFACTURER_ID DFRA + diff --git a/src/config/DRONIUSF7/config.h b/src/config/DRONIUSF7/config.h new file mode 100644 index 0000000000..d566a5cb51 --- /dev/null +++ b/src/config/DRONIUSF7/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME DRONIUSF7 +#define MANUFACTURER_ID FOSS + diff --git a/src/config/DYSF44530D/config.h b/src/config/DYSF44530D/config.h new file mode 100644 index 0000000000..c948c5b8e6 --- /dev/null +++ b/src/config/DYSF44530D/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME DYSF44530D +#define MANUFACTURER_ID DYST + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/DYSF4PRO/config.h b/src/config/DYSF4PRO/config.h new file mode 100644 index 0000000000..a9968aba22 --- /dev/null +++ b/src/config/DYSF4PRO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME DYSF4PRO +#define MANUFACTURER_ID DYST + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/EACHINEF411_AIO/config.h b/src/config/EACHINEF411_AIO/config.h new file mode 100644 index 0000000000..92952f38e4 --- /dev/null +++ b/src/config/EACHINEF411_AIO/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME EACHINEF411_AIO +#define MANUFACTURER_ID EACH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/EACHINEF722/config.h b/src/config/EACHINEF722/config.h new file mode 100644 index 0000000000..001dbd29f0 --- /dev/null +++ b/src/config/EACHINEF722/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME EACHINEF722 +#define MANUFACTURER_ID EACH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/EACHINEF722_AIO/config.h b/src/config/EACHINEF722_AIO/config.h new file mode 100644 index 0000000000..a5498c7efb --- /dev/null +++ b/src/config/EACHINEF722_AIO/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME EACHINEF722_AIO +#define MANUFACTURER_ID EACH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/ELINF405/config.h b/src/config/ELINF405/config.h new file mode 100644 index 0000000000..bcc4bc8158 --- /dev/null +++ b/src/config/ELINF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME ELINF405 +#define MANUFACTURER_ID DRCL + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/ELINF722/config.h b/src/config/ELINF722/config.h new file mode 100644 index 0000000000..22aa745db2 --- /dev/null +++ b/src/config/ELINF722/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ELINF722 +#define MANUFACTURER_ID DRCL + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/ELLE0/config.h b/src/config/ELLE0/config.h new file mode 100644 index 0000000000..bae4e07235 --- /dev/null +++ b/src/config/ELLE0/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME ELLE0 +#define MANUFACTURER_ID LEGA + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 + diff --git a/src/config/EMAX_BABYHAWK_II_HD/config.h b/src/config/EMAX_BABYHAWK_II_HD/config.h new file mode 100644 index 0000000000..0669c14d80 --- /dev/null +++ b/src/config/EMAX_BABYHAWK_II_HD/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME EMAX_BABYHAWK_II_HD +#define MANUFACTURER_ID EMAX + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/EMAX_TINYHAWKF4SX1280/config.h b/src/config/EMAX_TINYHAWKF4SX1280/config.h new file mode 100644 index 0000000000..0facd0c988 --- /dev/null +++ b/src/config/EMAX_TINYHAWKF4SX1280/config.h @@ -0,0 +1,56 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME EMAX_TINYHAWKF4SX1280 +#define MANUFACTURER_ID EMAX + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PA8 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC14 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PB9 + diff --git a/src/config/EMAX_TINYHAWK_F411RX/config.h b/src/config/EMAX_TINYHAWK_F411RX/config.h new file mode 100644 index 0000000000..4f28e67b4c --- /dev/null +++ b/src/config/EMAX_TINYHAWK_F411RX/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME EMAX_TINYHAWK_F411RX +#define MANUFACTURER_ID EMAX + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_RX_CC2500 +#define USE_MAX7456 + diff --git a/src/config/EXF722DUAL/config.h b/src/config/EXF722DUAL/config.h new file mode 100644 index 0000000000..10eebb1637 --- /dev/null +++ b/src/config/EXF722DUAL/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME EXF722DUAL +#define MANUFACTURER_ID EXUA + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/EXUAVF4PRO/config.h b/src/config/EXUAVF4PRO/config.h new file mode 100644 index 0000000000..d246ab0c5e --- /dev/null +++ b/src/config/EXUAVF4PRO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME EXUAVF4PRO +#define MANUFACTURER_ID EXUA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/F4BY/config.h b/src/config/F4BY/config.h new file mode 100644 index 0000000000..cd7c9172ba --- /dev/null +++ b/src/config/F4BY/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME F4BY +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_SDCARD + diff --git a/src/config/FENIX_F405/config.h b/src/config/FENIX_F405/config.h new file mode 100644 index 0000000000..9d53b85a06 --- /dev/null +++ b/src/config/FENIX_F405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FENIX_F405 +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25M +#define USE_MAX7456 + diff --git a/src/config/FF_FORTINIF4/config.h b/src/config/FF_FORTINIF4/config.h new file mode 100644 index 0000000000..3f8ac62a0e --- /dev/null +++ b/src/config/FF_FORTINIF4/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_FORTINIF4 +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/FF_FORTINIF4_REV03/config.h b/src/config/FF_FORTINIF4_REV03/config.h new file mode 100644 index 0000000000..57170bcbe0 --- /dev/null +++ b/src/config/FF_FORTINIF4_REV03/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_FORTINIF4_REV03 +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/FF_PIKOF4/config.h b/src/config/FF_PIKOF4/config.h new file mode 100644 index 0000000000..a45272e0a5 --- /dev/null +++ b/src/config/FF_PIKOF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_PIKOF4 +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 + diff --git a/src/config/FF_PIKOF4OSD/config.h b/src/config/FF_PIKOF4OSD/config.h new file mode 100644 index 0000000000..211ecf925c --- /dev/null +++ b/src/config/FF_PIKOF4OSD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_PIKOF4OSD +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/FF_RACEPIT/config.h b/src/config/FF_RACEPIT/config.h new file mode 100644 index 0000000000..5a3781c951 --- /dev/null +++ b/src/config/FF_RACEPIT/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_RACEPIT +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/FF_RACEPITF7/config.h b/src/config/FF_RACEPITF7/config.h new file mode 100644 index 0000000000..53f7cb760f --- /dev/null +++ b/src/config/FF_RACEPITF7/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FF_RACEPITF7 +#define MANUFACTURER_ID FFPV + diff --git a/src/config/FF_RACEPITF7_MINI/config.h b/src/config/FF_RACEPITF7_MINI/config.h new file mode 100644 index 0000000000..4c1dcffca1 --- /dev/null +++ b/src/config/FF_RACEPITF7_MINI/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FF_RACEPITF7_MINI +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FF_RACEPIT_MINI/config.h b/src/config/FF_RACEPIT_MINI/config.h new file mode 100644 index 0000000000..af8c70a552 --- /dev/null +++ b/src/config/FF_RACEPIT_MINI/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FF_RACEPIT_MINI +#define MANUFACTURER_ID FFPV + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FISHDRONEF4/config.h b/src/config/FISHDRONEF4/config.h new file mode 100644 index 0000000000..6a747ce84a --- /dev/null +++ b/src/config/FISHDRONEF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FISHDRONEF4 +#define MANUFACTURER_ID LEGA + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/FLOWBOX/config.h b/src/config/FLOWBOX/config.h new file mode 100644 index 0000000000..2dd8a53c01 --- /dev/null +++ b/src/config/FLOWBOX/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLOWBOX +#define MANUFACTURER_ID NERC + diff --git a/src/config/FLOWBOXV2/config.h b/src/config/FLOWBOXV2/config.h new file mode 100644 index 0000000000..da7cd66689 --- /dev/null +++ b/src/config/FLOWBOXV2/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLOWBOXV2 +#define MANUFACTURER_ID NERC + diff --git a/src/config/FLYCOLORF7/config.h b/src/config/FLYCOLORF7/config.h new file mode 100644 index 0000000000..d5c05be074 --- /dev/null +++ b/src/config/FLYCOLORF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FLYCOLORF7 +#define MANUFACTURER_ID FLCO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYCOLORF7_AIO/config.h b/src/config/FLYCOLORF7_AIO/config.h new file mode 100644 index 0000000000..9ba5c1bbfb --- /dev/null +++ b/src/config/FLYCOLORF7_AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FLYCOLORF7_AIO +#define MANUFACTURER_ID FLCO + diff --git a/src/config/FLYWOOF405/config.h b/src/config/FLYWOOF405/config.h new file mode 100644 index 0000000000..1c916efad7 --- /dev/null +++ b/src/config/FLYWOOF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FLYWOOF405 +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF405NANO/config.h b/src/config/FLYWOOF405NANO/config.h new file mode 100644 index 0000000000..d0e4c0397b --- /dev/null +++ b/src/config/FLYWOOF405NANO/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FLYWOOF405NANO +#define MANUFACTURER_ID FLWO + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF405PRO/config.h b/src/config/FLYWOOF405PRO/config.h new file mode 100644 index 0000000000..be79088180 --- /dev/null +++ b/src/config/FLYWOOF405PRO/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FLYWOOF405PRO +#define MANUFACTURER_ID FLWO + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF405S_AIO/config.h b/src/config/FLYWOOF405S_AIO/config.h new file mode 100644 index 0000000000..edf2fd47f3 --- /dev/null +++ b/src/config/FLYWOOF405S_AIO/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FLYWOOF405S_AIO +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF411/config.h b/src/config/FLYWOOF411/config.h new file mode 100644 index 0000000000..d4c1904cb2 --- /dev/null +++ b/src/config/FLYWOOF411/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLYWOOF411 +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF411EVO_HD/config.h b/src/config/FLYWOOF411EVO_HD/config.h new file mode 100644 index 0000000000..5b43b7d39e --- /dev/null +++ b/src/config/FLYWOOF411EVO_HD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLYWOOF411EVO_HD +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF411HEX/config.h b/src/config/FLYWOOF411HEX/config.h new file mode 100644 index 0000000000..fc44c2cfe2 --- /dev/null +++ b/src/config/FLYWOOF411HEX/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLYWOOF411HEX +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF411V2/config.h b/src/config/FLYWOOF411V2/config.h new file mode 100644 index 0000000000..8903cc6926 --- /dev/null +++ b/src/config/FLYWOOF411V2/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLYWOOF411V2 +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF411_5IN1_AIO/config.h b/src/config/FLYWOOF411_5IN1_AIO/config.h new file mode 100644 index 0000000000..899ed1f020 --- /dev/null +++ b/src/config/FLYWOOF411_5IN1_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FLYWOOF411_5IN1_AIO +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_RX_CC2500 +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF745/config.h b/src/config/FLYWOOF745/config.h new file mode 100644 index 0000000000..1eddf9986d --- /dev/null +++ b/src/config/FLYWOOF745/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FLYWOOF745 +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF745NANO/config.h b/src/config/FLYWOOF745NANO/config.h new file mode 100644 index 0000000000..8cb305785b --- /dev/null +++ b/src/config/FLYWOOF745NANO/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FLYWOOF745NANO +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FLYWOOF7DUAL/config.h b/src/config/FLYWOOF7DUAL/config.h new file mode 100644 index 0000000000..bc2198fa6f --- /dev/null +++ b/src/config/FLYWOOF7DUAL/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FLYWOOF7DUAL +#define MANUFACTURER_ID FLWO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF405/config.h b/src/config/FOXEERF405/config.h new file mode 100644 index 0000000000..30bcb74326 --- /dev/null +++ b/src/config/FOXEERF405/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FOXEERF405 +#define MANUFACTURER_ID FOXE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/FOXEERF722DUAL/config.h b/src/config/FOXEERF722DUAL/config.h new file mode 100644 index 0000000000..90b80bb78f --- /dev/null +++ b/src/config/FOXEERF722DUAL/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FOXEERF722DUAL +#define MANUFACTURER_ID FOXE + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF722V2/config.h b/src/config/FOXEERF722V2/config.h new file mode 100644 index 0000000000..9ad30ecf73 --- /dev/null +++ b/src/config/FOXEERF722V2/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FOXEERF722V2 +#define MANUFACTURER_ID FOXE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF722V3/config.h b/src/config/FOXEERF722V3/config.h new file mode 100644 index 0000000000..9587205317 --- /dev/null +++ b/src/config/FOXEERF722V3/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FOXEERF722V3 +#define MANUFACTURER_ID FOXE + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF722V4/config.h b/src/config/FOXEERF722V4/config.h new file mode 100644 index 0000000000..1f2906be54 --- /dev/null +++ b/src/config/FOXEERF722V4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME FOXEERF722V4 +#define MANUFACTURER_ID FOXE + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF745V2_AIO/config.h b/src/config/FOXEERF745V2_AIO/config.h new file mode 100644 index 0000000000..94f4a556bb --- /dev/null +++ b/src/config/FOXEERF745V2_AIO/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FOXEERF745V2_AIO +#define MANUFACTURER_ID FOXE + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF745V3_AIO/config.h b/src/config/FOXEERF745V3_AIO/config.h new file mode 100644 index 0000000000..815d96d984 --- /dev/null +++ b/src/config/FOXEERF745V3_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FOXEERF745V3_AIO +#define MANUFACTURER_ID FOXE + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERF745_AIO/config.h b/src/config/FOXEERF745_AIO/config.h new file mode 100644 index 0000000000..21a1ae13d7 --- /dev/null +++ b/src/config/FOXEERF745_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FOXEERF745_AIO +#define MANUFACTURER_ID FOXE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FOXEERH743/config.h b/src/config/FOXEERH743/config.h new file mode 100644 index 0000000000..3c2432da66 --- /dev/null +++ b/src/config/FOXEERH743/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME FOXEERH743 +#define MANUFACTURER_ID FOXE + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/FPVCYCLEF401/config.h b/src/config/FPVCYCLEF401/config.h new file mode 100644 index 0000000000..a53840d905 --- /dev/null +++ b/src/config/FPVCYCLEF401/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME FPVCYCLEF401 +#define MANUFACTURER_ID TURC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/FPVM_BETAFLIGHTF7/config.h b/src/config/FPVM_BETAFLIGHTF7/config.h new file mode 100644 index 0000000000..ff2b6fca33 --- /dev/null +++ b/src/config/FPVM_BETAFLIGHTF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME FPVM_BETAFLIGHTF7 +#define MANUFACTURER_ID FPVM + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/FRSKYF4/config.h b/src/config/FRSKYF4/config.h new file mode 100644 index 0000000000..344c1c1767 --- /dev/null +++ b/src/config/FRSKYF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FRSKYF4 +#define MANUFACTURER_ID FRSK + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/FURYF4/config.h b/src/config/FURYF4/config.h new file mode 100644 index 0000000000..9b67b7eb73 --- /dev/null +++ b/src/config/FURYF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FURYF4 +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_SDCARD + diff --git a/src/config/FURYF4OSD/config.h b/src/config/FURYF4OSD/config.h new file mode 100644 index 0000000000..afebb47b8b --- /dev/null +++ b/src/config/FURYF4OSD/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME FURYF4OSD +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEELANGF411/config.h b/src/config/GEELANGF411/config.h new file mode 100644 index 0000000000..85f8cdf4ca --- /dev/null +++ b/src/config/GEELANGF411/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEELANGF411 +#define MANUFACTURER_ID GEEL + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/GEMEF411/config.h b/src/config/GEMEF411/config.h new file mode 100644 index 0000000000..be131a802f --- /dev/null +++ b/src/config/GEMEF411/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEMEF411 +#define MANUFACTURER_ID GFPV + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/GEMEF722/config.h b/src/config/GEMEF722/config.h new file mode 100644 index 0000000000..bf1fb1f493 --- /dev/null +++ b/src/config/GEMEF722/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GEMEF722 +#define MANUFACTURER_ID GFPV + diff --git a/src/config/GEPRCF405/config.h b/src/config/GEPRCF405/config.h new file mode 100644 index 0000000000..98989efbc8 --- /dev/null +++ b/src/config/GEPRCF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME GEPRCF405 +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEPRCF411/config.h b/src/config/GEPRCF411/config.h new file mode 100644 index 0000000000..d70877b005 --- /dev/null +++ b/src/config/GEPRCF411/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEPRCF411 +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/GEPRCF411SX1280/config.h b/src/config/GEPRCF411SX1280/config.h new file mode 100644 index 0000000000..c9d0d9d031 --- /dev/null +++ b/src/config/GEPRCF411SX1280/config.h @@ -0,0 +1,60 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEPRCF411SX1280 +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_LSM6DSO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB9 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC13 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/GEPRCF411_AIO/config.h b/src/config/GEPRCF411_AIO/config.h new file mode 100644 index 0000000000..0a75462131 --- /dev/null +++ b/src/config/GEPRCF411_AIO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEPRCF411_AIO +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEPRCF411_PRO/config.h b/src/config/GEPRCF411_PRO/config.h new file mode 100644 index 0000000000..be1f646e1f --- /dev/null +++ b/src/config/GEPRCF411_PRO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME GEPRCF411_PRO +#define MANUFACTURER_ID GEPR + diff --git a/src/config/GEPRCF722/config.h b/src/config/GEPRCF722/config.h new file mode 100644 index 0000000000..cd22f57e30 --- /dev/null +++ b/src/config/GEPRCF722/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GEPRCF722 +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEPRCF722BT/config.h b/src/config/GEPRCF722BT/config.h new file mode 100644 index 0000000000..2376ed10c8 --- /dev/null +++ b/src/config/GEPRCF722BT/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GEPRCF722BT +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEPRCF722_BT_HD/config.h b/src/config/GEPRCF722_BT_HD/config.h new file mode 100644 index 0000000000..9475018608 --- /dev/null +++ b/src/config/GEPRCF722_BT_HD/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GEPRCF722_BT_HD +#define MANUFACTURER_ID GEPR + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_SDCARD +#define USE_MAX7456 + diff --git a/src/config/GEPRCF745_BT_HD/config.h b/src/config/GEPRCF745_BT_HD/config.h new file mode 100644 index 0000000000..cf5efcb9b1 --- /dev/null +++ b/src/config/GEPRCF745_BT_HD/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME GEPRCF745_BT_HD +#define MANUFACTURER_ID GEPR + diff --git a/src/config/GEPRC_F722_AIO/config.h b/src/config/GEPRC_F722_AIO/config.h new file mode 100644 index 0000000000..3aaf4e2682 --- /dev/null +++ b/src/config/GEPRC_F722_AIO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GEPRC_F722_AIO +#define MANUFACTURER_ID GEPR + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/GEP_F405_VTX_V3/config.h b/src/config/GEP_F405_VTX_V3/config.h new file mode 100644 index 0000000000..ebbcf00a0a --- /dev/null +++ b/src/config/GEP_F405_VTX_V3/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME GEP_F405_VTX_V3 +#define MANUFACTURER_ID GEPR + diff --git a/src/config/GRAVITYF7/config.h b/src/config/GRAVITYF7/config.h new file mode 100644 index 0000000000..154707b07d --- /dev/null +++ b/src/config/GRAVITYF7/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME GRAVITYF7 +#define MANUFACTURER_ID FLMO + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF405/config.h b/src/config/HAKRCF405/config.h new file mode 100644 index 0000000000..ba5e527837 --- /dev/null +++ b/src/config/HAKRCF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HAKRCF405 +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_MAX7456 + diff --git a/src/config/HAKRCF405D/config.h b/src/config/HAKRCF405D/config.h new file mode 100644 index 0000000000..56da34f757 --- /dev/null +++ b/src/config/HAKRCF405D/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HAKRCF405D +#define MANUFACTURER_ID HARC + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF405V2/config.h b/src/config/HAKRCF405V2/config.h new file mode 100644 index 0000000000..4cfec744ab --- /dev/null +++ b/src/config/HAKRCF405V2/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HAKRCF405V2 +#define MANUFACTURER_ID HARC + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF411/config.h b/src/config/HAKRCF411/config.h new file mode 100644 index 0000000000..54a6690a31 --- /dev/null +++ b/src/config/HAKRCF411/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME HAKRCF411 +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_MAX7456 + diff --git a/src/config/HAKRCF411D/config.h b/src/config/HAKRCF411D/config.h new file mode 100644 index 0000000000..77d034ca3b --- /dev/null +++ b/src/config/HAKRCF411D/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME HAKRCF411D +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF722/config.h b/src/config/HAKRCF722/config.h new file mode 100644 index 0000000000..d5c65055e8 --- /dev/null +++ b/src/config/HAKRCF722/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HAKRCF722 +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/HAKRCF722D/config.h b/src/config/HAKRCF722D/config.h new file mode 100644 index 0000000000..3ddb6ecd8d --- /dev/null +++ b/src/config/HAKRCF722D/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HAKRCF722D +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF722MINI/config.h b/src/config/HAKRCF722MINI/config.h new file mode 100644 index 0000000000..c1644e9af2 --- /dev/null +++ b/src/config/HAKRCF722MINI/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HAKRCF722MINI +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF722V2/config.h b/src/config/HAKRCF722V2/config.h new file mode 100644 index 0000000000..b26dbd62ce --- /dev/null +++ b/src/config/HAKRCF722V2/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HAKRCF722V2 +#define MANUFACTURER_ID HARC + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HAKRCF7230D/config.h b/src/config/HAKRCF7230D/config.h new file mode 100644 index 0000000000..61925eed75 --- /dev/null +++ b/src/config/HAKRCF7230D/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HAKRCF7230D +#define MANUFACTURER_ID HARC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HELSEL_STRIKERF7/config.h b/src/config/HELSEL_STRIKERF7/config.h new file mode 100644 index 0000000000..3097a86f4e --- /dev/null +++ b/src/config/HELSEL_STRIKERF7/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HELSEL_STRIKERF7 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 + diff --git a/src/config/HGLRCF405/config.h b/src/config/HGLRCF405/config.h new file mode 100644 index 0000000000..47ed69b9d6 --- /dev/null +++ b/src/config/HGLRCF405/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HGLRCF405 +#define MANUFACTURER_ID HGLR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/HGLRCF405AS/config.h b/src/config/HGLRCF405AS/config.h new file mode 100644 index 0000000000..2fe0977b2b --- /dev/null +++ b/src/config/HGLRCF405AS/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HGLRCF405AS +#define MANUFACTURER_ID HGLR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_BARO +#define USE_BARO_BMP280 + diff --git a/src/config/HGLRCF411/config.h b/src/config/HGLRCF411/config.h new file mode 100644 index 0000000000..c0d7791e85 --- /dev/null +++ b/src/config/HGLRCF411/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME HGLRCF411 +#define MANUFACTURER_ID HGLR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/HGLRCF411SX1280/config.h b/src/config/HGLRCF411SX1280/config.h new file mode 100644 index 0000000000..ac84859235 --- /dev/null +++ b/src/config/HGLRCF411SX1280/config.h @@ -0,0 +1,54 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME HGLRCF411SX1280 +#define MANUFACTURER_ID HGLR + +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB9 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC13 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/HGLRCF722/config.h b/src/config/HGLRCF722/config.h new file mode 100644 index 0000000000..0f1efb2648 --- /dev/null +++ b/src/config/HGLRCF722/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HGLRCF722 +#define MANUFACTURER_ID HGLR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 + diff --git a/src/config/HGLRCF722E/config.h b/src/config/HGLRCF722E/config.h new file mode 100644 index 0000000000..0f09522765 --- /dev/null +++ b/src/config/HGLRCF722E/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HGLRCF722E +#define MANUFACTURER_ID HGLR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_SPI_BMP280 + diff --git a/src/config/HGLRCF745/config.h b/src/config/HGLRCF745/config.h new file mode 100644 index 0000000000..c8acfcfe70 --- /dev/null +++ b/src/config/HGLRCF745/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME HGLRCF745 +#define MANUFACTURER_ID HGLR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_BARO_SPI_DPS310 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/HIFIONRCF7/config.h b/src/config/HIFIONRCF7/config.h new file mode 100644 index 0000000000..c268e96f2d --- /dev/null +++ b/src/config/HIFIONRCF7/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HIFIONRCF7 +#define MANUFACTURER_ID HFOR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HOBBYWING_XROTORF4G3/config.h b/src/config/HOBBYWING_XROTORF4G3/config.h new file mode 100644 index 0000000000..8ba61bed83 --- /dev/null +++ b/src/config/HOBBYWING_XROTORF4G3/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME HOBBYWING_XROTORF4G3 +#define MANUFACTURER_ID HOWI + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/HOBBYWING_XROTORF7CONV/config.h b/src/config/HOBBYWING_XROTORF7CONV/config.h new file mode 100644 index 0000000000..67af8f572b --- /dev/null +++ b/src/config/HOBBYWING_XROTORF7CONV/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME HOBBYWING_XROTORF7CONV +#define MANUFACTURER_ID HOWI + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/HYBRIDG4/config.h b/src/config/HYBRIDG4/config.h new file mode 100644 index 0000000000..7bbd214c4d --- /dev/null +++ b/src/config/HYBRIDG4/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32G47X + +#define BOARD_NAME HYBRIDG4 +#define MANUFACTURER_ID NERC + diff --git a/src/config/IFLIGHT_BLITZ_F405/config.h b/src/config/IFLIGHT_BLITZ_F405/config.h new file mode 100644 index 0000000000..db931ba959 --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME IFLIGHT_BLITZ_F405 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_BLITZ_F411RX/config.h b/src/config/IFLIGHT_BLITZ_F411RX/config.h new file mode 100644 index 0000000000..66e6fabf93 --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F411RX/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME IFLIGHT_BLITZ_F411RX +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_BLITZ_F722/config.h b/src/config/IFLIGHT_BLITZ_F722/config.h new file mode 100644 index 0000000000..d48cd3d1e3 --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F722/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME IFLIGHT_BLITZ_F722 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_BLITZ_F722_X1/config.h b/src/config/IFLIGHT_BLITZ_F722_X1/config.h new file mode 100644 index 0000000000..d590e066e3 --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F722_X1/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME IFLIGHT_BLITZ_F722_X1 +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_BLITZ_F7_AIO/config.h b/src/config/IFLIGHT_BLITZ_F7_AIO/config.h new file mode 100644 index 0000000000..77953f167c --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F7_AIO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME IFLIGHT_BLITZ_F7_AIO +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_BLITZ_F7_PRO/config.h b/src/config/IFLIGHT_BLITZ_F7_PRO/config.h new file mode 100644 index 0000000000..a69429ac65 --- /dev/null +++ b/src/config/IFLIGHT_BLITZ_F7_PRO/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME IFLIGHT_BLITZ_F7_PRO +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/IFLIGHT_F405_AIO/config.h b/src/config/IFLIGHT_F405_AIO/config.h new file mode 100644 index 0000000000..1287f3dd62 --- /dev/null +++ b/src/config/IFLIGHT_F405_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME IFLIGHT_F405_AIO +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F405_TWING/config.h b/src/config/IFLIGHT_F405_TWING/config.h new file mode 100644 index 0000000000..153a71718f --- /dev/null +++ b/src/config/IFLIGHT_F405_TWING/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME IFLIGHT_F405_TWING +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F411_AIO32/config.h b/src/config/IFLIGHT_F411_AIO32/config.h new file mode 100644 index 0000000000..4411be790b --- /dev/null +++ b/src/config/IFLIGHT_F411_AIO32/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME IFLIGHT_F411_AIO32 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F411_PRO/config.h b/src/config/IFLIGHT_F411_PRO/config.h new file mode 100644 index 0000000000..2e0a8aed88 --- /dev/null +++ b/src/config/IFLIGHT_F411_PRO/config.h @@ -0,0 +1,48 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME IFLIGHT_F411_PRO +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F4SX1280/config.h b/src/config/IFLIGHT_F4SX1280/config.h new file mode 100644 index 0000000000..9422793454 --- /dev/null +++ b/src/config/IFLIGHT_F4SX1280/config.h @@ -0,0 +1,50 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME IFLIGHT_F4SX1280 +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PA8 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC14 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/IFLIGHT_F722_TWING/config.h b/src/config/IFLIGHT_F722_TWING/config.h new file mode 100644 index 0000000000..d1d4e28c68 --- /dev/null +++ b/src/config/IFLIGHT_F722_TWING/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME IFLIGHT_F722_TWING +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25M512 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F745_AIO/config.h b/src/config/IFLIGHT_F745_AIO/config.h new file mode 100644 index 0000000000..e82d7d3924 --- /dev/null +++ b/src/config/IFLIGHT_F745_AIO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME IFLIGHT_F745_AIO +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_F745_AIO_V2/config.h b/src/config/IFLIGHT_F745_AIO_V2/config.h new file mode 100644 index 0000000000..755dc13906 --- /dev/null +++ b/src/config/IFLIGHT_F745_AIO_V2/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME IFLIGHT_F745_AIO_V2 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_H743_AIO_V2/config.h b/src/config/IFLIGHT_H743_AIO_V2/config.h new file mode 100644 index 0000000000..700cab5535 --- /dev/null +++ b/src/config/IFLIGHT_H743_AIO_V2/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME IFLIGHT_H743_AIO_V2 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_H7_TWING/config.h b/src/config/IFLIGHT_H7_TWING/config.h new file mode 100644 index 0000000000..84ccee0edc --- /dev/null +++ b/src/config/IFLIGHT_H7_TWING/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME IFLIGHT_H7_TWING +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_SUCCEX_E_F4/config.h b/src/config/IFLIGHT_SUCCEX_E_F4/config.h new file mode 100644 index 0000000000..94051fb5c1 --- /dev/null +++ b/src/config/IFLIGHT_SUCCEX_E_F4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME IFLIGHT_SUCCEX_E_F4 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/IFLIGHT_SUCCEX_E_F7/config.h b/src/config/IFLIGHT_SUCCEX_E_F7/config.h new file mode 100644 index 0000000000..7d259c55ba --- /dev/null +++ b/src/config/IFLIGHT_SUCCEX_E_F7/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME IFLIGHT_SUCCEX_E_F7 +#define MANUFACTURER_ID IFRC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/JBF7/config.h b/src/config/JBF7/config.h new file mode 100644 index 0000000000..4ebd85574e --- /dev/null +++ b/src/config/JBF7/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME JBF7 +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/JBF7_DJI/config.h b/src/config/JBF7_DJI/config.h new file mode 100644 index 0000000000..8d39492f72 --- /dev/null +++ b/src/config/JBF7_DJI/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME JBF7_DJI +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/JBF7_V2/config.h b/src/config/JBF7_V2/config.h new file mode 100644 index 0000000000..dbe7baab17 --- /dev/null +++ b/src/config/JBF7_V2/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME JBF7_V2 +#define MANUFACTURER_ID IFRC + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_BARO +#define USE_BARO_DPS310 + diff --git a/src/config/JHEF405/config.h b/src/config/JHEF405/config.h new file mode 100644 index 0000000000..2c76237313 --- /dev/null +++ b/src/config/JHEF405/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME JHEF405 +#define MANUFACTURER_ID JHEF + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/JHEF405PRO/config.h b/src/config/JHEF405PRO/config.h new file mode 100644 index 0000000000..222fa6b33a --- /dev/null +++ b/src/config/JHEF405PRO/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME JHEF405PRO +#define MANUFACTURER_ID JHEF + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/JHEF411/config.h b/src/config/JHEF411/config.h new file mode 100644 index 0000000000..13a948b02d --- /dev/null +++ b/src/config/JHEF411/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME JHEF411 +#define MANUFACTURER_ID JHEF + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/JHEF745/config.h b/src/config/JHEF745/config.h new file mode 100644 index 0000000000..ab47362812 --- /dev/null +++ b/src/config/JHEF745/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME JHEF745 +#define MANUFACTURER_ID JHEF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/JHEF7DUAL/config.h b/src/config/JHEF7DUAL/config.h new file mode 100644 index 0000000000..4645e2523b --- /dev/null +++ b/src/config/JHEF7DUAL/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME JHEF7DUAL +#define MANUFACTURER_ID JHEF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/JHEH743_AIO/config.h b/src/config/JHEH743_AIO/config.h new file mode 100644 index 0000000000..dcd8145dd2 --- /dev/null +++ b/src/config/JHEH743_AIO/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME JHEH743_AIO +#define MANUFACTURER_ID JHEF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/KAKUTEF4/config.h b/src/config/KAKUTEF4/config.h new file mode 100644 index 0000000000..a3b73bef09 --- /dev/null +++ b/src/config/KAKUTEF4/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME KAKUTEF4 +#define MANUFACTURER_ID HBRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/KAKUTEF4V2/config.h b/src/config/KAKUTEF4V2/config.h new file mode 100644 index 0000000000..889d83111b --- /dev/null +++ b/src/config/KAKUTEF4V2/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME KAKUTEF4V2 +#define MANUFACTURER_ID HBRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/KAKUTEF7/config.h b/src/config/KAKUTEF7/config.h new file mode 100644 index 0000000000..1af905743a --- /dev/null +++ b/src/config/KAKUTEF7/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME KAKUTEF7 +#define MANUFACTURER_ID HBRO + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/KAKUTEF7HDV/config.h b/src/config/KAKUTEF7HDV/config.h new file mode 100644 index 0000000000..38d29c0ba7 --- /dev/null +++ b/src/config/KAKUTEF7HDV/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME KAKUTEF7HDV +#define MANUFACTURER_ID HBRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_SDCARD + diff --git a/src/config/KAKUTEF7MINI/config.h b/src/config/KAKUTEF7MINI/config.h new file mode 100644 index 0000000000..b52d852115 --- /dev/null +++ b/src/config/KAKUTEF7MINI/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME KAKUTEF7MINI +#define MANUFACTURER_ID HBRO + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/KAKUTEF7MINIV3/config.h b/src/config/KAKUTEF7MINIV3/config.h new file mode 100644 index 0000000000..f299c0d7ae --- /dev/null +++ b/src/config/KAKUTEF7MINIV3/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME KAKUTEF7MINIV3 +#define MANUFACTURER_ID HBRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/KAKUTEF7V2/config.h b/src/config/KAKUTEF7V2/config.h new file mode 100644 index 0000000000..c6c003ef8e --- /dev/null +++ b/src/config/KAKUTEF7V2/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME KAKUTEF7V2 +#define MANUFACTURER_ID HBRO + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/KAKUTEH7/config.h b/src/config/KAKUTEH7/config.h new file mode 100644 index 0000000000..ac479864e2 --- /dev/null +++ b/src/config/KAKUTEH7/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME KAKUTEH7 +#define MANUFACTURER_ID HBRO + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/KAKUTEH7MINI/config.h b/src/config/KAKUTEH7MINI/config.h new file mode 100644 index 0000000000..746330d2fb --- /dev/null +++ b/src/config/KAKUTEH7MINI/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME KAKUTEH7MINI +#define MANUFACTURER_ID HBRO + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/KAKUTEH7V2/config.h b/src/config/KAKUTEH7V2/config.h new file mode 100644 index 0000000000..03177ea813 --- /dev/null +++ b/src/config/KAKUTEH7V2/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME KAKUTEH7V2 +#define MANUFACTURER_ID HBRO + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/KD722/config.h b/src/config/KD722/config.h new file mode 100644 index 0000000000..3fb02c9316 --- /dev/null +++ b/src/config/KD722/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME KD722 +#define MANUFACTURER_ID HARC + diff --git a/src/config/KIWIF4/config.h b/src/config/KIWIF4/config.h new file mode 100644 index 0000000000..dc248f58dd --- /dev/null +++ b/src/config/KIWIF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME KIWIF4 +#define MANUFACTURER_ID FLLF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/KIWIF4V2/config.h b/src/config/KIWIF4V2/config.h new file mode 100644 index 0000000000..4948793c75 --- /dev/null +++ b/src/config/KIWIF4V2/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME KIWIF4V2 +#define MANUFACTURER_ID FLLF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/KROOZX/config.h b/src/config/KROOZX/config.h new file mode 100644 index 0000000000..65198b12ac --- /dev/null +++ b/src/config/KROOZX/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME KROOZX +#define MANUFACTURER_ID LEGA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/LDARC_F411/config.h b/src/config/LDARC_F411/config.h new file mode 100644 index 0000000000..a2e44229b3 --- /dev/null +++ b/src/config/LDARC_F411/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME LDARC_F411 +#define MANUFACTURER_ID LDAR + diff --git a/src/config/LUXAIO/config.h b/src/config/LUXAIO/config.h new file mode 100644 index 0000000000..678b14bb63 --- /dev/null +++ b/src/config/LUXAIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME LUXAIO +#define MANUFACTURER_ID LMNR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/LUXF4OSD/config.h b/src/config/LUXF4OSD/config.h new file mode 100644 index 0000000000..5810ddee70 --- /dev/null +++ b/src/config/LUXF4OSD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME LUXF4OSD +#define MANUFACTURER_ID LMNR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/LUXF7HDV/config.h b/src/config/LUXF7HDV/config.h new file mode 100644 index 0000000000..f8660fe3d0 --- /dev/null +++ b/src/config/LUXF7HDV/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME LUXF7HDV +#define MANUFACTURER_ID LMNR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/LUXMINIF7/config.h b/src/config/LUXMINIF7/config.h new file mode 100644 index 0000000000..6b3b26b60b --- /dev/null +++ b/src/config/LUXMINIF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME LUXMINIF7 +#define MANUFACTURER_ID LMNR + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF405US/config.h b/src/config/MAMBAF405US/config.h new file mode 100644 index 0000000000..8e73763ea0 --- /dev/null +++ b/src/config/MAMBAF405US/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MAMBAF405US +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MAMBAF405US_I2C/config.h b/src/config/MAMBAF405US_I2C/config.h new file mode 100644 index 0000000000..938b512e32 --- /dev/null +++ b/src/config/MAMBAF405US_I2C/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MAMBAF405US_I2C +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF405_2022A/config.h b/src/config/MAMBAF405_2022A/config.h new file mode 100644 index 0000000000..53d5a0021e --- /dev/null +++ b/src/config/MAMBAF405_2022A/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MAMBAF405_2022A +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF405_2022B/config.h b/src/config/MAMBAF405_2022B/config.h new file mode 100644 index 0000000000..693c8eae7d --- /dev/null +++ b/src/config/MAMBAF405_2022B/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MAMBAF405_2022B +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF411/config.h b/src/config/MAMBAF411/config.h new file mode 100644 index 0000000000..2c84632465 --- /dev/null +++ b/src/config/MAMBAF411/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME MAMBAF411 +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF722/config.h b/src/config/MAMBAF722/config.h new file mode 100644 index 0000000000..90f337fa03 --- /dev/null +++ b/src/config/MAMBAF722/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MAMBAF722 +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MAMBAF722_2022A/config.h b/src/config/MAMBAF722_2022A/config.h new file mode 100644 index 0000000000..f9352de272 --- /dev/null +++ b/src/config/MAMBAF722_2022A/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MAMBAF722_2022A +#define MANUFACTURER_ID DIAT + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_DPS310 + diff --git a/src/config/MAMBAF722_2022B/config.h b/src/config/MAMBAF722_2022B/config.h new file mode 100644 index 0000000000..d57c08b8f7 --- /dev/null +++ b/src/config/MAMBAF722_2022B/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MAMBAF722_2022B +#define MANUFACTURER_ID DIAT + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/MAMBAF722_I2C/config.h b/src/config/MAMBAF722_I2C/config.h new file mode 100644 index 0000000000..f0eaa561ae --- /dev/null +++ b/src/config/MAMBAF722_I2C/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MAMBAF722_I2C +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MAMBAF722_X8/config.h b/src/config/MAMBAF722_X8/config.h new file mode 100644 index 0000000000..c92255fc49 --- /dev/null +++ b/src/config/MAMBAF722_X8/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MAMBAF722_X8 +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MAMBAG4/config.h b/src/config/MAMBAG4/config.h new file mode 100644 index 0000000000..f0a241e3fc --- /dev/null +++ b/src/config/MAMBAG4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32G47X + +#define BOARD_NAME MAMBAG4 +#define MANUFACTURER_ID DIAT + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MAMBAH743/config.h b/src/config/MAMBAH743/config.h new file mode 100644 index 0000000000..45c9713dcf --- /dev/null +++ b/src/config/MAMBAH743/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME MAMBAH743 +#define MANUFACTURER_ID DIAT + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42605 +#define USE_ACC_SPI_ICM42605 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/MATEKF405AIO/config.h b/src/config/MATEKF405AIO/config.h new file mode 100644 index 0000000000..16d98e2626 --- /dev/null +++ b/src/config/MATEKF405AIO/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405AIO +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF405CTR/config.h b/src/config/MATEKF405CTR/config.h new file mode 100644 index 0000000000..dccba537dd --- /dev/null +++ b/src/config/MATEKF405CTR/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405CTR +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF405MINI/config.h b/src/config/MATEKF405MINI/config.h new file mode 100644 index 0000000000..6edd9e67d3 --- /dev/null +++ b/src/config/MATEKF405MINI/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405MINI +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MATEKF405SE/config.h b/src/config/MATEKF405SE/config.h new file mode 100644 index 0000000000..a304ee580c --- /dev/null +++ b/src/config/MATEKF405SE/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405SE +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF405STD/config.h b/src/config/MATEKF405STD/config.h new file mode 100644 index 0000000000..24ce738e95 --- /dev/null +++ b/src/config/MATEKF405STD/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405STD +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_ICM20602 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20602 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF405STD_CLONE/config.h b/src/config/MATEKF405STD_CLONE/config.h new file mode 100644 index 0000000000..8d53b38c86 --- /dev/null +++ b/src/config/MATEKF405STD_CLONE/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405STD_CLONE +#define MANUFACTURER_ID CLNE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF405TE/config.h b/src/config/MATEKF405TE/config.h new file mode 100644 index 0000000000..1e724b2618 --- /dev/null +++ b/src/config/MATEKF405TE/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405TE +#define MANUFACTURER_ID MTKS + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/MATEKF405TEMINI/config.h b/src/config/MATEKF405TEMINI/config.h new file mode 100644 index 0000000000..c849b5f5e0 --- /dev/null +++ b/src/config/MATEKF405TEMINI/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please ensure you update unified targets and not this file until the transition has complete. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MATEKF405TEMINI +#define MANUFACTURER_ID MTKS + +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_BARO_DPS310 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/MATEKF411/config.h b/src/config/MATEKF411/config.h new file mode 100644 index 0000000000..3267435119 --- /dev/null +++ b/src/config/MATEKF411/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME MATEKF411 +#define MANUFACTURER_ID MTKS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/MATEKF411RX/config.h b/src/config/MATEKF411RX/config.h new file mode 100644 index 0000000000..66dacc54f8 --- /dev/null +++ b/src/config/MATEKF411RX/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME MATEKF411RX +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_RX_CC2500 +#define USE_MAX7456 + diff --git a/src/config/MATEKF411SE/config.h b/src/config/MATEKF411SE/config.h new file mode 100644 index 0000000000..a4927837d2 --- /dev/null +++ b/src/config/MATEKF411SE/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME MATEKF411SE +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/MATEKF722/config.h b/src/config/MATEKF722/config.h new file mode 100644 index 0000000000..86131a2ac8 --- /dev/null +++ b/src/config/MATEKF722/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MATEKF722 +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKF722HD/config.h b/src/config/MATEKF722HD/config.h new file mode 100644 index 0000000000..2d50bdeca4 --- /dev/null +++ b/src/config/MATEKF722HD/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MATEKF722HD +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV + diff --git a/src/config/MATEKF722MINI/config.h b/src/config/MATEKF722MINI/config.h new file mode 100644 index 0000000000..998311d760 --- /dev/null +++ b/src/config/MATEKF722MINI/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MATEKF722MINI +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MATEKF722SE/config.h b/src/config/MATEKF722SE/config.h new file mode 100644 index 0000000000..5406fe4a2e --- /dev/null +++ b/src/config/MATEKF722SE/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MATEKF722SE +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MATEKH743/config.h b/src/config/MATEKH743/config.h new file mode 100644 index 0000000000..ee1b30d40d --- /dev/null +++ b/src/config/MATEKH743/config.h @@ -0,0 +1,48 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME MATEKH743 +#define MANUFACTURER_ID MTKS + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42605 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_DPS310 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MERAKRCF405/config.h b/src/config/MERAKRCF405/config.h new file mode 100644 index 0000000000..a2442a844f --- /dev/null +++ b/src/config/MERAKRCF405/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MERAKRCF405 +#define MANUFACTURER_ID MERA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/MERAKRCF722/config.h b/src/config/MERAKRCF722/config.h new file mode 100644 index 0000000000..1bce75d545 --- /dev/null +++ b/src/config/MERAKRCF722/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME MERAKRCF722 +#define MANUFACTURER_ID MERA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/MINI_H743_HD/config.h b/src/config/MINI_H743_HD/config.h new file mode 100644 index 0000000000..a593e2e05e --- /dev/null +++ b/src/config/MINI_H743_HD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME MINI_H743_HD +#define MANUFACTURER_ID RAST + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/MLTEMPF4/config.h b/src/config/MLTEMPF4/config.h new file mode 100644 index 0000000000..6cbb88c55e --- /dev/null +++ b/src/config/MLTEMPF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MLTEMPF4 +#define MANUFACTURER_ID MOLA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/MLTYPHF4/config.h b/src/config/MLTYPHF4/config.h new file mode 100644 index 0000000000..2211d3ed6b --- /dev/null +++ b/src/config/MLTYPHF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MLTYPHF4 +#define MANUFACTURER_ID MOLA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/MODULARF4/config.h b/src/config/MODULARF4/config.h new file mode 100644 index 0000000000..1e1dace4e3 --- /dev/null +++ b/src/config/MODULARF4/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME MODULARF4 +#define MANUFACTURER_ID TACO + diff --git a/src/config/NBD_CRICKETF7/config.h b/src/config/NBD_CRICKETF7/config.h new file mode 100644 index 0000000000..6f54a7c96a --- /dev/null +++ b/src/config/NBD_CRICKETF7/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NBD_CRICKETF7 +#define MANUFACTURER_ID NEBD + diff --git a/src/config/NBD_CRICKETF7V2/config.h b/src/config/NBD_CRICKETF7V2/config.h new file mode 100644 index 0000000000..6a8846672a --- /dev/null +++ b/src/config/NBD_CRICKETF7V2/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NBD_CRICKETF7V2 +#define MANUFACTURER_ID NEBD + diff --git a/src/config/NBD_GALAXYAIO255/config.h b/src/config/NBD_GALAXYAIO255/config.h new file mode 100644 index 0000000000..d61ac9e25b --- /dev/null +++ b/src/config/NBD_GALAXYAIO255/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME NBD_GALAXYAIO255 +#define MANUFACTURER_ID NEBD + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/NBD_INFINITYAIO/config.h b/src/config/NBD_INFINITYAIO/config.h new file mode 100644 index 0000000000..9b6e03caea --- /dev/null +++ b/src/config/NBD_INFINITYAIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NBD_INFINITYAIO +#define MANUFACTURER_ID NEBD + diff --git a/src/config/NBD_INFINITYAIOV2/config.h b/src/config/NBD_INFINITYAIOV2/config.h new file mode 100644 index 0000000000..45afca9fef --- /dev/null +++ b/src/config/NBD_INFINITYAIOV2/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME NBD_INFINITYAIOV2 +#define MANUFACTURER_ID NEBD + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/NBD_INFINITYAIOV2PRO/config.h b/src/config/NBD_INFINITYAIOV2PRO/config.h new file mode 100644 index 0000000000..b391a67128 --- /dev/null +++ b/src/config/NBD_INFINITYAIOV2PRO/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME NBD_INFINITYAIOV2PRO +#define MANUFACTURER_ID NEBD + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/NBD_INFINITYF4/config.h b/src/config/NBD_INFINITYF4/config.h new file mode 100644 index 0000000000..6d1f69fd6f --- /dev/null +++ b/src/config/NBD_INFINITYF4/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME NBD_INFINITYF4 +#define MANUFACTURER_ID NEBD + diff --git a/src/config/NERO/config.h b/src/config/NERO/config.h new file mode 100644 index 0000000000..b7c9487f71 --- /dev/null +++ b/src/config/NERO/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NERO +#define MANUFACTURER_ID BKMN + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 + diff --git a/src/config/NEUTRONRCF407/config.h b/src/config/NEUTRONRCF407/config.h new file mode 100644 index 0000000000..cae12c7b4e --- /dev/null +++ b/src/config/NEUTRONRCF407/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME NEUTRONRCF407 +#define MANUFACTURER_ID NERC + diff --git a/src/config/NEUTRONRCF411AIO/config.h b/src/config/NEUTRONRCF411AIO/config.h new file mode 100644 index 0000000000..b2f2cb4195 --- /dev/null +++ b/src/config/NEUTRONRCF411AIO/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME NEUTRONRCF411AIO +#define MANUFACTURER_ID NERC + +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/NEUTRONRCF411SX1280/config.h b/src/config/NEUTRONRCF411SX1280/config.h new file mode 100644 index 0000000000..50b5a13223 --- /dev/null +++ b/src/config/NEUTRONRCF411SX1280/config.h @@ -0,0 +1,57 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME NEUTRONRCF411SX1280 +#define MANUFACTURER_ID NERC + +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_ACC_SPI_ICM42605 +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PB9 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC13 +#define RX_SPI_BIND PB2 +#define RX_SPI_LED PC15 + diff --git a/src/config/NEUTRONRCF722AIO/config.h b/src/config/NEUTRONRCF722AIO/config.h new file mode 100644 index 0000000000..8a6ecade83 --- /dev/null +++ b/src/config/NEUTRONRCF722AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NEUTRONRCF722AIO +#define MANUFACTURER_ID NERC + diff --git a/src/config/NEUTRONRCF7AIO/config.h b/src/config/NEUTRONRCF7AIO/config.h new file mode 100644 index 0000000000..15ff89afaf --- /dev/null +++ b/src/config/NEUTRONRCF7AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME NEUTRONRCF7AIO +#define MANUFACTURER_ID NERC + diff --git a/src/config/NEUTRONRCG4AIO/config.h b/src/config/NEUTRONRCG4AIO/config.h new file mode 100644 index 0000000000..a29a117a4b --- /dev/null +++ b/src/config/NEUTRONRCG4AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32G47X + +#define BOARD_NAME NEUTRONRCG4AIO +#define MANUFACTURER_ID NERC + diff --git a/src/config/NEUTRONRCH743AIO/config.h b/src/config/NEUTRONRCH743AIO/config.h new file mode 100644 index 0000000000..c8b66648ce --- /dev/null +++ b/src/config/NEUTRONRCH743AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME NEUTRONRCH743AIO +#define MANUFACTURER_ID NERC + diff --git a/src/config/NEUTRONRCH7BT/config.h b/src/config/NEUTRONRCH7BT/config.h new file mode 100644 index 0000000000..4b24ccdb19 --- /dev/null +++ b/src/config/NEUTRONRCH7BT/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME NEUTRONRCH7BT +#define MANUFACTURER_ID NERC + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25M02G +#define USE_MAX7456 + diff --git a/src/config/NIDICI_F4/config.h b/src/config/NIDICI_F4/config.h new file mode 100644 index 0000000000..04a5041793 --- /dev/null +++ b/src/config/NIDICI_F4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME NIDICI_F4 +#define MANUFACTURER_ID HNEC + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/NOX/config.h b/src/config/NOX/config.h new file mode 100644 index 0000000000..2fc0b9db60 --- /dev/null +++ b/src/config/NOX/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME NOX +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/NUCLEOF722/config.h b/src/config/NUCLEOF722/config.h new file mode 100644 index 0000000000..6c46d5c0c3 --- /dev/null +++ b/src/config/NUCLEOF722/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME NUCLEOF722 +#define MANUFACTURER_ID STMI + +#define USE_GYRO +#define USE_GYRO_MPU6050 +#define USE_ACC +#define USE_ACC_MPU6050 + diff --git a/src/config/OMNIBUSF4/config.h b/src/config/OMNIBUSF4/config.h new file mode 100644 index 0000000000..106f3ee986 --- /dev/null +++ b/src/config/OMNIBUSF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNIBUSF4 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/OMNIBUSF4FW/config.h b/src/config/OMNIBUSF4FW/config.h new file mode 100644 index 0000000000..b1ca5fa46a --- /dev/null +++ b/src/config/OMNIBUSF4FW/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNIBUSF4FW +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/OMNIBUSF4NANOV7/config.h b/src/config/OMNIBUSF4NANOV7/config.h new file mode 100644 index 0000000000..02d61ae2f3 --- /dev/null +++ b/src/config/OMNIBUSF4NANOV7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNIBUSF4NANOV7 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/OMNIBUSF4SD/config.h b/src/config/OMNIBUSF4SD/config.h new file mode 100644 index 0000000000..6f7292fc9d --- /dev/null +++ b/src/config/OMNIBUSF4SD/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNIBUSF4SD +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/OMNIBUSF4V6/config.h b/src/config/OMNIBUSF4V6/config.h new file mode 100644 index 0000000000..a993749251 --- /dev/null +++ b/src/config/OMNIBUSF4V6/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNIBUSF4V6 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/OMNIBUSF7/config.h b/src/config/OMNIBUSF7/config.h new file mode 100644 index 0000000000..d70abc6994 --- /dev/null +++ b/src/config/OMNIBUSF7/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME OMNIBUSF7 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/OMNIBUSF7NANOV7/config.h b/src/config/OMNIBUSF7NANOV7/config.h new file mode 100644 index 0000000000..473044172a --- /dev/null +++ b/src/config/OMNIBUSF7NANOV7/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME OMNIBUSF7NANOV7 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/OMNIBUSF7V2/config.h b/src/config/OMNIBUSF7V2/config.h new file mode 100644 index 0000000000..b8b79c34a4 --- /dev/null +++ b/src/config/OMNIBUSF7V2/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME OMNIBUSF7V2 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/OMNINXT4/config.h b/src/config/OMNINXT4/config.h new file mode 100644 index 0000000000..0f892f7c21 --- /dev/null +++ b/src/config/OMNINXT4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME OMNINXT4 +#define MANUFACTURER_ID AIRB + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_SPI_LPS +#define USE_MAX7456 + diff --git a/src/config/OMNINXT7/config.h b/src/config/OMNINXT7/config.h new file mode 100644 index 0000000000..de7cf8c0b6 --- /dev/null +++ b/src/config/OMNINXT7/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME OMNINXT7 +#define MANUFACTURER_ID AIRB + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_LPS +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/PIRXF4/config.h b/src/config/PIRXF4/config.h new file mode 100644 index 0000000000..aafb123c00 --- /dev/null +++ b/src/config/PIRXF4/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME PIRXF4 +#define MANUFACTURER_ID LEGA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/PLUMF4/config.h b/src/config/PLUMF4/config.h new file mode 100644 index 0000000000..0e7ad7ffb0 --- /dev/null +++ b/src/config/PLUMF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME PLUMF4 +#define MANUFACTURER_ID FLLF + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/PODIUMF4/config.h b/src/config/PODIUMF4/config.h new file mode 100644 index 0000000000..61a4d23761 --- /dev/null +++ b/src/config/PODIUMF4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME PODIUMF4 +#define MANUFACTURER_ID LEGA + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/PODRACERAIO/config.h b/src/config/PODRACERAIO/config.h new file mode 100644 index 0000000000..6ae36bb328 --- /dev/null +++ b/src/config/PODRACERAIO/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME PODRACERAIO +#define MANUFACTURER_ID TEBS + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/PYRODRONEF4/config.h b/src/config/PYRODRONEF4/config.h new file mode 100644 index 0000000000..85bff832a4 --- /dev/null +++ b/src/config/PYRODRONEF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME PYRODRONEF4 +#define MANUFACTURER_ID PYDR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/PYRODRONEF4PDB/config.h b/src/config/PYRODRONEF4PDB/config.h new file mode 100644 index 0000000000..0d5866f364 --- /dev/null +++ b/src/config/PYRODRONEF4PDB/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME PYRODRONEF4PDB +#define MANUFACTURER_ID PYDR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/PYRODRONEF7/config.h b/src/config/PYRODRONEF7/config.h new file mode 100644 index 0000000000..0ce71e03f3 --- /dev/null +++ b/src/config/PYRODRONEF7/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME PYRODRONEF7 +#define MANUFACTURER_ID PYDR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/REVO/config.h b/src/config/REVO/config.h new file mode 100644 index 0000000000..b6f578df36 --- /dev/null +++ b/src/config/REVO/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME REVO +#define MANUFACTURER_ID OPEN + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 + diff --git a/src/config/REVOLT/config.h b/src/config/REVOLT/config.h new file mode 100644 index 0000000000..497411a289 --- /dev/null +++ b/src/config/REVOLT/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME REVOLT +#define MANUFACTURER_ID FLON + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 + diff --git a/src/config/REVOLTOSD/config.h b/src/config/REVOLTOSD/config.h new file mode 100644 index 0000000000..e4730ced58 --- /dev/null +++ b/src/config/REVOLTOSD/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME REVOLTOSD +#define MANUFACTURER_ID FLON + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/REVONANO/config.h b/src/config/REVONANO/config.h new file mode 100644 index 0000000000..f96f80374f --- /dev/null +++ b/src/config/REVONANO/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME REVONANO +#define MANUFACTURER_ID OPEN + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 + diff --git a/src/config/RUSHCORE7/config.h b/src/config/RUSHCORE7/config.h new file mode 100644 index 0000000000..ef0942578b --- /dev/null +++ b/src/config/RUSHCORE7/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME RUSHCORE7 +#define MANUFACTURER_ID RUSH + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/RUSRACE_F4/config.h b/src/config/RUSRACE_F4/config.h new file mode 100644 index 0000000000..42eb0d31a5 --- /dev/null +++ b/src/config/RUSRACE_F4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME RUSRACE_F4 +#define MANUFACTURER_ID CUST + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/RUSRACE_F7/config.h b/src/config/RUSRACE_F7/config.h new file mode 100644 index 0000000000..7c27bd8d20 --- /dev/null +++ b/src/config/RUSRACE_F7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME RUSRACE_F7 +#define MANUFACTURER_ID CUST + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SIRMIXALOT/config.h b/src/config/SIRMIXALOT/config.h new file mode 100644 index 0000000000..1bb0ad04b9 --- /dev/null +++ b/src/config/SIRMIXALOT/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SIRMIXALOT +#define MANUFACTURER_ID CUST + diff --git a/src/config/SKYSTARSF405/config.h b/src/config/SKYSTARSF405/config.h new file mode 100644 index 0000000000..10a45823b6 --- /dev/null +++ b/src/config/SKYSTARSF405/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SKYSTARSF405 +#define MANUFACTURER_ID SKST + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SKYSTARSF405AIO/config.h b/src/config/SKYSTARSF405AIO/config.h new file mode 100644 index 0000000000..24076ffab8 --- /dev/null +++ b/src/config/SKYSTARSF405AIO/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SKYSTARSF405AIO +#define MANUFACTURER_ID SKST + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SKYSTARSF411/config.h b/src/config/SKYSTARSF411/config.h new file mode 100644 index 0000000000..de73292178 --- /dev/null +++ b/src/config/SKYSTARSF411/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME SKYSTARSF411 +#define MANUFACTURER_ID SKST + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SKYSTARSF7HD/config.h b/src/config/SKYSTARSF7HD/config.h new file mode 100644 index 0000000000..3a2e2244b0 --- /dev/null +++ b/src/config/SKYSTARSF7HD/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SKYSTARSF7HD +#define MANUFACTURER_ID SKST + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SKYSTARSF7HDPRO/config.h b/src/config/SKYSTARSF7HDPRO/config.h new file mode 100644 index 0000000000..bfa5da44fc --- /dev/null +++ b/src/config/SKYSTARSF7HDPRO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SKYSTARSF7HDPRO +#define MANUFACTURER_ID SKST + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SKYSTARSH7HD/config.h b/src/config/SKYSTARSH7HD/config.h new file mode 100644 index 0000000000..97c4bd565b --- /dev/null +++ b/src/config/SKYSTARSH7HD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME SKYSTARSH7HD +#define MANUFACTURER_ID SKST + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_BMP280 diff --git a/src/config/SKYZONEF405/config.h b/src/config/SKYZONEF405/config.h new file mode 100644 index 0000000000..4deff17439 --- /dev/null +++ b/src/config/SKYZONEF405/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SKYZONEF405 +#define MANUFACTURER_ID SKZO + +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/SOULF4/config.h b/src/config/SOULF4/config.h new file mode 100644 index 0000000000..dc7dceefb5 --- /dev/null +++ b/src/config/SOULF4/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SOULF4 +#define MANUFACTURER_ID DERC + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_BARO_BMP085 +#define USE_BARO_MS5611 +#define USE_MAX7456 + diff --git a/src/config/SPARKY2/config.h b/src/config/SPARKY2/config.h new file mode 100644 index 0000000000..a15dd34c42 --- /dev/null +++ b/src/config/SPARKY2/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPARKY2 +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU9250 +#define USE_ACC +#define USE_ACC_SPI_MPU9250 +#define USE_BARO +#define USE_BARO_MS5611 + diff --git a/src/config/SPCMAKERF411/config.h b/src/config/SPCMAKERF411/config.h new file mode 100644 index 0000000000..47d6570f78 --- /dev/null +++ b/src/config/SPCMAKERF411/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME SPCMAKERF411 +#define MANUFACTURER_ID SPCM + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SPEDIXF4/config.h b/src/config/SPEDIXF4/config.h new file mode 100644 index 0000000000..df5fa6303a --- /dev/null +++ b/src/config/SPEDIXF4/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPEDIXF4 +#define MANUFACTURER_ID SPDX + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC_SPI_ICM20689 +#define USE_FLASH +#define USE_FLASH_M25P16 + +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF4/config.h b/src/config/SPEEDYBEEF4/config.h new file mode 100644 index 0000000000..daa09c29d7 --- /dev/null +++ b/src/config/SPEEDYBEEF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPEEDYBEEF4 +#define MANUFACTURER_ID SPBE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF405V3/config.h b/src/config/SPEEDYBEEF405V3/config.h new file mode 100644 index 0000000000..aaa7661a2d --- /dev/null +++ b/src/config/SPEEDYBEEF405V3/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPEEDYBEEF405V3 +#define MANUFACTURER_ID SPBE + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_SDCARD +#define USE_BARO +#define USE_BARO_DPS310 + diff --git a/src/config/SPEEDYBEEF7/config.h b/src/config/SPEEDYBEEF7/config.h new file mode 100644 index 0000000000..1f90075407 --- /dev/null +++ b/src/config/SPEEDYBEEF7/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPEEDYBEEF7 +#define MANUFACTURER_ID SPBE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20689 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF7MINI/config.h b/src/config/SPEEDYBEEF7MINI/config.h new file mode 100644 index 0000000000..453ab8834f --- /dev/null +++ b/src/config/SPEEDYBEEF7MINI/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPEEDYBEEF7MINI +#define MANUFACTURER_ID SPBE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF7MINIV2/config.h b/src/config/SPEEDYBEEF7MINIV2/config.h new file mode 100644 index 0000000000..9a5e59fef2 --- /dev/null +++ b/src/config/SPEEDYBEEF7MINIV2/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPEEDYBEEF7MINIV2 +#define MANUFACTURER_ID SPBE + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF7V2/config.h b/src/config/SPEEDYBEEF7V2/config.h new file mode 100644 index 0000000000..e040d78099 --- /dev/null +++ b/src/config/SPEEDYBEEF7V2/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPEEDYBEEF7V2 +#define MANUFACTURER_ID SPBE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEEF7V3/config.h b/src/config/SPEEDYBEEF7V3/config.h new file mode 100644 index 0000000000..044fc8dd28 --- /dev/null +++ b/src/config/SPEEDYBEEF7V3/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPEEDYBEEF7V3 +#define MANUFACTURER_ID SPBE + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_SDCARD +#define USE_MAX7456 + diff --git a/src/config/SPEEDYBEE_F745_AIO/config.h b/src/config/SPEEDYBEE_F745_AIO/config.h new file mode 100644 index 0000000000..eb5a6a9c6e --- /dev/null +++ b/src/config/SPEEDYBEE_F745_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F745 + +#define BOARD_NAME SPEEDYBEE_F745_AIO +#define MANUFACTURER_ID SPBE + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/SPRACINGF4EVO/config.h b/src/config/SPRACINGF4EVO/config.h new file mode 100644 index 0000000000..b7f69ef894 --- /dev/null +++ b/src/config/SPRACINGF4EVO/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPRACINGF4EVO +#define MANUFACTURER_ID SPRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_SDCARD + diff --git a/src/config/SPRACINGF4NEO/config.h b/src/config/SPRACINGF4NEO/config.h new file mode 100644 index 0000000000..93237a679f --- /dev/null +++ b/src/config/SPRACINGF4NEO/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SPRACINGF4NEO +#define MANUFACTURER_ID SPRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/SPRACINGF7DUAL/config.h b/src/config/SPRACINGF7DUAL/config.h new file mode 100644 index 0000000000..72f73e006a --- /dev/null +++ b/src/config/SPRACINGF7DUAL/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME SPRACINGF7DUAL +#define MANUFACTURER_ID SPRO + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/SPRACINGH7EXTREME/config.h b/src/config/SPRACINGH7EXTREME/config.h new file mode 100644 index 0000000000..d26c0f7c0b --- /dev/null +++ b/src/config/SPRACINGH7EXTREME/config.h @@ -0,0 +1,131 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H750 + +#define BOARD_NAME SPRACINGH7EXTREME +#define MANUFACTURER_ID SPRO + +#define TARGET_BOARD_IDENTIFIER "SP7E" +#define USBD_PRODUCT_STRING "SPRacingH7EXTREME" + +#define FC_VMA_ADDRESS 0x97CE0000 + +#define EEPROM_SIZE 8192 + +#define USE_SPRACING_PERSISTENT_RTC_WORKAROUND + +#define USE_BUTTONS +#define BUTTON_A_PIN PE4 +#define BUTTON_A_PIN_INVERTED +#define BUTTON_B_PIN PE4 +#define BUTTON_B_PIN_INVERTED + +#define USE_QUADSPI +#define USE_QUADSPI_DEVICE_1 +#define QUADSPI1_SCK_PIN PB2 +#define QUADSPI1_BK1_IO0_PIN PD11 +#define QUADSPI1_BK1_IO1_PIN PD12 +#define QUADSPI1_BK1_IO2_PIN PE2 +#define QUADSPI1_BK1_IO3_PIN PD13 +#define QUADSPI1_BK1_CS_PIN PB10 +#define QUADSPI1_BK2_IO0_PIN PE7 +#define QUADSPI1_BK2_IO1_PIN PE8 +#define QUADSPI1_BK2_IO2_PIN PE9 +#define QUADSPI1_BK2_IO3_PIN PE10 +#define QUADSPI1_BK2_CS_PIN NONE +#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY +#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) + +#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT + +#define FLASH_QUADSPI_INSTANCE QUADSPI + +#define CONFIG_IN_EXTERNAL_FLASH + +#define SDCARD_DETECT_PIN PD10 +#define SDCARD_DETECT_INVERTED +#define SDIO_DEVICE SDIODEV_1 +#define SDIO_USE_4BIT 1 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 + +#define USE_SPI + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PD3 +#define SPI2_MISO_PIN PC2 +#define SPI2_MOSI_PIN PC3 +#define SPI2_NSS_PIN PB12 + +#define USE_SPI_DEVICE_3 +#define SPI3_SCK_PIN PB3 +#define SPI3_MISO_PIN PB4 +#define SPI3_MOSI_PIN PD6 +#define SPI3_NSS_PIN PA15 + +#define USE_SPI_DEVICE_4 +#define SPI4_SCK_PIN PE12 +#define SPI4_MISO_PIN PE13 +#define SPI4_MOSI_PIN PE14 +#define SPI4_NSS_PIN PE11 + +#define USE_USB_ID + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL_PIN PB8 +#define I2C1_SDA_PIN PB9 +#define I2C_DEVICE (I2CDEV_1) + +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define USE_PID_AUDIO + +#define VTX_RTC6705_OPTIONAL + +#define ADC1_DMA_OPT 8 +#define ADC3_DMA_OPT 9 + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP388 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_SDCARD +#define USE_CAMERA_CONTROL +#define USE_MAX7456 + diff --git a/src/config/SPRACINGH7RF/config.h b/src/config/SPRACINGH7RF/config.h new file mode 100644 index 0000000000..7faea31103 --- /dev/null +++ b/src/config/SPRACINGH7RF/config.h @@ -0,0 +1,188 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H730 + +#define BOARD_NAME SPRACINGH7RF +#define MANUFACTURER_ID SPRO + +#define TARGET_BOARD_IDENTIFIER "SP7R" +#define USBD_PRODUCT_STRING "SPRacingH7RF" + +#define FC_VMA_ADDRESS 0x90100000 + +#define EEPROM_SIZE 8192 + +#define USE_SPRACING_PERSISTENT_RTC_WORKAROUND + +#define USE_BUTTONS +#define BUTTON_A_PIN PE4 +#define BUTTON_A_PIN_INVERTED +#define BUTTON_B_PIN PE4 +#define BUTTON_B_PIN_INVERTED + +#define USE_OCTOSPI +#define USE_OCTOSPI_DEVICE_1 + +#define USE_SPI + +#define USE_SPI_DEVICE_2 +#define SPI2_SCK_PIN PD3 +#define SPI2_MISO_PIN PB14 +#define SPI2_MOSI_PIN PB15 +#define SPI2_NSS_PIN PB12 + +#define USE_SPI_DEVICE_6 +#define SPI6_SCK_PIN PB3 +#define SPI6_MISO_PIN PB4 +#define SPI6_MOSI_PIN PB5 +#define SPI6_NSS_PIN PA15 + +#define SX1280_BUSY_PIN PC7 +#define SX1280_DIO1_PIN PC6 +#define SX1280_DIO2_PIN PD4 +#define SX1280_DIO3_PIN NONE + +#define USE_FLASH_MEMORY_MAPPED +#define FLASH_OCTOSPI_INSTANCE OCTOSPI1 +#define CONFIG_IN_MEMORY_MAPPED_FLASH +#define USE_FIRMWARE_PARTITION + +#define SDCARD_DETECT_PIN PC13 +#define SDCARD_DETECT_INVERTED +#define SDIO_DEVICE SDIODEV_1 +#define SDIO_USE_4BIT 1 +#define SDIO_CK_PIN PC12 +#define SDIO_CMD_PIN PD2 +#define SDIO_D0_PIN PC8 +#define SDIO_D1_PIN PC9 +#define SDIO_D2_PIN PC10 +#define SDIO_D3_PIN PC11 + +#define TARGET_IO_PORTA 0xffff +#define TARGET_IO_PORTB (0xffff & ~(BIT(2)|BIT(6))) +#define TARGET_IO_PORTC 0xffff +#define TARGET_IO_PORTD (0xffff & ~(BIT(11)|BIT(12)|BIT(13))) +#define TARGET_IO_PORTE (0xffff & ~(BIT(2)|BIT(7)|BIT(8)|BIT(9)|BIT(10))) +#define TARGET_IO_PORTF 0xffff +#define TARGET_IO_PORTG 0xffff +#define TARGET_IO_PORTH 0xffff + +#define USE_I2C +#define USE_I2C_DEVICE_1 +#define I2C1_SCL_PIN PB8 +#define I2C1_SDA_PIN PB9 + +#define USE_I2C_DEVICE_2 +#define I2C2_SCL_PIN PB10 +#define I2C2_SDA_PIN PB11 + +#define MAG_I2C_INSTANCE (I2CDEV_1) +#define BARO_I2C_INSTANCE (I2CDEV_2) + +#define USE_MPU_DATA_READY_SIGNAL +#define ENSURE_MPU_DATA_READY_IS_LOW + +#define SX1280_BUSY_PIN PC7 +#define SX1280_DIO1_PIN PC6 +#define SX1280_DIO2_PIN PD4 +#define SX1280_DIO3_PIN NONE + +#define SX1280_NRESET_PIN PD10 + +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_SX1280 +#define RX_SPI_INSTANCE SPI2 +#define RX_NSS_PIN SPI2_NSS_PIN +#define RX_SPI_EXTI_PIN SX1280_DIO1_PIN +#define RX_EXPRESSLRS_SPI_RESET_PIN SX1280_NRESET_PIN +#define RX_EXPRESSLRS_SPI_BUSY_PIN SX1280_BUSY_PIN +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM6 + +#define DEFAULT_RX_FEATURE FEATURE_RX_SPI +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS + +#define ADC3_DMA_OPT 10 +#define ADC_INSTANCE ADC3 +#define ADC1_INSTANCE ADC1 +#define ADC3_INSTANCE ADC3 +#define CURRENT_METER_2_ADC_PIN PC0 +#define CURRENT_METER_2_ADC_INSTANCE ADC3 +#define CURRENT_METER_1_ADC_PIN PC1 +#define CURRENT_METER_1_ADC_INSTANCE ADC3 +#define EXTERNAL1_ADC_PIN PC2 +#define EXTERNAL1_ADC_INSTANCE ADC3 +#define VBAT_ADC_PIN PC3 +#define VBAT_ADC_INSTANCE ADC3 +#define VIDEO_IN_ADC_PIN PC5 +#define VIDEO_OUT_ADC_PIN PC4 +#define RSSI_ADC_PIN CURRENT_METER_2_ADC_PIN +#define RSSI_ADC_INSTANCE CURRENT_METER_2_ADC_INSTANCE +#define CURRENT_METER_ADC_PIN CURRENT_METER_1_ADC_PIN +#define CURRENT_METER_ADC_INSTANCE CURRENT_METER_1_ADC_INSTANCE +#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC +#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC + +#define VTX_ENABLE_PIN PC15 +#define PINIO1_PIN VTX_ENABLE_PIN + +#define USE_ACC +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP388 +#define USE_MAG_HMC5883 +#define USE_MAG_QMC5883 +#define USE_FLASH_W25Q128FV +#define USE_SDCARD + +#define USE_OSD +#define SPRACING_PIXEL_OSD_BLACK_PIN PE12 +#define SPRACING_PIXEL_OSD_WHITE_PIN PE13 +#define SPRACING_PIXEL_OSD_MASK_ENABLE_PIN PE14 +#define SPRACING_PIXEL_OSD_WHITE_SOURCE_SELECT_PIN PE15 + +#define SPRACING_PIXEL_OSD_SYNC_IN_PIN PE11 + +#define SPRACING_PIXEL_OSD_SYNC_OUT_PIN PA8 + +#define SPRACING_PIXEL_OSD_WHITE_SOURCE_PIN PA4 + +#define SPRACING_PIXEL_OSD_VIDEO_THRESHOLD_DEBUG_PIN PA5 + +#define SPRACING_PIXEL_OSD_PIXEL_DEBUG_1_PIN PE5 + +#define SPRACING_PIXEL_OSD_PIXEL_DEBUG_2_PIN PE6 + +#define SPRACING_PIXEL_OSD_PIXEL_GATING_DEBUG_PIN PB0 + +#define SPRACING_PIXEL_OSD_PIXEL_BLANKING_DEBUG_PIN PB1 + diff --git a/src/config/STACKX/config.h b/src/config/STACKX/config.h new file mode 100644 index 0000000000..91f889afd2 --- /dev/null +++ b/src/config/STACKX/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME STACKX +#define MANUFACTURER_ID LEGA + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/STM32F411DISCOVERY/config.h b/src/config/STM32F411DISCOVERY/config.h new file mode 100644 index 0000000000..6926b9e2c5 --- /dev/null +++ b/src/config/STM32F411DISCOVERY/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME STM32F411DISCOVERY +#define MANUFACTURER_ID STMI + +#define USE_ACC +#define USE_ACC_LSM303DLHC +#define USE_GYRO +#define USE_GYRO_L3GD20 +#define MPU_I2C_INSTANCE I2CDEV_1 + diff --git a/src/config/STM32F4DISCOVERY/config.h b/src/config/STM32F4DISCOVERY/config.h new file mode 100644 index 0000000000..b9b1cd67a5 --- /dev/null +++ b/src/config/STM32F4DISCOVERY/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME STM32F4DISCOVERY +#define MANUFACTURER_ID STMI + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_SDCARD + diff --git a/src/config/SYNERGYF4/config.h b/src/config/SYNERGYF4/config.h new file mode 100644 index 0000000000..ba3575f646 --- /dev/null +++ b/src/config/SYNERGYF4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME SYNERGYF4 +#define MANUFACTURER_ID KLEE + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/TALONF4V2/config.h b/src/config/TALONF4V2/config.h new file mode 100644 index 0000000000..ca5fbec3e7 --- /dev/null +++ b/src/config/TALONF4V2/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME TALONF4V2 +#define MANUFACTURER_ID HENA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TALONF7DJIHD/config.h b/src/config/TALONF7DJIHD/config.h new file mode 100644 index 0000000000..34c22a9da4 --- /dev/null +++ b/src/config/TALONF7DJIHD/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TALONF7DJIHD +#define MANUFACTURER_ID HENA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TALONF7FUSION/config.h b/src/config/TALONF7FUSION/config.h new file mode 100644 index 0000000000..8a7bf28ce1 --- /dev/null +++ b/src/config/TALONF7FUSION/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TALONF7FUSION +#define MANUFACTURER_ID HENA + +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TALONF7V2/config.h b/src/config/TALONF7V2/config.h new file mode 100644 index 0000000000..7c15b620b6 --- /dev/null +++ b/src/config/TALONF7V2/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TALONF7V2 +#define MANUFACTURER_ID HENA + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TCMMF411/config.h b/src/config/TCMMF411/config.h new file mode 100644 index 0000000000..827036c581 --- /dev/null +++ b/src/config/TCMMF411/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TCMMF411 +#define MANUFACTURER_ID TCMM + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TCMMF7/config.h b/src/config/TCMMF7/config.h new file mode 100644 index 0000000000..621955e04f --- /dev/null +++ b/src/config/TCMMF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TCMMF7 +#define MANUFACTURER_ID TCMM + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/TMH7/config.h b/src/config/TMH7/config.h new file mode 100644 index 0000000000..ef2df28d3f --- /dev/null +++ b/src/config/TMH7/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32H743 + +#define BOARD_NAME TMH7 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMOTORF4/config.h b/src/config/TMOTORF4/config.h new file mode 100644 index 0000000000..1e37ea78c5 --- /dev/null +++ b/src/config/TMOTORF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME TMOTORF4 +#define MANUFACTURER_ID TMTR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_SPI_ICM20602 +#define USE_ACC_SPI_ICM20602 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMOTORF411/config.h b/src/config/TMOTORF411/config.h new file mode 100644 index 0000000000..8415244221 --- /dev/null +++ b/src/config/TMOTORF411/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TMOTORF411 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMOTORF4SX1280/config.h b/src/config/TMOTORF4SX1280/config.h new file mode 100644 index 0000000000..fe55dabf5c --- /dev/null +++ b/src/config/TMOTORF4SX1280/config.h @@ -0,0 +1,50 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TMOTORF4SX1280 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_RX_SPI +#define USE_RX_EXPRESSLRS +#define USE_RX_EXPRESSLRS_TELEMETRY +#define USE_RX_SX1280 +#define RX_CHANNELS_AETR +#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS +#define RX_EXPRESSLRS_TIMER_INSTANCE TIM5 +#define RX_EXPRESSLRS_SPI_RESET_PIN PA8 +#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 +#define RX_SPI_CS PA15 +#define RX_SPI_EXTI PC14 +#define RX_SPI_BIND PB10 +#define RX_SPI_LED PA14 + diff --git a/src/config/TMOTORF7/config.h b/src/config/TMOTORF7/config.h new file mode 100644 index 0000000000..11ff5624d7 --- /dev/null +++ b/src/config/TMOTORF7/config.h @@ -0,0 +1,46 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMOTORF7 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_M25P16 + +#define USE_MAX7456 + diff --git a/src/config/TMOTORF722SE/config.h b/src/config/TMOTORF722SE/config.h new file mode 100644 index 0000000000..bd14e97835 --- /dev/null +++ b/src/config/TMOTORF722SE/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMOTORF722SE +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMOTORF7V2/config.h b/src/config/TMOTORF7V2/config.h new file mode 100644 index 0000000000..47f962a878 --- /dev/null +++ b/src/config/TMOTORF7V2/config.h @@ -0,0 +1,47 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMOTORF7V2 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC_SPI_ICM42688P +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMOTORF7_AIO/config.h b/src/config/TMOTORF7_AIO/config.h new file mode 100644 index 0000000000..43539b6335 --- /dev/null +++ b/src/config/TMOTORF7_AIO/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMOTORF7_AIO +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_FLASH +#define USE_FLASH_M25Q128 +#define USE_MAX7456 + diff --git a/src/config/TMOTORVELOXF7V2/config.h b/src/config/TMOTORVELOXF7V2/config.h new file mode 100644 index 0000000000..355c99fe7d --- /dev/null +++ b/src/config/TMOTORVELOXF7V2/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMOTORVELOXF7V2 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMPACERF7/config.h b/src/config/TMPACERF7/config.h new file mode 100644 index 0000000000..6470937a61 --- /dev/null +++ b/src/config/TMPACERF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMPACERF7 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMPACERF7MINI/config.h b/src/config/TMPACERF7MINI/config.h new file mode 100644 index 0000000000..963be21583 --- /dev/null +++ b/src/config/TMPACERF7MINI/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMPACERF7MINI +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42688P +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMVELOXF411/config.h b/src/config/TMVELOXF411/config.h new file mode 100644 index 0000000000..b056883d4f --- /dev/null +++ b/src/config/TMVELOXF411/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TMVELOXF411 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TMVELOXF7/config.h b/src/config/TMVELOXF7/config.h new file mode 100644 index 0000000000..6b607714d6 --- /dev/null +++ b/src/config/TMVELOXF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TMVELOXF7 +#define MANUFACTURER_ID TMTR + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/TRANSTECF405HD/config.h b/src/config/TRANSTECF405HD/config.h new file mode 100644 index 0000000000..2518d36f7a --- /dev/null +++ b/src/config/TRANSTECF405HD/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME TRANSTECF405HD +#define MANUFACTURER_ID TTRH + diff --git a/src/config/TRANSTECF411/config.h b/src/config/TRANSTECF411/config.h new file mode 100644 index 0000000000..96b1115626 --- /dev/null +++ b/src/config/TRANSTECF411/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TRANSTECF411 +#define MANUFACTURER_ID TTRH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/TRANSTECF411AIO/config.h b/src/config/TRANSTECF411AIO/config.h new file mode 100644 index 0000000000..28e873db6b --- /dev/null +++ b/src/config/TRANSTECF411AIO/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TRANSTECF411AIO +#define MANUFACTURER_ID TTRH + diff --git a/src/config/TRANSTECF411HD/config.h b/src/config/TRANSTECF411HD/config.h new file mode 100644 index 0000000000..b8305fa275 --- /dev/null +++ b/src/config/TRANSTECF411HD/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME TRANSTECF411HD +#define MANUFACTURER_ID TTRH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 + diff --git a/src/config/TRANSTECF7/config.h b/src/config/TRANSTECF7/config.h new file mode 100644 index 0000000000..f839ee61b8 --- /dev/null +++ b/src/config/TRANSTECF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TRANSTECF7 +#define MANUFACTURER_ID TTRH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_ACC_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/TRANSTECF7HD/config.h b/src/config/TRANSTECF7HD/config.h new file mode 100644 index 0000000000..67f889ca04 --- /dev/null +++ b/src/config/TRANSTECF7HD/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME TRANSTECF7HD +#define MANUFACTURER_ID TTRH + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 + diff --git a/src/config/TUNERCF405/config.h b/src/config/TUNERCF405/config.h new file mode 100644 index 0000000000..c5efec60a2 --- /dev/null +++ b/src/config/TUNERCF405/config.h @@ -0,0 +1,39 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME TUNERCF405 +#define MANUFACTURER_ID TURC + +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_GYRO +#define USE_ACC +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 + diff --git a/src/config/UAVPNG030MINI/config.h b/src/config/UAVPNG030MINI/config.h new file mode 100644 index 0000000000..3f9323e001 --- /dev/null +++ b/src/config/UAVPNG030MINI/config.h @@ -0,0 +1,37 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME UAVPNG030MINI +#define MANUFACTURER_ID NGUA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 + diff --git a/src/config/VGOODF722DUAL/config.h b/src/config/VGOODF722DUAL/config.h new file mode 100644 index 0000000000..7bcc621d56 --- /dev/null +++ b/src/config/VGOODF722DUAL/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME VGOODF722DUAL +#define MANUFACTURER_ID VGRC + diff --git a/src/config/VGOODRCF4/config.h b/src/config/VGOODRCF4/config.h new file mode 100644 index 0000000000..9d84d0eedf --- /dev/null +++ b/src/config/VGOODRCF4/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME VGOODRCF4 +#define MANUFACTURER_ID VGRC + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/VGOODRCF405_DJI/config.h b/src/config/VGOODRCF405_DJI/config.h new file mode 100644 index 0000000000..f33cbeec23 --- /dev/null +++ b/src/config/VGOODRCF405_DJI/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME VGOODRCF405_DJI +#define MANUFACTURER_ID VGRC + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/VGOODRCF411_DJI/config.h b/src/config/VGOODRCF411_DJI/config.h new file mode 100644 index 0000000000..ea7c5eed0b --- /dev/null +++ b/src/config/VGOODRCF411_DJI/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME VGOODRCF411_DJI +#define MANUFACTURER_ID VGRC + diff --git a/src/config/VGOODRCF722_DJI/config.h b/src/config/VGOODRCF722_DJI/config.h new file mode 100644 index 0000000000..14bfd2ae82 --- /dev/null +++ b/src/config/VGOODRCF722_DJI/config.h @@ -0,0 +1,32 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME VGOODRCF722_DJI +#define MANUFACTURER_ID VGRC + diff --git a/src/config/VIVAF4AIO/config.h b/src/config/VIVAF4AIO/config.h new file mode 100644 index 0000000000..df5c29bc50 --- /dev/null +++ b/src/config/VIVAF4AIO/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME VIVAF4AIO +#define MANUFACTURER_ID VIVA + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/VRRACE/config.h b/src/config/VRRACE/config.h new file mode 100644 index 0000000000..3c181255c0 --- /dev/null +++ b/src/config/VRRACE/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME VRRACE +#define MANUFACTURER_ID LEGA + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_MAX7456 + diff --git a/src/config/WIZZF7HD/config.h b/src/config/WIZZF7HD/config.h new file mode 100644 index 0000000000..e7697621a1 --- /dev/null +++ b/src/config/WIZZF7HD/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME WIZZF7HD +#define MANUFACTURER_ID WIZZ + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/WORMFC/config.h b/src/config/WORMFC/config.h new file mode 100644 index 0000000000..dd6c8f6e20 --- /dev/null +++ b/src/config/WORMFC/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME WORMFC +#define MANUFACTURER_ID FOSS + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_BARO +#define USE_BARO_SPI_LPS +#define USE_MAX7456 + diff --git a/src/config/XILOF4/config.h b/src/config/XILOF4/config.h new file mode 100644 index 0000000000..2e7f34640a --- /dev/null +++ b/src/config/XILOF4/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME XILOF4 +#define MANUFACTURER_ID GEFP + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 + diff --git a/src/config/XRACERF4/config.h b/src/config/XRACERF4/config.h new file mode 100644 index 0000000000..3738561a64 --- /dev/null +++ b/src/config/XRACERF4/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME XRACERF4 +#define MANUFACTURER_ID FPVM + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6500 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/YUPIF4/config.h b/src/config/YUPIF4/config.h new file mode 100644 index 0000000000..ed06b65a60 --- /dev/null +++ b/src/config/YUPIF4/config.h @@ -0,0 +1,42 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F405 + +#define BOARD_NAME YUPIF4 +#define MANUFACTURER_ID YUPF + +#define USE_GYRO +#define USE_GYRO_FAST_KALMAN +#define USE_GYRO_SPI_MPU6500 +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_MPU6500 +#define USE_ACC_SPI_ICM20689 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/YUPIF7/config.h b/src/config/YUPIF7/config.h new file mode 100644 index 0000000000..a67e440d92 --- /dev/null +++ b/src/config/YUPIF7/config.h @@ -0,0 +1,41 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME YUPIF7 +#define MANUFACTURER_ID YUPF + +#define USE_GYRO +#define USE_GYRO_SPI_ICM20689 +#define USE_ACC +#define USE_ACC_SPI_ICM20689 +#define USE_BARO +#define USE_BARO_MS5611 +#define USE_BARO_BMP280 +#define USE_MAX7456 + diff --git a/src/config/ZEEZF7/config.h b/src/config/ZEEZF7/config.h new file mode 100644 index 0000000000..e8b855db66 --- /dev/null +++ b/src/config/ZEEZF7/config.h @@ -0,0 +1,40 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ZEEZF7 +#define MANUFACTURER_ID ZEEZ + +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_FLASH +#define USE_FLASH_W25N01G +#define USE_MAX7456 + diff --git a/src/config/ZEEZF7V2/config.h b/src/config/ZEEZF7V2/config.h new file mode 100644 index 0000000000..41293ec646 --- /dev/null +++ b/src/config/ZEEZF7V2/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ZEEZF7V2 +#define MANUFACTURER_ID ZEEZ + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_BARO +#define USE_BARO_DPS310 +#define USE_BARO_BMP280 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 + diff --git a/src/config/ZEEZF7V3/config.h b/src/config/ZEEZF7V3/config.h new file mode 100644 index 0000000000..241d17ee19 --- /dev/null +++ b/src/config/ZEEZF7V3/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ZEEZF7V3 +#define MANUFACTURER_ID ZEEZ + +#define USE_GYRO +#define USE_GYRO_SPI_ICM42605 +#define USE_GYRO_SPI_ICM42688P +#define USE_ACC +#define USE_ACC_SPI_ICM42605 +#define USE_ACC_SPI_ICM42688P +#define USE_BARO +#define USE_BARO_BMP388 +#define USE_FLASH +#define USE_FLASH_M25P16 +#define USE_MAX7456 +#define USE_SDCARD + diff --git a/src/config/ZEEZWHOOP/config.h b/src/config/ZEEZWHOOP/config.h new file mode 100644 index 0000000000..b4a2fd33c9 --- /dev/null +++ b/src/config/ZEEZWHOOP/config.h @@ -0,0 +1,38 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME ZEEZWHOOP +#define MANUFACTURER_ID ZEEZ + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_GYRO_SPI_MPU6000 +#define USE_MAX7456 + diff --git a/src/config/ZEUSF4EVO/config.h b/src/config/ZEUSF4EVO/config.h new file mode 100644 index 0000000000..98ea8e4b2e --- /dev/null +++ b/src/config/ZEUSF4EVO/config.h @@ -0,0 +1,43 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME ZEUSF4EVO +#define MANUFACTURER_ID HGLR + +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_MAX7456 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_BARO +#define USE_BARO_BMP280 + diff --git a/src/config/ZEUSF4FR/config.h b/src/config/ZEUSF4FR/config.h new file mode 100644 index 0000000000..a8847ebba1 --- /dev/null +++ b/src/config/ZEUSF4FR/config.h @@ -0,0 +1,45 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F411 + +#define BOARD_NAME ZEUSF4FR +#define MANUFACTURER_ID HGLR + +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_GYRO_SPI_MPU6000 +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_RX_SPI +#define USR_RX_CC2500 +#define USE_BARO +#define USE_BARO_SPI_BMP280 + diff --git a/src/config/ZEUSF722_AIO/config.h b/src/config/ZEUSF722_AIO/config.h new file mode 100644 index 0000000000..993a6c5814 --- /dev/null +++ b/src/config/ZEUSF722_AIO/config.h @@ -0,0 +1,44 @@ +/* + * This file is part of Betaflight. + * + * Betaflight is free software. You can redistribute this software + * and/or modify this software 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. + * + * Betaflight 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 this software. + * + * If not, see . + */ + +/* + This file has been auto generated from unified-targets repo. + + The auto generation is transitional only, please remove this comment once the file is edited. +*/ + +#define FC_TARGET_MCU STM32F7X2 + +#define BOARD_NAME ZEUSF722_AIO +#define MANUFACTURER_ID HGLR + +#define USE_ACC +#define USE_ACC_SPI_MPU6000 +#define USE_GYRO_SPI_MPU6000 +#define USE_GYRO +#define USE_ACCGYRO_BMI270 +#define USE_FLASH +#define USE_FLASH_W25Q128FV +#define USE_MAX7456 +#define USE_BARO +#define USE_BARO_SPI_BMP280 +#define USE_BARO_SPI_DPS310 + diff --git a/src/link/stm32_h723_common.ld b/src/link/stm32_h723_common.ld new file mode 100644 index 0000000000..d10f3d957f --- /dev/null +++ b/src/link/stm32_h723_common.ld @@ -0,0 +1,187 @@ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* Highest address of the user mode stack */ +_estack = ORIGIN(STACKRAM) + LENGTH(STACKRAM); /* end of RAM */ + +/* Base address where the quad spi. */ +__octospi1_start = ORIGIN(OCTOSPI1); +__octospi2_start = ORIGIN(OCTOSPI2); + +/* Generate a link error if heap and stack don't fit into RAM */ +_Min_Heap_Size = 0; /* required amount of heap */ +_Min_Stack_Size = 0x800; /* required amount of stack */ + +/* Define output sections */ +SECTIONS +{ + _isr_vector_table_flash_base = LOADADDR(.isr_vector); + PROVIDE (isr_vector_table_flash_base = _isr_vector_table_flash_base); + + .isr_vector : + { + . = ALIGN(512); + PROVIDE (isr_vector_table_base = .); + KEEP(*(.isr_vector)) /* Startup code */ + . = ALIGN(4); + PROVIDE (isr_vector_table_end = .); + } >VECTAB AT> MAIN + + _ram_isr_vector_table_base = LOADADDR(.ram_isr_vector); + PROVIDE (ram_isr_vector_table_base = _ram_isr_vector_table_base); + + .ram_isr_vector (NOLOAD) : + { + . = ALIGN(512); /* Vector table offset must be multiple of 0x200 */ + PROVIDE (ram_isr_vector_table_base = .); + . += (isr_vector_table_end - isr_vector_table_base); + . = ALIGN(4); + PROVIDE (ram_isr_vector_table_end = .); + } >DTCM_RAM + + /* The program code and other data goes into MAIN */ + .text : + { + . = ALIGN(4); + *(.text) /* .text sections (code) */ + *(.text*) /* .text* sections (code) */ + *(.rodata) /* .rodata sections (constants, strings, etc.) */ + *(.rodata*) /* .rodata* sections (constants, strings, etc.) */ + *(.glue_7) /* glue arm to thumb code */ + *(.glue_7t) /* glue thumb to arm code */ + *(.eh_frame) + + KEEP (*(.init)) + KEEP (*(.fini)) + + . = ALIGN(4); + _etext = .; /* define a global symbols at end of code */ + } >MAIN + + /* Critical program code goes into ITCM RAM */ + /* Copy specific fast-executing code to ITCM RAM */ + tcm_code = LOADADDR(.tcm_code); + .tcm_code : + { + . = ALIGN(4); + tcm_code_start = .; + *(.tcm_code) + *(.tcm_code*) + . = ALIGN(4); + tcm_code_end = .; + } >ITCM_RAM AT >MAIN + + .ARM.extab : + { + *(.ARM.extab* .gnu.linkonce.armextab.*) + } >MAIN + + .ARM : + { + __exidx_start = .; + *(.ARM.exidx*) __exidx_end = .; + } >MAIN + + .pg_registry : + { + PROVIDE_HIDDEN (__pg_registry_start = .); + KEEP (*(.pg_registry)) + KEEP (*(SORT(.pg_registry.*))) + PROVIDE_HIDDEN (__pg_registry_end = .); + } >MAIN + + .pg_resetdata : + { + PROVIDE_HIDDEN (__pg_resetdata_start = .); + KEEP (*(.pg_resetdata)) + PROVIDE_HIDDEN (__pg_resetdata_end = .); + } >MAIN + + /* used by the startup to initialize data */ + _sidata = LOADADDR(.data); + + /* Initialized data sections goes into RAM, load LMA copy after code */ + .data : + { + . = ALIGN(4); + _sdata = .; /* create a global symbol at data start */ + *(.data) /* .data sections */ + *(.data*) /* .data* sections */ + + . = ALIGN(4); + _edata = .; /* define a global symbol at data end */ + } >DTCM_RAM AT >MAIN + + /* Non-critical program code goes into RAM */ + /* Copy specific slow-executing code to RAM */ + ram_code = LOADADDR(.ram_code); + .ram_code : + { + . = ALIGN(4); + ram_code_start = .; + *(.ram_code) + *(.ram_code*) + . = ALIGN(4); + ram_code_end = .; + } >RAM AT >MAIN + + /* Uninitialized data section */ + . = ALIGN(4); + .bss (NOLOAD) : + { + /* This is used by the startup in order to initialize the .bss secion */ + _sbss = .; /* define a global symbol at bss start */ + __bss_start__ = _sbss; + *(.bss) + *(SORT_BY_ALIGNMENT(.bss*)) + *(COMMON) + + . = ALIGN(4); + _ebss = .; /* define a global symbol at bss end */ + __bss_end__ = _ebss; + } >RAM + + /* Uninitialized data section */ + . = ALIGN(4); + .sram2 (NOLOAD) : + { + /* This is used by the startup in order to initialize the .sram2 secion */ + _ssram2 = .; /* define a global symbol at sram2 start */ + __sram2_start__ = _ssram2; + *(.sram2) + *(SORT_BY_ALIGNMENT(.sram2*)) + + . = ALIGN(4); + _esram2 = .; /* define a global symbol at sram2 end */ + __sram2_end__ = _esram2; + } >RAM + + /* used during startup to initialized fastram_data */ + _sfastram_idata = LOADADDR(.fastram_data); + + /* Initialized FAST_DATA section for unsuspecting developers */ + .fastram_data : + { + . = ALIGN(4); + _sfastram_data = .; /* create a global symbol at data start */ + *(.fastram_data) /* .data sections */ + *(.fastram_data*) /* .data* sections */ + + . = ALIGN(4); + _efastram_data = .; /* define a global symbol at data end */ + } >FASTRAM AT >MAIN + + . = ALIGN(4); + .fastram_bss (NOLOAD) : + { + _sfastram_bss = .; + __fastram_bss_start__ = _sfastram_bss; + *(.fastram_bss) + *(SORT_BY_ALIGNMENT(.fastram_bss*)) + + . = ALIGN(4); + _efastram_bss = .; + __fastram_bss_end__ = _efastram_bss; + } >FASTRAM +} diff --git a/src/link/stm32_h723_common_post.ld b/src/link/stm32_h723_common_post.ld new file mode 100644 index 0000000000..89b4224806 --- /dev/null +++ b/src/link/stm32_h723_common_post.ld @@ -0,0 +1,44 @@ +SECTIONS +{ + .persistent_data (NOLOAD) : + { + __persistent_data_start__ = .; + *(.persistent_data) + . = ALIGN(4); + __persistent_data_end__ = .; + } >RAM + + /* User_heap_stack section, used to check that there is enough RAM left */ + _heap_stack_end = ORIGIN(STACKRAM)+LENGTH(STACKRAM) - 8; /* 8 bytes to allow for alignment */ + _heap_stack_begin = _heap_stack_end - _Min_Stack_Size - _Min_Heap_Size; + . = _heap_stack_begin; + ._user_heap_stack : + { + . = ALIGN(4); + PROVIDE ( end = . ); + PROVIDE ( _end = . ); + . = . + _Min_Heap_Size; + . = . + _Min_Stack_Size; + . = ALIGN(4); + } >STACKRAM = 0xa5 + + /* MEMORY_bank1 section, code must be located here explicitly */ + /* Example: extern int foo(void) __attribute__ ((section (".mb1text"))); */ + .memory_b1_text : + { + *(.mb1text) /* .mb1text sections (code) */ + *(.mb1text*) /* .mb1text* sections (code) */ + *(.mb1rodata) /* read-only data (constants) */ + *(.mb1rodata*) + } >MEMORY_B1 + + /* Remove information from the standard libraries */ + /DISCARD/ : + { + libc.a ( * ) + libm.a ( * ) + libgcc.a ( * ) + } + + .ARM.attributes 0 : { *(.ARM.attributes) } +} diff --git a/src/link/stm32_h730_common.ld b/src/link/stm32_h730_common.ld index a485128aa8..d10f3d957f 100644 --- a/src/link/stm32_h730_common.ld +++ b/src/link/stm32_h730_common.ld @@ -113,6 +113,19 @@ SECTIONS _edata = .; /* define a global symbol at data end */ } >DTCM_RAM AT >MAIN + /* Non-critical program code goes into RAM */ + /* Copy specific slow-executing code to RAM */ + ram_code = LOADADDR(.ram_code); + .ram_code : + { + . = ALIGN(4); + ram_code_start = .; + *(.ram_code) + *(.ram_code*) + . = ALIGN(4); + ram_code_end = .; + } >RAM AT >MAIN + /* Uninitialized data section */ . = ALIGN(4); .bss (NOLOAD) : diff --git a/src/link/stm32_ram_h723_exst.ld b/src/link/stm32_ram_h723_exst.ld new file mode 100644 index 0000000000..c9f0bcd874 --- /dev/null +++ b/src/link/stm32_ram_h723_exst.ld @@ -0,0 +1,143 @@ +/* +***************************************************************************** +** +** File : stm32_ram_h723_exst.ld +** +** Abstract : Linker script for STM32H723xG Device with +** 320K AXI-SRAM mapped onto AXI bus on D1 domain + (Shared AXI/I-TCM 192KB is all configured as AXI-SRAM) +** 16K SRAM1 mapped on D2 domain +** 16K SRAM2 mapped on D2 domain +** 16K SRAM mapped on D3 domain +** 64K ITCM +** 128K DTCM +** +***************************************************************************** +*/ + +/* Entry Point */ +ENTRY(Reset_Handler) + +/* +0x00000000 to 0x0000FFFF 64K ITCM +0x20000000 to 0x2001FFFF 128K DTCM, main RAM +0x24000000 to 0x2404FFFF 320K AXI SRAM, D1 domain +0x30000000 to 0x30003FFF 16K SRAM1, D2 domain +0x30004000 to 0x30007FFF 16K SRAM2, D2 domain +0x38000000 to 0x38003FFF 16K SRAM4, D3 domain, unused +0x38800000 to 0x38800FFF 4K BACKUP SRAM, Backup domain, unused + +0x08000000 to 0x0801FFFF 128K isr vector, startup code, firmware, no config! // FLASH_Sector_0 +*/ + +/* + +For H7 EXFL (External Flash) targets a binary is built that is placed on an external device. +The bootloader will enable the memory mapped mode on the CPU which allows code to run directly from +the external flash device. + +The bootloader then executes code at the CODE_RAM address. The address of CODE_RAM is fixed to 0x90010000 +and must not be changed. + +The initial CODE_RAM is sized at 1MB. + +*/ + +/* see .exst section below */ +_exst_hash_size = 64; + +/* Specify the memory areas */ +MEMORY +{ + ITCM_RAM (rwx) : ORIGIN = 0x00000000, LENGTH = 64K + DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 128K + RAM (rwx) : ORIGIN = 0x24000000, LENGTH = 128K + 192K /* 128K AXI SRAM + 192K ITCM & AXI = 320K */ + + D2_RAM (rwx) : ORIGIN = 0x30000000, LENGTH = 32K /* SRAM1 16K + SRAM2 16K */ + D3_RAM (rwx) : ORIGIN = 0x38000000, LENGTH = 16K /* SRAM4 16K */ + + BACKUP_SRAM (rwx) : ORIGIN = 0x38800000, LENGTH = 4K + + MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K + + OCTOSPI2 (rx) : ORIGIN = 0x70000000, LENGTH = 256M + OCTOSPI1 (rx) : ORIGIN = 0x90000000, LENGTH = 256M + OCTOSPI1_CODE (rx): ORIGIN = ORIGIN(OCTOSPI1) + 1M, LENGTH = 1M - _exst_hash_size /* hard coded start address, as required by SPRACINGH7 boot loader, don't change! */ + EXST_HASH (rx) : ORIGIN = ORIGIN(OCTOSPI1_CODE) + LENGTH(OCTOSPI1_CODE), LENGTH = _exst_hash_size +} + +REGION_ALIAS("STACKRAM", DTCM_RAM) +REGION_ALIAS("FASTRAM", DTCM_RAM) +REGION_ALIAS("MAIN", OCTOSPI1_CODE) + +REGION_ALIAS("VECTAB", MAIN) + +INCLUDE "stm32_h723_common.ld" + +SECTIONS +{ + /* used during startup to initialized dmaram_data */ + _sdmaram_idata = LOADADDR(.dmaram_data); + + . = ALIGN(32); + .dmaram_data : + { + PROVIDE(dmaram_start = .); + _sdmaram = .; + _dmaram_start__ = _sdmaram; + _sdmaram_data = .; /* create a global symbol at data start */ + *(.dmaram_data) /* .data sections */ + *(.dmaram_data*) /* .data* sections */ + . = ALIGN(32); + _edmaram_data = .; /* define a global symbol at data end */ + } >RAM AT >MAIN + + . = ALIGN(32); + .dmaram_bss (NOLOAD) : + { + _sdmaram_bss = .; + __dmaram_bss_start__ = _sdmaram_bss; + *(.dmaram_bss) + *(SORT_BY_ALIGNMENT(.dmaram_bss*)) + . = ALIGN(32); + _edmaram_bss = .; + __dmaram_bss_end__ = _edmaram_bss; + } >RAM + + . = ALIGN(32); + .DMA_RAM (NOLOAD) : + { + KEEP(*(.DMA_RAM)) + PROVIDE(dmaram_end = .); + _edmaram = .; + _dmaram_end__ = _edmaram; + } >RAM + + .DMA_RW_D2 (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarw_start = .); + _sdmarw = .; + _dmarw_start__ = _sdmarw; + KEEP(*(.DMA_RW)) + PROVIDE(dmarw_end = .); + _edmarw = .; + _dmarw_end__ = _edmarw; + } >D2_RAM + + .DMA_RW_AXI (NOLOAD) : + { + . = ALIGN(32); + PROVIDE(dmarwaxi_start = .); + _sdmarwaxi = .; + _dmarwaxi_start__ = _sdmarwaxi; + KEEP(*(.DMA_RW_AXI)) + PROVIDE(dmarwaxi_end = .); + _edmarwaxi = .; + _dmarwaxi_end__ = _edmarwaxi; + } >RAM +} + +INCLUDE "stm32_h723_common_post.ld" +INCLUDE "stm32_ram_h723_exst_post.ld" + diff --git a/src/link/stm32_ram_h723_exst_post.ld b/src/link/stm32_ram_h723_exst_post.ld new file mode 100644 index 0000000000..97ed6c28f3 --- /dev/null +++ b/src/link/stm32_ram_h723_exst_post.ld @@ -0,0 +1,29 @@ +SECTIONS +{ + /* Create space for a hash. Currently an MD5 has is used, which is 16 */ + /* bytes long. however the last 64 bytes are RESERVED for hash related */ + .exst_hash : + { + /* 64 bytes is the size of an MD5 hashing block size. */ + . = ORIGIN(EXST_HASH); + + BYTE(0x00); /* block format */ + BYTE(0x00); /* Checksum method, 0x00 = MD5 hash */ + BYTE(0x00); /* Reserved */ + BYTE(0x00); /* Reserved */ + + /* Fill the last 60 bytes with data, including an empty hash aligned */ + + /* to the last 16 bytes. */ + FILL(0x00000000); /* Reserved */ + + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH) - 16; + __md5_hash_address__ = .; + LONG(0x00000000); + LONG(0x00000000); + LONG(0x00000000); + LONG(0x00000000); + . = ORIGIN(EXST_HASH) + LENGTH(EXST_HASH); + __firmware_end__ = .; + } >EXST_HASH +} diff --git a/src/main/blackbox/blackbox.c b/src/main/blackbox/blackbox.c index 514ad49584..294dae9893 100644 --- a/src/main/blackbox/blackbox.c +++ b/src/main/blackbox/blackbox.c @@ -1535,12 +1535,14 @@ static bool blackboxWriteSysinfo(void) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_RETURN_ALT, "%d", gpsRescueConfig()->initialAltitudeM) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_RETURN_SPEED, "%d", gpsRescueConfig()->rescueGroundspeed) - BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_PITCH_ANGLE_MAX, "%d", gpsRescueConfig()->angle) + BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE, "%d", gpsRescueConfig()->maxRescueAngle) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_ROLL_MIX, "%d", gpsRescueConfig()->rollMix) + BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF, "%d", gpsRescueConfig()->pitchCutoffHz) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCENT_DIST, "%d", gpsRescueConfig()->descentDistanceM) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DESCEND_RATE, "%d", gpsRescueConfig()->descendRate) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_LANDING_ALT, "%d", gpsRescueConfig()->targetLandingAltitudeM) + BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD, "%d", gpsRescueConfig()->disarmThreshold) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_THROTTLE_MIN, "%d", gpsRescueConfig()->throttleMin) BLACKBOX_PRINT_HEADER_LINE(PARAM_NAME_GPS_RESCUE_THROTTLE_MAX, "%d", gpsRescueConfig()->throttleMax) diff --git a/src/main/build/debug.c b/src/main/build/debug.c index f2f6196172..deb5a9dbb2 100644 --- a/src/main/build/debug.c +++ b/src/main/build/debug.c @@ -108,5 +108,5 @@ const char * const debugModeNames[DEBUG_COUNT] = { "VTX_MSP", "GPS_DOP", "FAILSAFE", - "RPM_LIMITER", + "DSHOT_TELEMETRY_COUNTS" }; diff --git a/src/main/build/debug.h b/src/main/build/debug.h index 2c06404dee..1413badcb4 100644 --- a/src/main/build/debug.h +++ b/src/main/build/debug.h @@ -106,7 +106,7 @@ typedef enum { DEBUG_VTX_MSP, DEBUG_GPS_DOP, DEBUG_FAILSAFE, - DEBUG_RPM_LIMITER, + DEBUG_DSHOT_TELEMETRY_COUNTS, DEBUG_COUNT } debugType_e; diff --git a/src/main/build/version.h b/src/main/build/version.h index 65f93eae1a..4f45c31020 100644 --- a/src/main/build/version.h +++ b/src/main/build/version.h @@ -26,7 +26,7 @@ #define FC_FIRMWARE_IDENTIFIER "BTFL" #define FC_VERSION_MAJOR 4 // increment when a major release is made (big new feature, etc) #define FC_VERSION_MINOR 4 // increment when a minor release is made (small new feature, change etc) -#define FC_VERSION_PATCH_LEVEL 0 // increment when a bug is fixed +#define FC_VERSION_PATCH_LEVEL 2 // increment when a bug is fixed #define FC_VERSION_STRING STR(FC_VERSION_MAJOR) "." STR(FC_VERSION_MINOR) "." STR(FC_VERSION_PATCH_LEVEL) diff --git a/src/main/cli/cli.c b/src/main/cli/cli.c index 95208d7c59..6031adb437 100644 --- a/src/main/cli/cli.c +++ b/src/main/cli/cli.c @@ -2582,8 +2582,8 @@ static void cliFlashRead(const char *cmdName, char *cmdline) cliPrintLinefeed(); } } -#endif -#endif +#endif // USE_FLASH_TOOLS +#endif // USE_FLASHFS #ifdef USE_VTX_CONTROL static void printVtx(dumpFlags_t dumpMask, const vtxConfig_t *vtxConfig, const vtxConfig_t *vtxConfigDefault, const char *headingStr) diff --git a/src/main/cli/settings.c b/src/main/cli/settings.c index 5c652beef1..2788f81b19 100644 --- a/src/main/cli/settings.c +++ b/src/main/cli/settings.c @@ -1044,12 +1044,14 @@ const clivalue_t valueTable[] = { { PARAM_NAME_GPS_RESCUE_RETURN_ALT, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 2, 255 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, initialAltitudeM) }, { PARAM_NAME_GPS_RESCUE_RETURN_SPEED, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 3000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, rescueGroundspeed) }, - { PARAM_NAME_GPS_RESCUE_PITCH_ANGLE_MAX, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 60 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, angle) }, + { PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 80 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, maxRescueAngle) }, { PARAM_NAME_GPS_RESCUE_ROLL_MIX, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 0, 250 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, rollMix) }, + { PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 10, 255 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, pitchCutoffHz) }, { PARAM_NAME_GPS_RESCUE_DESCENT_DIST, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 5, 500 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, descentDistanceM) }, { PARAM_NAME_GPS_RESCUE_DESCEND_RATE, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 25, 500 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, descendRate) }, { PARAM_NAME_GPS_RESCUE_LANDING_ALT, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 15 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, targetLandingAltitudeM) }, + { PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD, VAR_UINT8 | MASTER_VALUE, .config.minmaxUnsigned = { 1, 250 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, disarmThreshold) }, { PARAM_NAME_GPS_RESCUE_THROTTLE_MIN, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMin) }, { PARAM_NAME_GPS_RESCUE_THROTTLE_MAX, VAR_UINT16 | MASTER_VALUE, .config.minmaxUnsigned = { 1000, 2000 }, PG_GPS_RESCUE, offsetof(gpsRescueConfig_t, throttleMax) }, @@ -1207,7 +1209,7 @@ const clivalue_t valueTable[] = { #ifdef USE_FEEDFORWARD { PARAM_NAME_FEEDFORWARD_TRANSITION, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 0, 100 }, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_transition) }, { PARAM_NAME_FEEDFORWARD_AVERAGING, VAR_UINT8 | PROFILE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_FEEDFORWARD_AVERAGING }, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_averaging) }, - { PARAM_NAME_FEEDFORWARD_SMOOTH_FACTOR, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = {0, 75}, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_smooth_factor) }, + { PARAM_NAME_FEEDFORWARD_SMOOTH_FACTOR, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = {0, 95}, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_smooth_factor) }, { PARAM_NAME_FEEDFORWARD_JITTER_FACTOR, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = {0, 20}, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_jitter_factor) }, { PARAM_NAME_FEEDFORWARD_BOOST, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = { 0, 50 }, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_boost) }, { PARAM_NAME_FEEDFORWARD_MAX_RATE_LIMIT, VAR_UINT8 | PROFILE_VALUE, .config.minmaxUnsigned = {0, 150}, PG_PID_PROFILE, offsetof(pidProfile_t, feedforward_max_rate_limit) }, @@ -1619,7 +1621,7 @@ const clivalue_t valueTable[] = { { "usb_msc_pin_pullup", VAR_UINT8 | HARDWARE_VALUE | MODE_LOOKUP, .config.lookup = { TABLE_OFF_ON }, PG_USB_CONFIG, offsetof(usbDev_t, mscButtonUsePullup) }, #endif // PG_FLASH_CONFIG -#ifdef USE_FLASH_CHIP +#ifdef USE_FLASH_SPI { "flash_spi_bus", VAR_UINT8 | HARDWARE_VALUE, .config.minmaxUnsigned = { 0, SPIDEV_COUNT }, PG_FLASH_CONFIG, offsetof(flashConfig_t, spiDevice) }, #endif // RCDEVICE diff --git a/src/main/cms/cms.c b/src/main/cms/cms.c index 3517912224..c4578ffd30 100644 --- a/src/main/cms/cms.c +++ b/src/main/cms/cms.c @@ -161,9 +161,10 @@ bool cmsDisplayPortSelect(displayPort_t *instance) // 13 cols x 9 rows, top row printed as a Bold Heading // Needs the "smallScreen" adaptions -#define CMS_MAX_ROWS 16 +#define CMS_MAX_ROWS 31 #define NORMAL_SCREEN_MIN_COLS 18 // Less is a small screen +#define NORMAL_SCREEN_MAX_COLS 30 // More is a large screen static bool smallScreen; static uint8_t leftMenuColumn; static uint8_t rightMenuColumn; @@ -389,7 +390,7 @@ static int cmsDrawMenuItemValue(displayPort_t *pDisplay, char *buff, uint8_t row #else colpos = smallScreen ? rightMenuColumn - maxSize : rightMenuColumn; #endif - cnt = cmsDisplayWrite(pDisplay, colpos, row, DISPLAYPORT_ATTR_NORMAL, buff); + cnt = cmsDisplayWrite(pDisplay, colpos, row, DISPLAYPORT_SEVERITY_NORMAL, buff); return cnt; } @@ -590,7 +591,7 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t case OME_Label: if (IS_PRINTVALUE(*flags) && p->data) { // A label with optional string, immediately following text - cnt = cmsDisplayWrite(pDisplay, leftMenuColumn + 1 + (uint8_t)strlen(p->text), row, DISPLAYPORT_ATTR_NORMAL, p->data); + cnt = cmsDisplayWrite(pDisplay, leftMenuColumn + 1 + (uint8_t)strlen(p->text), row, DISPLAYPORT_SEVERITY_NORMAL, p->data); CLR_PRINTVALUE(*flags); } break; @@ -606,9 +607,9 @@ static int cmsDrawMenuEntry(displayPort_t *pDisplay, const OSD_Entry *p, uint8_t #ifdef CMS_MENU_DEBUG // Shouldn't happen. Notify creator of this menu content #ifdef CMS_OSD_RIGHT_ALIGNED_VALUES - cnt = cmsDisplayWrite(pDisplay, rightMenuColumn - 6, row, DISPLAYPORT_ATTR_NORMAL, "BADENT"); + cnt = cmsDisplayWrite(pDisplay, rightMenuColumn - 6, row, DISPLAYPORT_SEVERITY_NORMAL, "BADENT"); #else - cnt = cmsDisplayWrite(pDisplay, rightMenuColumn, row, DISPLAYPORT_ATTR_NORMAL, "BADENT"); + cnt = cmsDisplayWrite(pDisplay, rightMenuColumn, row, DISPLAYPORT_SEVERITY_NORMAL, "BADENT"); #endif #endif break; @@ -747,7 +748,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) #endif if (pDisplay->cursorRow >= 0 && currentCtx.cursorRow != pDisplay->cursorRow) { - room -= cmsDisplayWrite(pDisplay, leftMenuColumn, top + pDisplay->cursorRow * linesPerMenuItem, DISPLAYPORT_ATTR_NORMAL, " "); + room -= cmsDisplayWrite(pDisplay, leftMenuColumn, top + pDisplay->cursorRow * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, " "); } if (room < 30) { @@ -755,7 +756,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) } if (pDisplay->cursorRow != currentCtx.cursorRow) { - room -= cmsDisplayWrite(pDisplay, leftMenuColumn, top + currentCtx.cursorRow * linesPerMenuItem, DISPLAYPORT_ATTR_NORMAL, ">"); + room -= cmsDisplayWrite(pDisplay, leftMenuColumn, top + currentCtx.cursorRow * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, ">"); pDisplay->cursorRow = currentCtx.cursorRow; } @@ -777,7 +778,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) if (IS_PRINTLABEL(runtimeEntryFlags[i])) { uint8_t coloff = leftMenuColumn; coloff += ((p->flags & OSD_MENU_ELEMENT_MASK) == OME_Label) ? 0 : 1; - room -= cmsDisplayWrite(pDisplay, coloff, top + i * linesPerMenuItem, DISPLAYPORT_ATTR_NORMAL, p->text); + room -= cmsDisplayWrite(pDisplay, coloff, top + i * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, p->text); CLR_PRINTLABEL(runtimeEntryFlags[i]); if (room < 30) { return; @@ -787,7 +788,7 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) // Highlight values overridden by sliders if (rowSliderOverride(p->flags)) { - displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_ATTR_NORMAL, 'S'); + displayWriteChar(pDisplay, leftMenuColumn - 1, top + i * linesPerMenuItem, DISPLAYPORT_SEVERITY_NORMAL, 'S'); } // Print values @@ -810,12 +811,12 @@ static void cmsDrawMenu(displayPort_t *pDisplay, uint32_t currentTimeUs) // simple text device and use the '^' (carat) and 'V' for arrow approximations. if (displayWasCleared && leftMenuColumn > 0) { // make sure there's room to draw the symbol if (currentCtx.page > 0) { - const uint8_t symbol = displaySupportsOsdSymbols(pDisplay) ? SYM_ARROW_NORTH : '^'; - displayWriteChar(pDisplay, leftMenuColumn - 1, top, DISPLAYPORT_ATTR_NORMAL, symbol); + const uint8_t symbol = displaySupportsOsdSymbols(pDisplay) ? SYM_ARROW_SMALL_UP : '^'; + displayWriteChar(pDisplay, leftMenuColumn - 1, top, DISPLAYPORT_SEVERITY_NORMAL, symbol); } if (currentCtx.page < pageCount - 1) { - const uint8_t symbol = displaySupportsOsdSymbols(pDisplay) ? SYM_ARROW_SOUTH : 'V'; - displayWriteChar(pDisplay, leftMenuColumn - 1, top + pageMaxRow, DISPLAYPORT_ATTR_NORMAL, symbol); + const uint8_t symbol = displaySupportsOsdSymbols(pDisplay) ? SYM_ARROW_SMALL_DOWN : 'v'; + displayWriteChar(pDisplay, leftMenuColumn - 1, top + pageMaxRow, DISPLAYPORT_SEVERITY_NORMAL, symbol); } } @@ -936,12 +937,21 @@ void cmsMenuOpen(void) } else { smallScreen = false; linesPerMenuItem = 1; - leftMenuColumn = (pCurrentDisplay->cols / 2) - 13; + if (pCurrentDisplay->cols <= NORMAL_SCREEN_MAX_COLS) { + leftMenuColumn = 2; #ifdef CMS_OSD_RIGHT_ALIGNED_VALUES - rightMenuColumn = (pCurrentDisplay->cols / 2) + 13; + rightMenuColumn = pCurrentDisplay->cols - 2; #else - rightMenuColumn = pCurrentDisplay->cols - CMS_DRAW_BUFFER_LEN; + rightMenuColumn = pCurrentDisplay->cols - CMS_DRAW_BUFFER_LEN; #endif + } else { + leftMenuColumn = (pCurrentDisplay->cols / 2) - 13; +#ifdef CMS_OSD_RIGHT_ALIGNED_VALUES + rightMenuColumn = (pCurrentDisplay->cols / 2) + 13; +#else + rightMenuColumn = pCurrentDisplay->cols - CMS_DRAW_BUFFER_LEN; +#endif + } maxMenuItems = pCurrentDisplay->rows - 2; } @@ -1004,7 +1014,7 @@ const void *cmsMenuExit(displayPort_t *pDisplay, const void *ptr) if ((exitType == CMS_EXIT_SAVEREBOOT) || (exitType == CMS_POPUP_SAVEREBOOT) || (exitType == CMS_POPUP_EXITREBOOT)) { displayClearScreen(pDisplay, DISPLAY_CLEAR_WAIT); - cmsDisplayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_NORMAL, "REBOOTING..."); + cmsDisplayWrite(pDisplay, 5, 3, DISPLAYPORT_SEVERITY_NORMAL, "REBOOTING..."); // Flush display displayRedraw(pDisplay); diff --git a/src/main/cms/cms_menu_blackbox.c b/src/main/cms/cms_menu_blackbox.c index 6548eca960..7f7e384679 100644 --- a/src/main/cms/cms_menu_blackbox.c +++ b/src/main/cms/cms_menu_blackbox.c @@ -170,7 +170,7 @@ static const void *cmsx_EraseFlash(displayPort_t *pDisplay, const void *ptr) } displayClearScreen(pDisplay, DISPLAY_CLEAR_WAIT); - displayWrite(pDisplay, 5, 3, DISPLAYPORT_ATTR_INFO, "ERASING FLASH..."); + displayWrite(pDisplay, 5, 3, DISPLAYPORT_SEVERITY_INFO, "ERASING FLASH..."); displayRedraw(pDisplay); flashfsEraseCompletely(); diff --git a/src/main/cms/cms_menu_gps_rescue.c b/src/main/cms/cms_menu_gps_rescue.c index a68ac9f564..d3350e1b9f 100644 --- a/src/main/cms/cms_menu_gps_rescue.c +++ b/src/main/cms/cms_menu_gps_rescue.c @@ -63,6 +63,7 @@ static uint8_t gpsRescueConfig_throttleP, gpsRescueConfig_throttleI, gpsRescueCo static uint8_t gpsRescueConfig_yawP; static uint8_t gpsRescueConfig_velP, gpsRescueConfig_velI, gpsRescueConfig_velD; +static uint8_t gpsRescueConfig_pitchCutoffHz; static const void *cms_menuGpsRescuePidOnEnter(displayPort_t *pDisp) { @@ -78,6 +79,7 @@ static const void *cms_menuGpsRescuePidOnEnter(displayPort_t *pDisp) gpsRescueConfig_velI = gpsRescueConfig()->velI; gpsRescueConfig_velD = gpsRescueConfig()->velD; + gpsRescueConfig_pitchCutoffHz = gpsRescueConfig()->pitchCutoffHz; return NULL; } @@ -96,6 +98,8 @@ static const void *cms_menuGpsRescuePidOnExit(displayPort_t *pDisp, const OSD_En gpsRescueConfigMutable()->velI = gpsRescueConfig_velI; gpsRescueConfigMutable()->velD = gpsRescueConfig_velD; + gpsRescueConfigMutable()->pitchCutoffHz = gpsRescueConfig_pitchCutoffHz; + return NULL; } @@ -113,6 +117,8 @@ const OSD_Entry cms_menuGpsRescuePidEntries[] = { "VELOCITY I", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_velI, 0, 255, 1 } }, { "VELOCITY D", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_velD, 0, 255, 1 } }, + { "SMOOTHING", OME_UINT8 | REBOOT_REQUIRED, NULL, &(OSD_UINT8_t){ &gpsRescueConfig_pitchCutoffHz, 10, 255, 1 } }, + {"BACK", OME_Back, NULL, NULL}, {NULL, OME_END, NULL, NULL} }; @@ -139,7 +145,7 @@ static const void *cmsx_menuGpsRescueOnEnter(displayPort_t *pDisp) gpsRescueConfig_initialAltitudeM = gpsRescueConfig()->initialAltitudeM; gpsRescueConfig_rescueGroundspeed = gpsRescueConfig()->rescueGroundspeed; - gpsRescueConfig_angle = gpsRescueConfig()->angle; + gpsRescueConfig_angle = gpsRescueConfig()->maxRescueAngle; gpsRescueConfig_descentDistanceM = gpsRescueConfig()->descentDistanceM; gpsRescueConfig_descendRate = gpsRescueConfig()->descendRate; @@ -167,7 +173,7 @@ static const void *cmsx_menuGpsRescueOnExit(displayPort_t *pDisp, const OSD_Entr gpsRescueConfigMutable()->initialAltitudeM = gpsRescueConfig_initialAltitudeM; gpsRescueConfigMutable()->rescueGroundspeed = gpsRescueConfig_rescueGroundspeed; - gpsRescueConfigMutable()->angle = gpsRescueConfig_angle; + gpsRescueConfigMutable()->maxRescueAngle = gpsRescueConfig_angle; gpsRescueConfigMutable()->descentDistanceM = gpsRescueConfig_descentDistanceM; gpsRescueConfigMutable()->descendRate = gpsRescueConfig_descendRate; diff --git a/src/main/cms/cms_menu_imu.c b/src/main/cms/cms_menu_imu.c index 9bd7c6cfff..c42675aec4 100644 --- a/src/main/cms/cms_menu_imu.c +++ b/src/main/cms/cms_menu_imu.c @@ -661,7 +661,7 @@ static const OSD_Entry cmsx_menuProfileOtherEntries[] = { #ifdef USE_FEEDFORWARD { "FF TRANSITION", OME_FLOAT, NULL, &(OSD_FLOAT_t) { &cmsx_feedforward_transition, 0, 100, 1, 10 } }, { "FF AVERAGING", OME_TAB, NULL, &(OSD_TAB_t) { &cmsx_feedforward_averaging, 4, lookupTableFeedforwardAveraging} }, - { "FF SMOOTHNESS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_smooth_factor, 0, 75, 1 } }, + { "FF SMOOTHNESS", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_smooth_factor, 0, 95, 1 } }, { "FF JITTER", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_jitter_factor, 0, 20, 1 } }, { "FF BOOST", OME_UINT8, NULL, &(OSD_UINT8_t) { &cmsx_feedforward_boost, 0, 50, 1 } }, #endif diff --git a/src/main/common/sdft.c b/src/main/common/sdft.c index 67c39f52ff..c10bbc341f 100644 --- a/src/main/common/sdft.c +++ b/src/main/common/sdft.c @@ -55,7 +55,7 @@ void sdftInit(sdft_t *sdft, const int startBin, const int endBin, const int numB sdft->endBin = constrain(endBin, sdft->startBin, SDFT_BIN_COUNT - 1); sdft->numBatches = MAX(numBatches, 1); - sdft->batchSize = (sdft->endBin - sdft->startBin) / sdft->numBatches + 1; // batchSize = ceil(numBins / numBatches) + sdft->batchSize = (sdft->endBin - sdft->startBin + 1) / sdft->numBatches; for (int i = 0; i < SDFT_SAMPLE_SIZE; i++) { sdft->samples[i] = 0.0f; @@ -183,7 +183,7 @@ static FAST_CODE void applySqrt(const sdft_t *sdft, float *data) } -// Needed for proper windowing at the edges of startBin and endBin +// Needed for proper windowing at the edges of active range static FAST_CODE void updateEdges(sdft_t *sdft, const float value, const int batchIdx) { // First bin outside of lower range diff --git a/src/main/config/config.c b/src/main/config/config.c index eb5931eb71..1aa4e9220e 100644 --- a/src/main/config/config.c +++ b/src/main/config/config.c @@ -630,8 +630,8 @@ void validateAndFixGyroConfig(void) // check for looptime restrictions based on motor protocol. Motor times have safety margin float motorUpdateRestriction; -#if defined(STM32F411xE) - /* If bidirectional DSHOT is being used on an F411 then force DSHOT300. The motor update restrictions then applied +#if defined(STM32F4)|| defined(STM32G4) + /* If bidirectional DSHOT is being used on an F4 or G4 then force DSHOT300. The motor update restrictions then applied * will automatically consider the loop time and adjust pid_process_denom appropriately */ if (motorConfig()->dev.useDshotTelemetry && (motorConfig()->dev.motorPwmProtocol == PWM_TYPE_DSHOT600)) { diff --git a/src/main/config/config_eeprom.c b/src/main/config/config_eeprom.c index d9adb982ea..1e166cab7b 100644 --- a/src/main/config/config_eeprom.c +++ b/src/main/config/config_eeprom.c @@ -83,8 +83,8 @@ typedef struct { uint32_t word; } PG_PACKED packingTest_t; -#if defined(CONFIG_IN_EXTERNAL_FLASH) -bool loadEEPROMFromExternalFlash(void) +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) +MMFLASH_CODE bool loadEEPROMFromExternalFlash(void) { const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG); const flashGeometry_t *flashGeometry = flashGetGeometry(); @@ -95,7 +95,9 @@ bool loadEEPROMFromExternalFlash(void) int bytesRead = 0; bool success = false; - +#ifdef CONFIG_IN_MEMORY_MAPPED_FLASH + flashMemoryMappedModeDisable(); +#endif do { bytesRead = flashReadBytes(flashStartAddress + totalBytesRead, &eepromData[totalBytesRead], EEPROM_SIZE - totalBytesRead); if (bytesRead > 0) { @@ -103,9 +105,55 @@ bool loadEEPROMFromExternalFlash(void) success = (totalBytesRead == EEPROM_SIZE); } } while (!success && bytesRead > 0); +#ifdef CONFIG_IN_MEMORY_MAPPED_FLASH + flashMemoryMappedModeEnable(); +#endif return success; } + +#ifdef CONFIG_IN_MEMORY_MAPPED_FLASH +MMFLASH_CODE_NOINLINE void saveEEPROMToMemoryMappedFlash(void) +{ + const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG); + const flashGeometry_t *flashGeometry = flashGetGeometry(); + + uint32_t flashSectorSize = flashGeometry->sectorSize; + uint32_t flashPageSize = flashGeometry->pageSize; + + uint32_t flashStartAddress = flashPartition->startSector * flashGeometry->sectorSize; + + uint32_t bytesRemaining = EEPROM_SIZE; + uint32_t offset = 0; + + flashMemoryMappedModeDisable(); + + do { + uint32_t flashAddress = flashStartAddress + offset; + + uint32_t bytesToWrite = bytesRemaining; + if (bytesToWrite > flashPageSize) { + bytesToWrite = flashPageSize; + } + + bool onSectorBoundary = flashAddress % flashSectorSize == 0; + if (onSectorBoundary) { + flashEraseSector(flashAddress); + } + + flashPageProgram(flashAddress, (uint8_t *)&eepromData[offset], bytesToWrite, NULL); + + bytesRemaining -= bytesToWrite; + offset += bytesToWrite; + } while (bytesRemaining > 0); + + flashWaitForReady(); + + flashMemoryMappedModeEnable(); +} +#endif + + #elif defined(CONFIG_IN_SDCARD) enum { @@ -255,7 +303,7 @@ void initEEPROM(void) #if defined(CONFIG_IN_FILE) loadEEPROMFromFile(); -#elif defined(CONFIG_IN_EXTERNAL_FLASH) +#elif defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) bool eepromLoaded = loadEEPROMFromExternalFlash(); if (!eepromLoaded) { // Flash read failed - just die now @@ -336,7 +384,7 @@ uint16_t getEEPROMConfigSize(void) size_t getEEPROMStorageSize(void) { -#if defined(CONFIG_IN_EXTERNAL_FLASH) +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) const flashPartition_t *flashPartition = flashPartitionFindByType(FLASH_PARTITION_TYPE_CONFIG); return FLASH_PARTITION_SECTOR_COUNT(flashPartition) * flashGetGeometry()->sectorSize; @@ -464,7 +512,7 @@ void writeConfigToEEPROM(void) if (writeSettingsToEEPROM()) { success = true; -#ifdef CONFIG_IN_EXTERNAL_FLASH +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) // copy it back from flash to the in-memory buffer. success = loadEEPROMFromExternalFlash(); #endif diff --git a/src/main/config/config_streamer.c b/src/main/config/config_streamer.c index b66c1ba793..0d4ef55faf 100644 --- a/src/main/config/config_streamer.c +++ b/src/main/config/config_streamer.c @@ -36,7 +36,7 @@ uint8_t eepromData[EEPROM_SIZE]; #endif -#if (defined(STM32H750xx) || defined(STM32H730xx)) && !(defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD)) +#if (defined(STM32H750xx) || defined(STM32H730xx)) && !(defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) || defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD)) #error "The configured MCU only has one flash page which contains the bootloader, no spare flash pages available, use external storage for persistent config or ram for target testing" #endif // @todo this is not strictly correct for F4/F7, where sector sizes are variable @@ -400,7 +400,7 @@ static int write_word(config_streamer_t *c, config_streamer_buffer_align_type_t flashPageProgramContinue(buffers, bufferSizes, 1); -#elif defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD) +#elif defined(CONFIG_IN_RAM) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) if (c->address == (uintptr_t)&eepromData[0]) { memset(eepromData, 0, sizeof(eepromData)); } @@ -541,11 +541,13 @@ int config_streamer_finish(config_streamer_t *c) { if (c->unlocked) { #if defined(CONFIG_IN_SDCARD) - bool saveEEPROMToSDCard(void); // XXX forward declaration to avoid circular dependency between config_streamer / config_eeprom + bool saveEEPROMToSDCard(void); // forward declaration to avoid circular dependency between config_streamer / config_eeprom saveEEPROMToSDCard(); - // TODO overwrite the data in the file on the SD card. #elif defined(CONFIG_IN_EXTERNAL_FLASH) flashFlush(); +#elif defined(CONFIG_IN_MEMORY_MAPPED_FLASH) + void saveEEPROMToMemoryMappedFlash(void); // forward declaration to avoid circular dependency between config_streamer / config_eeprom + saveEEPROMToMemoryMappedFlash(); #elif defined(CONFIG_IN_RAM) // NOP #elif defined(CONFIG_IN_FILE) diff --git a/src/main/config/config_streamer.h b/src/main/config/config_streamer.h index 20b3861a2a..9868008998 100644 --- a/src/main/config/config_streamer.h +++ b/src/main/config/config_streamer.h @@ -26,7 +26,7 @@ // Streams data out to the EEPROM, padding to the write size as // needed, and updating the checksum as it goes. -#ifdef CONFIG_IN_EXTERNAL_FLASH +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) #define CONFIG_STREAMER_BUFFER_SIZE 8 // Must not be greater than the smallest flash page size of all compiled-in flash devices. typedef uint32_t config_streamer_buffer_align_type_t; #elif defined(STM32H743xx) || defined(STM32H750xx) || defined(STM32H723xx) || defined(STM32H725xx) diff --git a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c index 54d3f8e478..a93027a2ad 100644 --- a/src/main/drivers/accgyro/accgyro_spi_icm426xx.c +++ b/src/main/drivers/accgyro/accgyro_spi_icm426xx.c @@ -48,9 +48,17 @@ // 24 MHz max SPI frequency #define ICM426XX_MAX_SPI_CLK_HZ 24000000 -#define ICM426XX_RA_PWR_MGMT0 0x4E +#define ICM426XX_RA_REG_BANK_SEL 0x76 +#define ICM426XX_BANK_SELECT0 0x00 +#define ICM426XX_BANK_SELECT1 0x01 +#define ICM426XX_BANK_SELECT2 0x02 +#define ICM426XX_BANK_SELECT3 0x03 +#define ICM426XX_BANK_SELECT4 0x04 + +#define ICM426XX_RA_PWR_MGMT0 0x4E // User Bank 0 #define ICM426XX_PWR_MGMT0_ACCEL_MODE_LN (3 << 0) #define ICM426XX_PWR_MGMT0_GYRO_MODE_LN (3 << 2) +#define ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF ((0 << 0) | (0 << 2)) #define ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF (0 << 5) #define ICM426XX_PWR_MGMT0_TEMP_DISABLE_ON (1 << 5) @@ -58,22 +66,22 @@ #define ICM426XX_RA_ACCEL_CONFIG0 0x50 // --- Registers for gyro and acc Anti-Alias Filter --------- -#define ICM426XX_RA_GYRO_CONFIG_STATIC3 0x0C -#define ICM426XX_RA_GYRO_CONFIG_STATIC4 0x0D -#define ICM426XX_RA_GYRO_CONFIG_STATIC5 0x0E -#define ICM426XX_RA_ACCEL_CONFIG_STATIC2 0x03 -#define ICM426XX_RA_ACCEL_CONFIG_STATIC3 0x04 -#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 +#define ICM426XX_RA_GYRO_CONFIG_STATIC3 0x0C // User Bank 1 +#define ICM426XX_RA_GYRO_CONFIG_STATIC4 0x0D // User Bank 1 +#define ICM426XX_RA_GYRO_CONFIG_STATIC5 0x0E // User Bank 1 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC2 0x03 // User Bank 2 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC3 0x04 // User Bank 2 +#define ICM426XX_RA_ACCEL_CONFIG_STATIC4 0x05 // User Bank 2 // --- Register & setting for gyro and acc UI Filter -------- -#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 -#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (14 << 4) -#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (14 << 0) +#define ICM426XX_RA_GYRO_ACCEL_CONFIG0 0x52 // User Bank 0 +#define ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY (15 << 4) +#define ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY (15 << 0) // ---------------------------------------------------------- -#define ICM426XX_RA_GYRO_DATA_X1 0x25 -#define ICM426XX_RA_ACCEL_DATA_X1 0x1F +#define ICM426XX_RA_GYRO_DATA_X1 0x25 // User Bank 0 +#define ICM426XX_RA_ACCEL_DATA_X1 0x1F // User Bank 0 -#define ICM426XX_RA_INT_CONFIG 0x14 +#define ICM426XX_RA_INT_CONFIG 0x14 // User Bank 0 #define ICM426XX_INT1_MODE_PULSED (0 << 2) #define ICM426XX_INT1_MODE_LATCHED (1 << 2) #define ICM426XX_INT1_DRIVE_CIRCUIT_OD (0 << 1) @@ -81,13 +89,13 @@ #define ICM426XX_INT1_POLARITY_ACTIVE_LOW (0 << 0) #define ICM426XX_INT1_POLARITY_ACTIVE_HIGH (1 << 0) -#define ICM426XX_RA_INT_CONFIG0 0x63 +#define ICM426XX_RA_INT_CONFIG0 0x63 // User Bank 0 #define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR ((0 << 5) || (0 << 4)) #define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_DUPLICATE ((0 << 5) || (0 << 4)) // duplicate settings in datasheet, Rev 1.2. #define ICM426XX_UI_DRDY_INT_CLEAR_ON_F1BR ((1 << 5) || (0 << 4)) #define ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR_AND_F1BR ((1 << 5) || (1 << 4)) -#define ICM426XX_RA_INT_CONFIG1 0x64 +#define ICM426XX_RA_INT_CONFIG1 0x64 // User Bank 0 #define ICM426XX_INT_ASYNC_RESET_BIT 4 #define ICM426XX_INT_TDEASSERT_DISABLE_BIT 5 #define ICM426XX_INT_TDEASSERT_ENABLED (0 << ICM426XX_INT_TDEASSERT_DISABLE_BIT) @@ -96,7 +104,7 @@ #define ICM426XX_INT_TPULSE_DURATION_100 (0 << ICM426XX_INT_TPULSE_DURATION_BIT) #define ICM426XX_INT_TPULSE_DURATION_8 (1 << ICM426XX_INT_TPULSE_DURATION_BIT) -#define ICM426XX_RA_INT_SOURCE0 0x65 +#define ICM426XX_RA_INT_SOURCE0 0x65 // User Bank 0 #define ICM426XX_UI_DRDY_INT1_EN_DISABLED (0 << 3) #define ICM426XX_UI_DRDY_INT1_EN_ENABLED (1 << 3) @@ -130,14 +138,23 @@ static uint8_t odrLUT[ODR_CONFIG_COUNT] = { // see GYRO_ODR in section 5.6 [ODR_CONFIG_1K] = 6, }; -// Possible gyro Anti-Alias Filter (AAF) cutoffs -static aafConfig_t aafLUT[AAF_CONFIG_COUNT] = { // see table in section 5.3 +// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P +static aafConfig_t aafLUT42688[AAF_CONFIG_COUNT] = { // see table in section 5.3 [AAF_CONFIG_258HZ] = { 6, 36, 10 }, [AAF_CONFIG_536HZ] = { 12, 144, 8 }, [AAF_CONFIG_997HZ] = { 21, 440, 6 }, [AAF_CONFIG_1962HZ] = { 37, 1376, 4 }, }; +// Possible gyro Anti-Alias Filter (AAF) cutoffs for ICM-42688P +// actual cutoff differs slightly from those of the 42688P +static aafConfig_t aafLUT42605[AAF_CONFIG_COUNT] = { // see table in section 5.3 + [AAF_CONFIG_258HZ] = { 21, 440, 6 }, // actually 249 Hz + [AAF_CONFIG_536HZ] = { 39, 1536, 4 }, // actually 524 Hz + [AAF_CONFIG_997HZ] = { 63, 3968, 3 }, // actually 995 Hz + [AAF_CONFIG_1962HZ] = { 63, 3968, 3 }, // 995 Hz is the max cutoff on the 42605 +}; + uint8_t icm426xxSpiDetect(const extDevice_t *dev) { spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, 0x00); @@ -191,7 +208,24 @@ bool icm426xxSpiAccDetect(accDev_t *acc) return true; } -static aafConfig_t getGyroAafConfig(void); +static aafConfig_t getGyroAafConfig(const mpuSensor_e, const aafConfig_e); + +static void turnGyroAccOff(const extDevice_t *dev) +{ + spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_GYRO_ACCEL_MODE_OFF); +} + +// Turn on gyro and acc on in Low Noise mode +static void turnGyroAccOn(const extDevice_t *dev) +{ + spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF | ICM426XX_PWR_MGMT0_ACCEL_MODE_LN | ICM426XX_PWR_MGMT0_GYRO_MODE_LN); + delay(1); +} + +static void setUserBank(const extDevice_t *dev, const uint8_t user_bank) +{ + spiWriteReg(dev, ICM426XX_RA_REG_BANK_SEL, user_bank & 7); +} void icm426xxGyroInit(gyroDev_t *gyro) { @@ -203,8 +237,45 @@ void icm426xxGyroInit(gyroDev_t *gyro) gyro->accDataReg = ICM426XX_RA_ACCEL_DATA_X1; gyro->gyroDataReg = ICM426XX_RA_GYRO_DATA_X1; - spiWriteReg(dev, ICM426XX_RA_PWR_MGMT0, ICM426XX_PWR_MGMT0_TEMP_DISABLE_OFF | ICM426XX_PWR_MGMT0_ACCEL_MODE_LN | ICM426XX_PWR_MGMT0_GYRO_MODE_LN); - delay(15); + // Turn off ACC and GYRO so they can be configured + // See section 12.9 in ICM-42688-P datasheet v1.7 + setUserBank(dev, ICM426XX_BANK_SELECT0); + turnGyroAccOff(dev); + + // Configure gyro Anti-Alias Filter (see section 5.3 "ANTI-ALIAS FILTER") + const mpuSensor_e gyroModel = gyro->mpuDetectionResult.sensor; + aafConfig_t aafConfig = getGyroAafConfig(gyroModel, gyroConfig()->gyro_hardware_lpf); + setUserBank(dev, ICM426XX_BANK_SELECT1); + spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC3, aafConfig.delt); + spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC4, aafConfig.deltSqr & 0xFF); + spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC5, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); + + // Configure acc Anti-Alias Filter for 1kHz sample rate (see tasks.c) + aafConfig = getGyroAafConfig(gyroModel, AAF_CONFIG_258HZ); + setUserBank(dev, ICM426XX_BANK_SELECT2); + spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC2, aafConfig.delt << 1); + spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC3, aafConfig.deltSqr & 0xFF); + spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC4, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); + + // Configure gyro and acc UI Filters + setUserBank(dev, ICM426XX_BANK_SELECT0); + spiWriteReg(dev, ICM426XX_RA_GYRO_ACCEL_CONFIG0, ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY | ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY); + + // Configure interrupt pin + spiWriteReg(dev, ICM426XX_RA_INT_CONFIG, ICM426XX_INT1_MODE_PULSED | ICM426XX_INT1_DRIVE_CIRCUIT_PP | ICM426XX_INT1_POLARITY_ACTIVE_HIGH); + spiWriteReg(dev, ICM426XX_RA_INT_CONFIG0, ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR); + + spiWriteReg(dev, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED); + + uint8_t intConfig1Value = spiReadRegMsk(dev, ICM426XX_RA_INT_CONFIG1); + // Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation" + intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT); + intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED); + + spiWriteReg(dev, ICM426XX_RA_INT_CONFIG1, intConfig1Value); + + // Turn on gyro and acc on again so ODR and FSR can be configured + turnGyroAccOn(dev); // Get desired output data rate uint8_t odrConfig; @@ -223,33 +294,6 @@ void icm426xxGyroInit(gyroDev_t *gyro) STATIC_ASSERT(INV_FSR_16G == 3, "INV_FSR_16G must be 3 to generate correct value"); spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG0, (3 - INV_FSR_16G) << 5 | (odrConfig & 0x0F)); delay(15); - - // Configure gyro Anti-Alias Filter (see section 5.3 "ANTI-ALIAS FILTER") - aafConfig_t aafConfig = getGyroAafConfig(); - spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC3, aafConfig.delt); - spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC4, aafConfig.deltSqr & 0xFF); - spiWriteReg(dev, ICM426XX_RA_GYRO_CONFIG_STATIC5, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); - - // Configure acc Anti-Alias Filter for 1kHz sample rate (see tasks.c) - aafConfig = aafLUT[AAF_CONFIG_258HZ]; - spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC2, aafConfig.delt << 1); - spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC3, aafConfig.deltSqr & 0xFF); - spiWriteReg(dev, ICM426XX_RA_ACCEL_CONFIG_STATIC4, (aafConfig.deltSqr >> 8) | (aafConfig.bitshift << 4)); - - // Configure gyro and acc UI Filters - spiWriteReg(dev, ICM426XX_RA_GYRO_ACCEL_CONFIG0, ICM426XX_ACCEL_UI_FILT_BW_LOW_LATENCY | ICM426XX_GYRO_UI_FILT_BW_LOW_LATENCY); - - spiWriteReg(dev, ICM426XX_RA_INT_CONFIG, ICM426XX_INT1_MODE_PULSED | ICM426XX_INT1_DRIVE_CIRCUIT_PP | ICM426XX_INT1_POLARITY_ACTIVE_HIGH); - spiWriteReg(dev, ICM426XX_RA_INT_CONFIG0, ICM426XX_UI_DRDY_INT_CLEAR_ON_SBR); - - spiWriteReg(dev, ICM426XX_RA_INT_SOURCE0, ICM426XX_UI_DRDY_INT1_EN_ENABLED); - - uint8_t intConfig1Value = spiReadRegMsk(dev, ICM426XX_RA_INT_CONFIG1); - // Datasheet says: "User should change setting to 0 from default setting of 1, for proper INT1 and INT2 pin operation" - intConfig1Value &= ~(1 << ICM426XX_INT_ASYNC_RESET_BIT); - intConfig1Value |= (ICM426XX_INT_TPULSE_DURATION_8 | ICM426XX_INT_TDEASSERT_DISABLED); - - spiWriteReg(dev, ICM426XX_RA_INT_CONFIG1, intConfig1Value); } bool icm426xxSpiGyroDetect(gyroDev_t *gyro) @@ -271,21 +315,37 @@ bool icm426xxSpiGyroDetect(gyroDev_t *gyro) return true; } -static aafConfig_t getGyroAafConfig(void) +static aafConfig_t getGyroAafConfig(const mpuSensor_e gyroModel, const aafConfig_e config) { - switch (gyroConfig()->gyro_hardware_lpf) { - case GYRO_HARDWARE_LPF_NORMAL: - return aafLUT[AAF_CONFIG_258HZ]; - case GYRO_HARDWARE_LPF_OPTION_1: - return aafLUT[AAF_CONFIG_536HZ]; - case GYRO_HARDWARE_LPF_OPTION_2: - return aafLUT[AAF_CONFIG_997HZ]; -#ifdef USE_GYRO_DLPF_EXPERIMENTAL - case GYRO_HARDWARE_LPF_EXPERIMENTAL: - return aafLUT[AAF_CONFIG_1962HZ]; -#endif + switch (gyroModel){ + case ICM_42605_SPI: + switch (config) { + case GYRO_HARDWARE_LPF_NORMAL: + return aafLUT42605[AAF_CONFIG_258HZ]; + case GYRO_HARDWARE_LPF_OPTION_1: + return aafLUT42605[AAF_CONFIG_536HZ]; + case GYRO_HARDWARE_LPF_OPTION_2: + return aafLUT42605[AAF_CONFIG_997HZ]; + default: + return aafLUT42605[AAF_CONFIG_258HZ]; + } + + case ICM_42688P_SPI: default: - return aafLUT[AAF_CONFIG_258HZ]; + switch (config) { + case GYRO_HARDWARE_LPF_NORMAL: + return aafLUT42688[AAF_CONFIG_258HZ]; + case GYRO_HARDWARE_LPF_OPTION_1: + return aafLUT42688[AAF_CONFIG_536HZ]; + case GYRO_HARDWARE_LPF_OPTION_2: + return aafLUT42688[AAF_CONFIG_997HZ]; +#ifdef USE_GYRO_DLPF_EXPERIMENTAL + case GYRO_HARDWARE_LPF_EXPERIMENTAL: + return aafLUT42688[AAF_CONFIG_1962HZ]; +#endif + default: + return aafLUT42688[AAF_CONFIG_258HZ]; + } } } diff --git a/src/main/drivers/adc_stm32h7xx.c b/src/main/drivers/adc_stm32h7xx.c index 0069859a96..b9dac05777 100644 --- a/src/main/drivers/adc_stm32h7xx.c +++ b/src/main/drivers/adc_stm32h7xx.c @@ -272,7 +272,12 @@ void adcInitCalibrationValues(void) // Need this separate from the main adcValue[] array, because channels are numbered // by ADC instance order that is different from ADC_xxx numbering. -static volatile DMA_RAM uint16_t adcConversionBuffer[ADC_CHANNEL_COUNT] __attribute__((aligned(32))); +#define ADC_BUF_LENGTH ADC_CHANNEL_COUNT +#define ADC_BUF_BYTES (ADC_BUF_LENGTH * sizeof(uint16_t)) +#define ADC_BUF_CACHE_ALIGN_BYTES ((ADC_BUF_BYTES + 0x20) & ~0x1f) +#define ADC_BUF_CACHE_ALIGN_LENGTH (ADC_BUF_CACHE_ALIGN_BYTES / sizeof(uint16_t)) + +static volatile DMA_RAM uint16_t adcConversionBuffer[ADC_BUF_CACHE_ALIGN_LENGTH] __attribute__((aligned(32))); void adcInit(const adcConfig_t *config) { @@ -535,8 +540,7 @@ void adcInit(const adcConfig_t *config) void adcGetChannelValues(void) { // Transfer values in conversion buffer into adcValues[] - // Cache coherency should be maintained by MPU facility - + SCB_InvalidateDCache_by_Addr((uint32_t*)adcConversionBuffer, ADC_BUF_CACHE_ALIGN_BYTES); for (int i = 0; i < ADC_CHANNEL_INTERNAL_FIRST_ID; i++) { if (adcOperatingConfig[i].enabled) { adcValues[adcOperatingConfig[i].dmaIndex] = adcConversionBuffer[adcOperatingConfig[i].dmaIndex]; diff --git a/src/main/drivers/bus_octospi.c b/src/main/drivers/bus_octospi.c new file mode 100644 index 0000000000..d51c59397a --- /dev/null +++ b/src/main/drivers/bus_octospi.c @@ -0,0 +1,119 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + * + * Author: Dominic Clifton + */ + +/* + * OctoSPI support. + * + * Some STM32H7 MCUs support 2 OCTOSPI peripherals, each with up to 2 flash chips, using 2/4/8 IO lines each. Small MCU packages only have one instance. + * Additionally there is an OCTOSPIM peripheral which maps OCTOSPI1/2 peripherals to IO pins and can perform arbitration. + * + * Initial implementation is focused on supporting memory-mapped flash chips connected to an OCTOSPI peripheral that is already initialised by a bootloader. + * + * As such the following things are NOT supported: + * * Configuration of IO pins. + * * Clock configuration. + * * User-configuration. + * * OCTOSPIM configuration. + * * OCTOSPI2. + * + * Should the firmware need to know about the pins used by OCTOSPI then code can be written to determine this from the registers of the OCTOSPIM and OCTOSPI1/2 peripherals. + * + * Implementation notes: + * It's not possible to use the HAL libraries without modifying them and maintaining the internal state of the HAL structures. + * The HAL libraries were not designed to support the use-case of a bootloader configuring the flash in memory mapped mode and then + * having a second piece of software (this firmware) also use the flash. Furthermore many HAL methods were not designed to run with + * interrupts disabled which is necessary as other ISRs in this firmware will be running from external flash and must be disabled. + * See HAL_OSPI_Abort, OSPI_WaitFlagStateUntilTimeout, etc. + * All code that is executed when memory mapped mode is disabled needs to run from RAM, this would also involve modification of the HAL + * libraries. + */ + +#include +#include +#include + +#include "platform.h" + +#ifdef USE_OCTOSPI + +#include "bus_octospi.h" +#include "bus_octospi_impl.h" + +octoSpiDevice_t octoSpiDevice[OCTOSPIDEV_COUNT] = { 0 }; + +MMFLASH_CODE_NOINLINE OCTOSPIDevice octoSpiDeviceByInstance(OCTOSPI_TypeDef *instance) +{ +#ifdef USE_OCTOSPI_DEVICE_1 + if (instance == OCTOSPI1) { + return OCTOSPIDEV_1; + } +#endif + + return OCTOSPIINVALID; +} + +OCTOSPI_TypeDef *octoSpiInstanceByDevice(OCTOSPIDevice device) +{ + if (device == OCTOSPIINVALID || device >= OCTOSPIDEV_COUNT) { + return NULL; + } + + return octoSpiDevice[device].dev; +} + +const octoSpiHardware_t octoSpiHardware[] = { +#if defined(STM32H730xx) || defined(STM32H723xx) + { + .device = OCTOSPIDEV_1, + .reg = OCTOSPI1, + } +#else +#error MCU not supported. +#endif +}; + +bool octoSpiInit(OCTOSPIDevice device) +{ + for (size_t hwindex = 0; hwindex < ARRAYLEN(octoSpiHardware); hwindex++) { + const octoSpiHardware_t *hw = &octoSpiHardware[hwindex]; + + OCTOSPIDevice device = hw->device; + octoSpiDevice_t *pDev = &octoSpiDevice[device]; + + pDev->dev = hw->reg; + } + + switch (device) { + case OCTOSPIINVALID: + return false; + case OCTOSPIDEV_1: +#ifdef USE_OCTOSPI_DEVICE_1 + octoSpiInitDevice(OCTOSPIDEV_1); + return true; +#else + break; +#endif + } + return false; +} + +#endif diff --git a/src/main/drivers/bus_octospi.h b/src/main/drivers/bus_octospi.h new file mode 100644 index 0000000000..14178bd793 --- /dev/null +++ b/src/main/drivers/bus_octospi.h @@ -0,0 +1,62 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + * + * Author: Dominic Clifton + */ + +#pragma once + +#ifdef USE_OCTOSPI + +typedef enum OCTOSPIDevice { + OCTOSPIINVALID = -1, + OCTOSPIDEV_1 = 0, +} OCTOSPIDevice; + +#define OCTOSPIDEV_COUNT 1 + +// Macros to convert between configuration ids and device ids. +#define OCTOSPI_CFG_TO_DEV(x) ((x) - 1) +#define OCTOSPI_DEV_TO_CFG(x) ((x) + 1) + +#if !defined(STM32H7) +#error OctoSPI unsupported on this MCU +#endif + +OCTOSPIDevice octoSpiDeviceByInstance(OCTOSPI_TypeDef *instance); +OCTOSPI_TypeDef *octoSpiInstanceByDevice(OCTOSPIDevice device); + + +bool octoSpiInit(OCTOSPIDevice device); +bool octoSpiReceive1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); +bool octoSpiReceive4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length); +bool octoSpiTransmit1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length); + +bool octoSpiReceiveWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length); +bool octoSpiReceiveWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length); +bool octoSpiTransmitWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); +bool octoSpiTransmitWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length); + +bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize); + + +void octoSpiDisableMemoryMappedMode(OCTOSPI_TypeDef *instance); +void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instance); + +#endif diff --git a/src/main/drivers/bus_octospi_impl.h b/src/main/drivers/bus_octospi_impl.h new file mode 100644 index 0000000000..3a22989238 --- /dev/null +++ b/src/main/drivers/bus_octospi_impl.h @@ -0,0 +1,40 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + * + * Author: Dominic Clifton + */ + +#pragma once + +#ifdef USE_OCTOSPI + +typedef struct octoSpiHardware_s { + OCTOSPIDevice device; + OCTOSPI_TypeDef *reg; +} octoSpiHardware_t; + +typedef struct OCTOSPIDevice_s { + OCTOSPI_TypeDef *dev; +} octoSpiDevice_t; + +extern octoSpiDevice_t octoSpiDevice[OCTOSPIDEV_COUNT]; + +void octoSpiInitDevice(OCTOSPIDevice device); + +#endif diff --git a/src/main/drivers/bus_octospi_stm32h7xx.c b/src/main/drivers/bus_octospi_stm32h7xx.c new file mode 100644 index 0000000000..f45aaddb44 --- /dev/null +++ b/src/main/drivers/bus_octospi_stm32h7xx.c @@ -0,0 +1,853 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + * + * Author: Dominic Clifton + */ + +/* + * + */ +#include +#include +#include + +#include "platform.h" + +#ifdef USE_OCTOSPI + +#include "drivers/system.h" + +#include "drivers/bus_octospi.h" +#include "drivers/bus_octospi_impl.h" + +#if !(defined(STM32H730xx) || defined(STM32H723xx)) +#error MCU not supported. +#endif + +#define OCTOSPI_INTERFACE_COUNT 1 + +#define OSPI_FUNCTIONAL_MODE_INDIRECT_WRITE ((uint32_t)0x00000000) +#define OSPI_FUNCTIONAL_MODE_INDIRECT_READ ((uint32_t)OCTOSPI_CR_FMODE_0) +#define OSPI_FUNCTIONAL_MODE_AUTO_POLLING ((uint32_t)OCTOSPI_CR_FMODE_1) +#define OSPI_FUNCTIONAL_MODE_MEMORY_MAPPED ((uint32_t)OCTOSPI_CR_FMODE) + +#define OSPI_DHQC_DISABLE ((uint32_t)0x00000000U) +#define OSPI_DHQC_ENABLE ((uint32_t)OCTOSPI_TCR_DHQC) + +#define OSPI_OPTYPE_COMMON_CFG ((uint32_t)0x00000000U) + +#define OSPI_OPTYPE_READ_CFG ((uint32_t)0x00000001U) +#define OSPI_OPTYPE_WRITE_CFG ((uint32_t)0x00000002U) +#define OSPI_OPTYPE_WRAP_CFG ((uint32_t)0x00000003U) + +#define OSPI_INSTRUCTION_NONE ((uint32_t)0x00000000U) +#define OSPI_INSTRUCTION_1_LINE ((uint32_t)OCTOSPI_CCR_IMODE_0) +#define OSPI_INSTRUCTION_2_LINES ((uint32_t)OCTOSPI_CCR_IMODE_1) +#define OSPI_INSTRUCTION_4_LINES ((uint32_t)(OCTOSPI_CCR_IMODE_0 | OCTOSPI_CCR_IMODE_1)) +#define OSPI_INSTRUCTION_8_LINES ((uint32_t)OCTOSPI_CCR_IMODE_2) + +#define OSPI_INSTRUCTION_8_BITS ((uint32_t)0x00000000U) +#define OSPI_INSTRUCTION_16_BITS ((uint32_t)OCTOSPI_CCR_ISIZE_0) +#define OSPI_INSTRUCTION_24_BITS ((uint32_t)OCTOSPI_CCR_ISIZE_1) +#define OSPI_INSTRUCTION_32_BITS ((uint32_t)OCTOSPI_CCR_ISIZE) + +#define OSPI_INSTRUCTION_DTR_DISABLE ((uint32_t)0x00000000U) +#define OSPI_INSTRUCTION_DTR_ENABLE ((uint32_t)OCTOSPI_CCR_IDTR) + +#define OSPI_ADDRESS_NONE ((uint32_t)0x00000000U) /*!< No address */ +#define OSPI_ADDRESS_1_LINE ((uint32_t)OCTOSPI_CCR_ADMODE_0) /*!< Address on a single line */ +#define OSPI_ADDRESS_2_LINES ((uint32_t)OCTOSPI_CCR_ADMODE_1) /*!< Address on two lines */ +#define OSPI_ADDRESS_4_LINES ((uint32_t)(OCTOSPI_CCR_ADMODE_0 | OCTOSPI_CCR_ADMODE_1)) /*!< Address on four lines */ +#define OSPI_ADDRESS_8_LINES ((uint32_t)OCTOSPI_CCR_ADMODE_2) /*!< Address on eight lines */ + +#define OSPI_ADDRESS_8_BITS ((uint32_t)0x00000000U) /*!< 8-bit address */ +#define OSPI_ADDRESS_16_BITS ((uint32_t)OCTOSPI_CCR_ADSIZE_0) /*!< 16-bit address */ +#define OSPI_ADDRESS_24_BITS ((uint32_t)OCTOSPI_CCR_ADSIZE_1) /*!< 24-bit address */ +#define OSPI_ADDRESS_32_BITS ((uint32_t)OCTOSPI_CCR_ADSIZE) /*!< 32-bit address */ + +#define OSPI_ADDRESS_DTR_DISABLE ((uint32_t)0x00000000U) /*!< DTR mode disabled for address phase */ +#define OSPI_ADDRESS_DTR_ENABLE ((uint32_t)OCTOSPI_CCR_ADDTR) + +#define OSPI_DATA_NONE ((uint32_t)0x00000000U) +#define OSPI_DATA_1_LINE ((uint32_t)OCTOSPI_CCR_DMODE_0) +#define OSPI_DATA_2_LINES ((uint32_t)OCTOSPI_CCR_DMODE_1) +#define OSPI_DATA_4_LINES ((uint32_t)(OCTOSPI_CCR_DMODE_0 | OCTOSPI_CCR_DMODE_1)) +#define OSPI_DATA_8_LINES ((uint32_t)OCTOSPI_CCR_DMODE_2) + +#define OSPI_DATA_DTR_DISABLE ((uint32_t)0x00000000U) +#define OSPI_DATA_DTR_ENABLE ((uint32_t)OCTOSPI_CCR_DDTR) + +#define OSPI_ALTERNATE_BYTES_NONE ((uint32_t)0x00000000U) +#define OSPI_ALTERNATE_BYTES_1_LINE ((uint32_t)OCTOSPI_CCR_ABMODE_0) +#define OSPI_ALTERNATE_BYTES_2_LINES ((uint32_t)OCTOSPI_CCR_ABMODE_1) +#define OSPI_ALTERNATE_BYTES_4_LINES ((uint32_t)(OCTOSPI_CCR_ABMODE_0 | OCTOSPI_CCR_ABMODE_1)) +#define OSPI_ALTERNATE_BYTES_8_LINES ((uint32_t)OCTOSPI_CCR_ABMODE_2) + +#define OSPI_ALTERNATE_BYTES_8_BITS ((uint32_t)0x00000000U) +#define OSPI_ALTERNATE_BYTES_16_BITS ((uint32_t)OCTOSPI_CCR_ABSIZE_0) +#define OSPI_ALTERNATE_BYTES_24_BITS ((uint32_t)OCTOSPI_CCR_ABSIZE_1) +#define OSPI_ALTERNATE_BYTES_32_BITS ((uint32_t)OCTOSPI_CCR_ABSIZE) + +#define OSPI_ALTERNATE_BYTES_DTR_DISABLE ((uint32_t)0x00000000U) +#define OSPI_ALTERNATE_BYTES_DTR_ENABLE ((uint32_t)OCTOSPI_CCR_ABDTR) + +#define OSPI_DQS_DISABLE ((uint32_t)0x00000000U) +#define OSPI_DQS_ENABLE ((uint32_t)OCTOSPI_CCR_DQSE) + +#define OSPI_SIOO_INST_EVERY_CMD ((uint32_t)0x00000000U) +#define OSPI_SIOO_INST_ONLY_FIRST_CMD ((uint32_t)OCTOSPI_CCR_SIOO) + +MMFLASH_CODE_NOINLINE static void Error_Handler(void) { + while (1) { + NOOP; + } +} + + +#define __OSPI_GET_FLAG(__INSTANCE__, __FLAG__) ((READ_BIT((__INSTANCE__)->SR, (__FLAG__)) != 0U) ? SET : RESET) +#define __OSPI_CLEAR_FLAG(__INSTANCE__, __FLAG__) WRITE_REG((__INSTANCE__)->FCR, (__FLAG__)) +#define __OSPI_ENABLE(__INSTANCE__) SET_BIT((__INSTANCE__)->CR, OCTOSPI_CR_EN) +#define __OSPI_DISABLE(__INSTANCE__) CLEAR_BIT((__INSTANCE__)->CR, OCTOSPI_CR_EN) +#define __OSPI_IS_ENABLED(__INSTANCE__) (READ_BIT((__INSTANCE__)->CR, OCTOSPI_CR_EN) != 0U) + +MMFLASH_CODE_NOINLINE static void octoSpiAbort(OCTOSPI_TypeDef *instance) +{ + SET_BIT(instance->CR, OCTOSPI_CR_ABORT); +} + +MMFLASH_CODE_NOINLINE static void octoSpiWaitStatusFlags(OCTOSPI_TypeDef *instance, uint32_t mask, FlagStatus flagStatus) +{ + uint32_t regval; + + switch (flagStatus) { + case SET: + while (!((regval = READ_REG(instance->SR)) & mask)) + {} + break; + case RESET: + while (((regval = READ_REG(instance->SR)) & mask)) + {} + break; + } +} + + +typedef struct { + uint32_t OperationType; + + uint32_t Instruction; + uint32_t InstructionMode; + uint32_t InstructionSize; + uint32_t InstructionDtrMode; + + uint32_t Address; + uint32_t AddressMode; + uint32_t AddressSize; + uint32_t AddressDtrMode; + + uint32_t AlternateBytes; + uint32_t AlternateBytesMode; + uint32_t AlternateBytesSize; + uint32_t AlternateBytesDtrMode; + + uint32_t DummyCycles; // 0-31 + + uint32_t DataMode; + uint32_t DataDtrMode; + uint32_t NbData; + + uint32_t DQSMode; + uint32_t SIOOMode; +} OSPI_Command_t; + +// TODO rename cmd to command +MMFLASH_CODE_NOINLINE static ErrorStatus octoSpiConfigureCommand(OCTOSPI_TypeDef *instance, OSPI_Command_t *cmd) +{ + ErrorStatus status = SUCCESS; + + MODIFY_REG(instance->CR, OCTOSPI_CR_FMODE, 0U); + + instance->CCR = (cmd->DQSMode | cmd->SIOOMode); + + if (cmd->AlternateBytesMode != OSPI_ALTERNATE_BYTES_NONE) + { + instance->ABR = cmd->AlternateBytes; + + MODIFY_REG( + instance->ABR, + (OCTOSPI_CCR_ABMODE | OCTOSPI_CCR_ABDTR | OCTOSPI_CCR_ABSIZE), + (cmd->AlternateBytesMode | cmd->AlternateBytesDtrMode | cmd->AlternateBytesSize) + ); + } + + MODIFY_REG(instance->TCR, OCTOSPI_TCR_DCYC, cmd->DummyCycles); + + if (cmd->DataMode != OSPI_DATA_NONE) + { + if (cmd->OperationType == OSPI_OPTYPE_COMMON_CFG) + { + instance->DLR = (cmd->NbData - 1U); + } + } + + + if (cmd->InstructionMode != OSPI_INSTRUCTION_NONE) + { + if (cmd->AddressMode != OSPI_ADDRESS_NONE) + { + if (cmd->DataMode != OSPI_DATA_NONE) + { + // instruction, address and data + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_IMODE | OCTOSPI_CCR_IDTR | OCTOSPI_CCR_ISIZE | + OCTOSPI_CCR_ADMODE | OCTOSPI_CCR_ADDTR | OCTOSPI_CCR_ADSIZE | + OCTOSPI_CCR_DMODE | OCTOSPI_CCR_DDTR), + (cmd->InstructionMode | cmd->InstructionDtrMode | cmd->InstructionSize | + cmd->AddressMode | cmd->AddressDtrMode | cmd->AddressSize | + cmd->DataMode | cmd->DataDtrMode)); + } + else + { + // instruction and address + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_IMODE | OCTOSPI_CCR_IDTR | OCTOSPI_CCR_ISIZE | + OCTOSPI_CCR_ADMODE | OCTOSPI_CCR_ADDTR | OCTOSPI_CCR_ADSIZE), + (cmd->InstructionMode | cmd->InstructionDtrMode | cmd->InstructionSize | + cmd->AddressMode | cmd->AddressDtrMode | cmd->AddressSize)); + + // DHQC bit is linked with DDTR + if (((instance->TCR & OCTOSPI_TCR_DHQC_Msk) == OSPI_DHQC_ENABLE) && + (cmd->InstructionDtrMode == OSPI_INSTRUCTION_DTR_ENABLE)) + { + MODIFY_REG(instance->CCR, OCTOSPI_CCR_DDTR, OSPI_DATA_DTR_ENABLE); + } + } + + instance->IR = cmd->Instruction; + + instance->AR = cmd->Address; + } + else + { + if (cmd->DataMode != OSPI_DATA_NONE) + { + // instruction and data + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_IMODE | OCTOSPI_CCR_IDTR | OCTOSPI_CCR_ISIZE | + OCTOSPI_CCR_DMODE | OCTOSPI_CCR_DDTR), + (cmd->InstructionMode | cmd->InstructionDtrMode | cmd->InstructionSize | + cmd->DataMode | cmd->DataDtrMode)); + } + else + { + // instruction only + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_IMODE | OCTOSPI_CCR_IDTR | OCTOSPI_CCR_ISIZE), + (cmd->InstructionMode | cmd->InstructionDtrMode | cmd->InstructionSize)); + + // DHQC bit is linked with DDTR + if (((instance->TCR & OCTOSPI_TCR_DHQC_Msk) == OSPI_DHQC_ENABLE) && + (cmd->InstructionDtrMode == OSPI_INSTRUCTION_DTR_ENABLE)) + { + MODIFY_REG(instance->CCR, OCTOSPI_CCR_DDTR, OSPI_DATA_DTR_ENABLE); + } + } + + instance->IR = cmd->Instruction; + + } + } + else + { + if (cmd->AddressMode != OSPI_ADDRESS_NONE) + { + if (cmd->DataMode != OSPI_DATA_NONE) + { + // address and data + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_ADMODE | OCTOSPI_CCR_ADDTR | OCTOSPI_CCR_ADSIZE | + OCTOSPI_CCR_DMODE | OCTOSPI_CCR_DDTR), + (cmd->AddressMode | cmd->AddressDtrMode | cmd->AddressSize | + cmd->DataMode | cmd->DataDtrMode)); + } + else + { + // address only + + MODIFY_REG(instance->CCR, (OCTOSPI_CCR_ADMODE | OCTOSPI_CCR_ADDTR | OCTOSPI_CCR_ADSIZE), + (cmd->AddressMode | cmd->AddressDtrMode | cmd->AddressSize)); + } + + instance->AR = cmd->Address; + } + else + { + // no instruction, no address + status = ERROR; + } + } + + return status; +} + +MMFLASH_CODE_NOINLINE ErrorStatus octoSpiCommand(OCTOSPI_TypeDef *instance, OSPI_Command_t *cmd) +{ + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); + + ErrorStatus status = octoSpiConfigureCommand(instance, cmd); + if (status == SUCCESS) { + if (cmd->DataMode == OSPI_DATA_NONE) + { + // transfer is already started, wait now. + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_TCF, SET); + __OSPI_CLEAR_FLAG(instance, OCTOSPI_SR_TCF); + } + } + + return status; +} + +/* + * Transmit + * + * Call optoSpiCommand first to configure the transaction stages. + */ +MMFLASH_CODE_NOINLINE ErrorStatus octoSpiTransmit(OCTOSPI_TypeDef *instance, uint8_t *data) +{ + if (data == NULL) { + return ERROR; + } + + + __IO uint32_t XferCount = READ_REG(instance->DLR) + 1U; + uint8_t *pBuffPtr = data; + + MODIFY_REG(instance->CR, OCTOSPI_CR_FMODE, OSPI_FUNCTIONAL_MODE_INDIRECT_WRITE); + + __IO uint32_t *data_reg = &instance->DR; + do + { + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_FTF, SET); + + *((__IO uint8_t *)data_reg) = *pBuffPtr; + pBuffPtr++; + XferCount--; + } while (XferCount > 0U); + + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_TCF, SET); + __OSPI_CLEAR_FLAG(instance, OCTOSPI_SR_TCF); + + return SUCCESS; +} + +/* + * Receive + * + * Call optoSpiCommand first to configure the transaction stages. + */ +MMFLASH_CODE_NOINLINE ErrorStatus octoSpiReceive(OCTOSPI_TypeDef *instance, uint8_t *data) +{ + if (data == NULL) { + return ERROR; + } + + __IO uint32_t XferCount = READ_REG(instance->DLR) + 1U; + uint8_t *pBuffPtr = data; + + MODIFY_REG(instance->CR, OCTOSPI_CR_FMODE, OSPI_FUNCTIONAL_MODE_INDIRECT_READ); + + uint32_t addr_reg = instance->AR; + uint32_t ir_reg = instance->IR; + + // Trigger the transfer by re-writing the address or instruction register + if (READ_BIT(instance->CCR, OCTOSPI_CCR_ADMODE) != OSPI_ADDRESS_NONE) + { + WRITE_REG(instance->AR, addr_reg); + } + else + { + WRITE_REG(instance->IR, ir_reg); + } + + __IO uint32_t *data_reg = &instance->DR; + + do + { + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_FTF | OCTOSPI_SR_TCF, SET); + + *pBuffPtr = *((__IO uint8_t *)data_reg); + pBuffPtr++; + XferCount--; + } while(XferCount > 0U); + + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_TCF, SET); + __OSPI_CLEAR_FLAG(instance, OCTOSPI_SR_TCF); + + return SUCCESS; +} + +typedef struct +{ + // CR register contains the all-important FMODE bits. + uint32_t CR; + + // flash chip specific configuration set by the bootloader + uint32_t CCR; + uint32_t TCR; + uint32_t IR; + uint32_t ABR; + // address register - no meaning. + // data length register no meaning. + +} octoSpiMemoryMappedModeConfigurationRegisterBackup_t; + +octoSpiMemoryMappedModeConfigurationRegisterBackup_t ospiMMMCRBackups[OCTOSPI_INTERFACE_COUNT]; + +void octoSpiBackupMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) +{ + OCTOSPIDevice device = octoSpiDeviceByInstance(instance); + if (device == OCTOSPIINVALID) { + return; + } + + octoSpiMemoryMappedModeConfigurationRegisterBackup_t *ospiMMMCRBackup = &ospiMMMCRBackups[device]; + + // backup all the registers used by memory mapped mode that: + // a) the bootloader configured. + // b) that other code in this implementation may have modified when memory mapped mode is disabled. + + ospiMMMCRBackup->CR = instance->CR; + ospiMMMCRBackup->IR = instance->IR; + ospiMMMCRBackup->CCR = instance->CCR; + ospiMMMCRBackup->TCR = instance->TCR; + ospiMMMCRBackup->ABR = instance->ABR; +} + +MMFLASH_CODE_NOINLINE void octoSpiRestoreMemoryMappedModeConfiguration(OCTOSPI_TypeDef *instance) +{ + OCTOSPIDevice device = octoSpiDeviceByInstance(instance); + if (device == OCTOSPIINVALID) { + return; + } + + octoSpiMemoryMappedModeConfigurationRegisterBackup_t *ospiMMMCRBackup = &ospiMMMCRBackups[device]; + + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); + + instance->ABR = ospiMMMCRBackup->ABR; + instance->TCR = ospiMMMCRBackup->TCR; + + instance->DLR = 0; // "no meaning" in MM mode. + + instance->CCR = ospiMMMCRBackup->CCR; + + instance->IR = ospiMMMCRBackup->IR; + instance->AR = 0; // "no meaning" in MM mode. + + octoSpiAbort(instance); + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); + + instance->CR = ospiMMMCRBackup->CR; +} + +/* + * Disable memory mapped mode. + * + * @See octoSpiEnableMemoryMappedMode + * @See MMFLASH_CODE_NOINLINE + * + * Once this is called any code or data in the memory mapped region cannot be accessed. + * Thus, this function itself must be in RAM, and the caller's code and data should all be in RAM + * and this requirement continues until octoSpiEnableMemoryMappedMode is called. + * This applies to ISR code that runs from the memory mapped region, so likely the caller should + * also disable IRQs before calling this. + */ +MMFLASH_CODE_NOINLINE void octoSpiDisableMemoryMappedMode(OCTOSPI_TypeDef *instance) +{ + if (READ_BIT(OCTOSPI1->CR, OCTOSPI_CR_FMODE) != OCTOSPI_CR_FMODE) { + failureMode(FAILURE_DEVELOPER); // likely not booted with memory mapped mode enabled, or mismatched calls to enable/disable memory map mode. + } + + octoSpiAbort(instance); + if (__OSPI_GET_FLAG(instance, OCTOSPI_SR_BUSY) == SET) { + + __OSPI_DISABLE(instance); + octoSpiAbort(instance); + } + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); + + uint32_t fmode = 0x0; // b00 = indirect write, see OCTOSPI->CR->FMODE + MODIFY_REG(instance->CR, OCTOSPI_CR_FMODE, fmode); + + uint32_t regval = READ_REG(instance->CR); + if ((regval & OCTOSPI_CR_FMODE) != fmode) { + Error_Handler(); + } + + if (!__OSPI_IS_ENABLED(instance)) { + __OSPI_ENABLE(instance); + } +} + +/* + * Enable memory mapped mode. + * + * @See octoSpiDisableMemoryMappedMode + * @See MMFLASH_CODE_NOINLINE + */ + +MMFLASH_CODE_NOINLINE void octoSpiEnableMemoryMappedMode(OCTOSPI_TypeDef *instance) +{ + octoSpiAbort(instance); + octoSpiWaitStatusFlags(instance, OCTOSPI_SR_BUSY, RESET); + + octoSpiRestoreMemoryMappedModeConfiguration(instance); +} + +MMFLASH_CODE_NOINLINE void octoSpiTestEnableDisableMemoryMappedMode(octoSpiDevice_t *octoSpi) +{ + OCTOSPI_TypeDef *instance = octoSpi->dev; + + __disable_irq(); + octoSpiDisableMemoryMappedMode(instance); + octoSpiEnableMemoryMappedMode(instance); + __enable_irq(); +} + +MMFLASH_DATA static const uint32_t octoSpi_addressSizeMap[] = { + OSPI_ADDRESS_8_BITS, + OSPI_ADDRESS_16_BITS, + OSPI_ADDRESS_24_BITS, + OSPI_ADDRESS_32_BITS +}; + +MMFLASH_CODE static uint32_t octoSpi_addressSizeFromValue(uint8_t addressSize) +{ + return octoSpi_addressSizeMap[((addressSize + 1) / 8) - 1]; // rounds to nearest OSPI_ADDRESS_* value that will hold the address. +} + + +MMFLASH_CODE_NOINLINE bool octoSpiTransmit1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, const uint8_t *out, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_NONE; + cmd.AddressSize = OSPI_ADDRESS_32_BITS; + + cmd.DummyCycles = dummyCycles; + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_NONE; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + if (out) { + cmd.DataMode = OSPI_DATA_1_LINE; + } + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS && out && length > 0) { + status = octoSpiTransmit(instance, (uint8_t *)out); + } + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiReceive1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_NONE; + cmd.AddressSize = OSPI_ADDRESS_32_BITS; + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_1_LINE; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiReceive(instance, in); + } + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiReceive4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint8_t *in, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_4_LINES; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_NONE; + cmd.AddressSize = OSPI_ADDRESS_32_BITS; + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_4_LINES; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiReceive(instance, in); + } + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiReceiveWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.Address = address; + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_1_LINE; + cmd.AddressSize = octoSpi_addressSizeFromValue(addressSize); + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_1_LINE; + cmd.NbData = length; + + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + cmd.DQSMode = OSPI_DQS_DISABLE; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiReceive(instance, in); + } + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiReceiveWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, uint8_t *in, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.Address = address; + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_1_LINE; + cmd.AddressSize = octoSpi_addressSizeFromValue(addressSize); + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_4_LINES; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiReceive(instance, in); + } + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiTransmitWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.Address = address; + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_1_LINE; + cmd.AddressSize = octoSpi_addressSizeFromValue(addressSize); + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_1_LINE; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiTransmit(instance, (uint8_t *)out); + } + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiTransmitWithAddress4LINES(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize, const uint8_t *out, int length) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.Address = address; + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_1_LINE; + cmd.AddressSize = octoSpi_addressSizeFromValue(addressSize); + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_4_LINES; + cmd.NbData = length; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + if (status == SUCCESS) { + status = octoSpiTransmit(instance, (uint8_t *)out); + } + + + return status == SUCCESS; +} + +MMFLASH_CODE_NOINLINE bool octoSpiInstructionWithAddress1LINE(OCTOSPI_TypeDef *instance, uint8_t instruction, uint8_t dummyCycles, uint32_t address, uint8_t addressSize) +{ + OSPI_Command_t cmd; // Can't initialise to zero as compiler optimization will use memset() which is not in RAM. + + cmd.OperationType = OSPI_OPTYPE_COMMON_CFG; + + cmd.Instruction = instruction; + cmd.InstructionDtrMode = OSPI_INSTRUCTION_DTR_DISABLE; + cmd.InstructionMode = OSPI_INSTRUCTION_1_LINE; + cmd.InstructionSize = OSPI_INSTRUCTION_8_BITS; + + cmd.Address = address; + cmd.AddressDtrMode = OSPI_ADDRESS_DTR_DISABLE; + cmd.AddressMode = OSPI_ADDRESS_1_LINE; + cmd.AddressSize = octoSpi_addressSizeFromValue(addressSize); + + cmd.AlternateBytesMode = OSPI_ALTERNATE_BYTES_NONE; + + cmd.DummyCycles = dummyCycles; + + cmd.DataDtrMode = OSPI_DATA_DTR_DISABLE; + cmd.DataMode = OSPI_DATA_NONE; + cmd.NbData = 0; + + cmd.DQSMode = OSPI_DQS_DISABLE; + cmd.SIOOMode = OSPI_SIOO_INST_EVERY_CMD; + + ErrorStatus status = octoSpiCommand(instance, &cmd); + + return status == SUCCESS; +} + + +void octoSpiInitDevice(OCTOSPIDevice device) +{ + octoSpiDevice_t *octoSpi = &(octoSpiDevice[device]); + +#if defined(STM32H730xx) || defined(STM32H723xx) + if (isMemoryMappedModeEnabledOnBoot()) { + // Bootloader has already configured the IO, clocks and peripherals. + octoSpiBackupMemoryMappedModeConfiguration(octoSpi->dev); + + octoSpiTestEnableDisableMemoryMappedMode(octoSpi); + } else { + failureMode(FAILURE_DEVELOPER); // trying to use this implementation when memory mapped mode is not already enabled by a bootloader + + // Here is where we would configure the OCTOSPI1/2 and OCTOSPIM peripherals for the non-memory-mapped use case. + } +#else +#error MCU not supported. +#endif + +} + +#endif diff --git a/src/main/drivers/bus_spi.c b/src/main/drivers/bus_spi.c index 5de25e0c52..82a9263991 100644 --- a/src/main/drivers/bus_spi.c +++ b/src/main/drivers/bus_spi.c @@ -717,7 +717,7 @@ void spiSequence(const extDevice_t *dev, busSegment_t *segments) { busDevice_t *bus = dev->bus; - ATOMIC_BLOCK(NVIC_PRIO_MAX) { + ATOMIC_BLOCK(NVIC_PRIO_SPI_DMA) { if (spiIsBusy(dev)) { busSegment_t *endSegment; diff --git a/src/main/drivers/display.h b/src/main/drivers/display.h index 58b8354838..d20979fb43 100644 --- a/src/main/drivers/display.h +++ b/src/main/drivers/display.h @@ -35,14 +35,14 @@ typedef enum { } displayPortDeviceType_e; typedef enum { - DISPLAYPORT_ATTR_NORMAL = 0, - DISPLAYPORT_ATTR_INFO, - DISPLAYPORT_ATTR_WARNING, - DISPLAYPORT_ATTR_CRITICAL, - DISPLAYPORT_ATTR_COUNT, + DISPLAYPORT_SEVERITY_NORMAL = 0, + DISPLAYPORT_SEVERITY_INFO, + DISPLAYPORT_SEVERITY_WARNING, + DISPLAYPORT_SEVERITY_CRITICAL, + DISPLAYPORT_SEVERITY_COUNT, } displayPortSeverity_e; -#define DISPLAYPORT_ATTR_BLINK 0x80 // Device local blink bit or'ed into displayPortSeverity_e +#define DISPLAYPORT_BLINK 0x80 // Device local blink bit or'ed into displayPortSeverity_e // System elements rendered by VTX or Goggles typedef enum { diff --git a/src/main/drivers/dshot_bitbang.c b/src/main/drivers/dshot_bitbang.c index 296ddc42c9..52eff23825 100644 --- a/src/main/drivers/dshot_bitbang.c +++ b/src/main/drivers/dshot_bitbang.c @@ -46,6 +46,16 @@ #include "drivers/timer.h" #include "pg/motor.h" +#include "pg/pinio.h" + +// DEBUG_DSHOT_TELEMETRY_COUNTS +// 0 - Count of telemetry packets read +// 1 - Count of missing edge +// 2 - Count of reception not complete in time +// 3 - Number of high bits before telemetry start + +// Maximum time to wait for telemetry reception to complete +#define DSHOT_TELEMETRY_TIMEOUT 2000 FAST_DATA_ZERO_INIT bbPacer_t bbPacers[MAX_MOTOR_PACERS]; // TIM1 or TIM8 FAST_DATA_ZERO_INIT int usedMotorPacers = 0; @@ -324,9 +334,12 @@ FAST_IRQ_HANDLER void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor) #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { if (bbPort->direction == DSHOT_BITBANG_DIRECTION_INPUT) { + bbPort->telemetryPending = false; #ifdef DEBUG_COUNT_INTERRUPT bbPort->inputIrq++; #endif + // Disable DMA as telemetry reception is complete + bbDMA_Cmd(bbPort, DISABLE); } else { #ifdef DEBUG_COUNT_INTERRUPT bbPort->outputIrq++; @@ -335,6 +348,7 @@ FAST_IRQ_HANDLER void bbDMAIrqHandler(dmaChannelDescriptor_t *descriptor) // Switch to input bbSwitchToInput(bbPort); + bbPort->telemetryPending = true; bbTIM_DMACmd(bbPort->timhw->tim, bbPort->dmaSource, ENABLE); } @@ -441,7 +455,7 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e p if (!bbPort || !dmaAllocate(dmaGetIdentifier(bbPort->dmaResource), bbPort->owner.owner, bbPort->owner.resourceIndex)) { bbDevice.vTable.write = motorWriteNull; - bbDevice.vTable.updateStart = motorUpdateStartNull; + bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull; bbDevice.vTable.updateComplete = motorUpdateCompleteNull; return false; @@ -493,49 +507,71 @@ static bool bbMotorConfig(IO_t io, uint8_t motorIndex, motorPwmProtocolTypes_e p return true; } -static bool bbUpdateStart(void) +static bool bbTelemetryWait(void) +{ + // Wait for telemetry reception to complete + bool telemetryPending; + bool telemetryWait = false; + const timeUs_t startTimeUs = micros(); + + do { + telemetryPending = false; + for (int i = 0; i < usedMotorPorts; i++) { + telemetryPending |= bbPorts[i].telemetryPending; + } + + telemetryWait |= telemetryPending; + + if (cmpTimeUs(micros(), startTimeUs) > DSHOT_TELEMETRY_TIMEOUT) { + break; + } + } while (telemetryPending); + + if (telemetryWait) { + DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 2, debug[2] + 1); + } + + return telemetryWait; +} + +static void bbUpdateInit(void) +{ + for (int i = 0; i < usedMotorPorts; i++) { + bbOutputDataClear(bbPorts[i].portOutputBuffer); + } +} + +static bool bbDecodeTelemetry(void) { #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { #ifdef USE_DSHOT_TELEMETRY_STATS const timeMs_t currentTimeMs = millis(); #endif - timeUs_t currentUs = micros(); - // don't send while telemetry frames might still be incoming - if (cmpTimeUs(currentUs, lastSendUs) < (timeDelta_t)(40 + 2 * dshotFrameUs)) { - return false; - } - - for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) { #ifdef USE_DSHOT_CACHE_MGMT - // Only invalidate the buffer once. If all motors are on a common port they'll share a buffer. - bool invalidated = false; - for (int i = 0; i < motorIndex; i++) { - if (bbMotors[motorIndex].bbPort->portInputBuffer == bbMotors[i].bbPort->portInputBuffer) { - invalidated = true; - } - } - if (!invalidated) { - SCB_InvalidateDCache_by_Addr((uint32_t *)bbMotors[motorIndex].bbPort->portInputBuffer, - DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES); - } + for (int i = 0; i < usedMotorPorts; i++) { + bbPort_t *bbPort = &bbPorts[i]; + SCB_InvalidateDCache_by_Addr((uint32_t *)bbPort->portInputBuffer, DSHOT_BB_PORT_IP_BUF_CACHE_ALIGN_BYTES); + } #endif - + for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) { #ifdef STM32F4 uint32_t rawValue = decode_bb_bitband( bbMotors[motorIndex].bbPort->portInputBuffer, - bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort), + bbMotors[motorIndex].bbPort->portInputCount, bbMotors[motorIndex].pinIndex); #else uint32_t rawValue = decode_bb( bbMotors[motorIndex].bbPort->portInputBuffer, - bbMotors[motorIndex].bbPort->portInputCount - bbDMA_Count(bbMotors[motorIndex].bbPort), + bbMotors[motorIndex].bbPort->portInputCount, bbMotors[motorIndex].pinIndex); #endif if (rawValue == DSHOT_TELEMETRY_NOEDGE) { + DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 1, debug[1] + 1); continue; } + DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 0, debug[0] + 1); dshotTelemetryState.readCount++; if (rawValue != DSHOT_TELEMETRY_INVALID) { @@ -556,10 +592,6 @@ static bool bbUpdateStart(void) dshotTelemetryState.rawValueState = DSHOT_RAW_VALUE_STATE_NOT_PROCESSED; } #endif - for (int i = 0; i < usedMotorPorts; i++) { - bbDMA_Cmd(&bbPorts[i], DISABLE); - bbOutputDataClear(bbPorts[i].portOutputBuffer); - } return true; } @@ -616,23 +648,11 @@ static void bbUpdateComplete(void) } } -#ifdef USE_DSHOT_CACHE_MGMT - for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) { - // Only clean each buffer once. If all motors are on a common port they'll share a buffer. - bool clean = false; - for (int i = 0; i < motorIndex; i++) { - if (bbMotors[motorIndex].bbPort->portOutputBuffer == bbMotors[i].bbPort->portOutputBuffer) { - clean = true; - } - } - if (!clean) { - SCB_CleanDCache_by_Addr(bbMotors[motorIndex].bbPort->portOutputBuffer, MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES); - } - } -#endif - for (int i = 0; i < usedMotorPorts; i++) { bbPort_t *bbPort = &bbPorts[i]; +#ifdef USE_DSHOT_CACHE_MGMT + SCB_CleanDCache_by_Addr(bbPort->portOutputBuffer, MOTOR_DSHOT_BUF_CACHE_ALIGN_BYTES); +#endif #ifdef USE_DSHOT_TELEMETRY if (useDshotTelemetry) { @@ -708,7 +728,9 @@ static motorVTable_t bbVTable = { .enable = bbEnableMotors, .disable = bbDisableMotors, .isMotorEnabled = bbIsMotorEnabled, - .updateStart = bbUpdateStart, + .telemetryWait = bbTelemetryWait, + .decodeTelemetry = bbDecodeTelemetry, + .updateInit = bbUpdateInit, .write = bbWrite, .writeInt = bbWriteInt, .updateComplete = bbUpdateComplete, @@ -755,7 +777,7 @@ motorDevice_t *dshotBitbangDevInit(const motorDevConfig_t *motorConfig, uint8_t if (!IOIsFreeOrPreinit(io)) { /* not enough motors initialised for the mixer or a break in the motors */ bbDevice.vTable.write = motorWriteNull; - bbDevice.vTable.updateStart = motorUpdateStartNull; + bbDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull; bbDevice.vTable.updateComplete = motorUpdateCompleteNull; bbStatus = DSHOT_BITBANG_STATUS_MOTOR_PIN_CONFLICT; return NULL; diff --git a/src/main/drivers/dshot_bitbang_decode.c b/src/main/drivers/dshot_bitbang_decode.c index 388b4dc32c..591436cdee 100644 --- a/src/main/drivers/dshot_bitbang_decode.c +++ b/src/main/drivers/dshot_bitbang_decode.c @@ -1,3 +1,23 @@ +/* + * This file is part of Cleanflight and Betaflight. + * + * Cleanflight and Betaflight are free software. You can redistribute + * this software and/or modify this software 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 and Betaflight are distributed in the hope that they + * 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 this software. + * + * If not, see . + */ + #include #include #include @@ -8,6 +28,7 @@ #include "common/maths.h" #include "common/utils.h" +#include "build/debug.h" #include "drivers/dshot.h" #include "drivers/dshot_bitbang_decode.h" @@ -28,7 +49,8 @@ uint16_t bbBuffer[134]; #define BITBAND_SRAM_BASE 0x22000000 #define BITBAND_SRAM(a,b) ((BITBAND_SRAM_BASE + (((a)-BITBAND_SRAM_REF)<<5) + ((b)<<2))) // Convert SRAM address - +#define DSHOT_TELEMETRY_START_MARGIN 10 +static uint8_t preambleSkip = 0; typedef struct bitBandWord_s { uint32_t value; @@ -84,6 +106,8 @@ static uint32_t decode_bb_value(uint32_t value, uint16_t buffer[], uint32_t coun uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) { + uint8_t startMargin; + #ifdef DEBUG_BBDECODE memset(sequence, 0, sizeof(sequence)); sequenceIndex = 0; @@ -94,6 +118,9 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) bitBandWord_t* b = p; bitBandWord_t* endP = p + (count - MIN_VALID_BBSAMPLES); + // Jump forward in the buffer to just before where we anticipate the first zero + p += preambleSkip; + // Eliminate leading high signal level by looking for first zero bit in data stream. // Manual loop unrolling and branch hinting to produce faster code. while (p < endP) { @@ -105,6 +132,9 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) } } + startMargin = p - b; + DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 3, startMargin); + if (p >= endP) { // not returning telemetry is ok if the esc cpu is // overburdened. in that case no edge will be found and @@ -188,6 +218,10 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) sequence[sequenceIndex] = sequence[sequenceIndex] + (nlen) * 3; sequenceIndex++; #endif + + // The anticipated edges were observed + preambleSkip = startMargin - DSHOT_TELEMETRY_START_MARGIN; + if (nlen > 0) { value <<= nlen; value |= 1 << (nlen - 1); @@ -198,6 +232,8 @@ uint32_t decode_bb_bitband( uint16_t buffer[], uint32_t count, uint32_t bit) FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) { + uint8_t startMargin; + #ifdef DEBUG_BBDECODE memset(sequence, 0, sizeof(sequence)); sequenceIndex = 0; @@ -209,12 +245,15 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) memset(sequence, 0, sizeof(sequence)); int sequenceIndex = 0; #endif - uint16_t lastValue = 0; uint32_t value = 0; uint16_t* p = buffer; uint16_t* endP = p + count - MIN_VALID_BBSAMPLES; + + // Jump forward in the buffer to just before where we anticipate the first zero + p += preambleSkip; + // Eliminate leading high signal level by looking for first zero bit in data stream. // Manual loop unrolling and branch hinting to produce faster code. while (p < endP) { @@ -226,10 +265,15 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) } } - if(*p & mask) { + startMargin = p - buffer; + DEBUG_SET(DEBUG_DSHOT_TELEMETRY_COUNTS, 3, startMargin); + + if (p >= endP) { // not returning telemetry is ok if the esc cpu is // overburdened. in that case no edge will be found and // BB_NOEDGE indicates the condition to caller + // Increase the start margin + preambleSkip--; return DSHOT_TELEMETRY_NOEDGE; } @@ -268,6 +312,8 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) // length of last sequence has to be inferred since the last bit with inverted dshot is high if (bits < 18) { + // Increase the start margin + preambleSkip--; return DSHOT_TELEMETRY_NOEDGE; } @@ -278,9 +324,14 @@ FAST_CODE uint32_t decode_bb( uint16_t buffer[], uint32_t count, uint32_t bit) #endif if (nlen < 0) { + // Increase the start margin + preambleSkip--; return DSHOT_TELEMETRY_NOEDGE; } + // The anticipated edges were observed + preambleSkip = startMargin - DSHOT_TELEMETRY_START_MARGIN; + if (nlen > 0) { value <<= nlen; value |= 1 << (nlen - 1); diff --git a/src/main/drivers/dshot_bitbang_impl.h b/src/main/drivers/dshot_bitbang_impl.h index f81fcc46db..928fbf4fc1 100644 --- a/src/main/drivers/dshot_bitbang_impl.h +++ b/src/main/drivers/dshot_bitbang_impl.h @@ -167,6 +167,7 @@ typedef struct bbPort_s { uint16_t *portInputBuffer; uint32_t portInputCount; bool inputActive; + volatile bool telemetryPending; // Misc #ifdef DEBUG_COUNT_INTERRUPT diff --git a/src/main/drivers/dshot_command.c b/src/main/drivers/dshot_command.c index 37d02b7f21..cd04ccc65f 100644 --- a/src/main/drivers/dshot_command.c +++ b/src/main/drivers/dshot_command.c @@ -218,7 +218,7 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot #ifdef USE_DSHOT_TELEMETRY timeUs_t timeoutUs = micros() + 1000; - while (!motorGetVTable().updateStart() && + while (!motorGetVTable().decodeTelemetry() && cmpTimeUs(timeoutUs, micros()) > 0); #endif for (uint8_t i = 0; i < motorDeviceCount(); i++) { @@ -239,7 +239,7 @@ void dshotCommandWrite(uint8_t index, uint8_t motorCount, uint8_t command, dshot dshotCommandControl_t *commandControl = addCommand(); if (commandControl) { commandControl->repeats = repeats; - commandControl->delayAfterCommandUs = delayAfterCommandUs; + commandControl->delayAfterCommandUs = DSHOT_COMMAND_DELAY_US; for (unsigned i = 0; i < motorCount; i++) { if (index == i || index == ALL_MOTORS) { commandControl->command[i] = command; diff --git a/src/main/drivers/dshot_dpwm.c b/src/main/drivers/dshot_dpwm.c index de26d589da..a7ab462f51 100644 --- a/src/main/drivers/dshot_dpwm.c +++ b/src/main/drivers/dshot_dpwm.c @@ -140,7 +140,7 @@ static motorVTable_t dshotPwmVTable = { .enable = dshotPwmEnableMotors, .disable = dshotPwmDisableMotors, .isMotorEnabled = dshotPwmIsMotorEnabled, - .updateStart = motorUpdateStartNull, // May be updated after copying + .decodeTelemetry = motorDecodeTelemetryNull, // May be updated after copying .write = dshotWrite, .writeInt = dshotWriteInt, .updateComplete = pwmCompleteDshotMotorUpdate, @@ -160,7 +160,7 @@ motorDevice_t *dshotPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl #ifdef USE_DSHOT_TELEMETRY useDshotTelemetry = motorConfig->useDshotTelemetry; - dshotPwmDevice.vTable.updateStart = pwmStartDshotMotorUpdate; + dshotPwmDevice.vTable.decodeTelemetry = pwmTelemetryDecode; #endif switch (motorConfig->motorPwmProtocol) { diff --git a/src/main/drivers/dshot_dpwm.h b/src/main/drivers/dshot_dpwm.h index dc1b190072..f2d963a40a 100644 --- a/src/main/drivers/dshot_dpwm.h +++ b/src/main/drivers/dshot_dpwm.h @@ -159,7 +159,7 @@ motorDmaOutput_t *getMotorDmaOutput(uint8_t index); void pwmWriteDshotInt(uint8_t index, uint16_t value); bool pwmDshotMotorHardwareConfig(const timerHardware_t *timerHardware, uint8_t motorIndex, uint8_t reorderedMotorIndex, motorPwmProtocolTypes_e pwmProtocolType, uint8_t output); #ifdef USE_DSHOT_TELEMETRY -bool pwmStartDshotMotorUpdate(void); +bool pwmTelemetryDecode(void); #endif void pwmCompleteDshotMotorUpdate(void); diff --git a/src/main/drivers/flash.c b/src/main/drivers/flash.c index ee8b55a3d7..39be0e9d83 100644 --- a/src/main/drivers/flash.c +++ b/src/main/drivers/flash.c @@ -36,8 +36,12 @@ #include "flash_w25m.h" #include "drivers/bus_spi.h" #include "drivers/bus_quadspi.h" +#include "drivers/bus_octospi.h" #include "drivers/io.h" #include "drivers/time.h" +#include "drivers/system.h" + +#ifdef USE_FLASH_SPI // 20 MHz max SPI frequency #define FLASH_MAX_SPI_CLK_HZ 20000000 @@ -47,13 +51,143 @@ static extDevice_t devInstance; static extDevice_t *dev; +#endif + static flashDevice_t flashDevice; static flashPartitionTable_t flashPartitionTable; static int flashPartitions = 0; #define FLASH_INSTRUCTION_RDID 0x9F -#ifdef USE_QUADSPI +#ifdef USE_FLASH_MEMORY_MAPPED +MMFLASH_CODE_NOINLINE void flashMemoryMappedModeDisable(void) +{ + __disable_irq(); +#ifdef USE_FLASH_OCTOSPI + octoSpiDisableMemoryMappedMode(flashDevice.io.handle.octoSpi); +#else +#error Invalid configuration - Not implemented +#endif +} + +MMFLASH_CODE_NOINLINE void flashMemoryMappedModeEnable(void) +{ +#ifdef USE_FLASH_OCTOSPI + octoSpiEnableMemoryMappedMode(flashDevice.io.handle.octoSpi); + __enable_irq(); +#else +#error Invalid configuration - Not implemented +#endif +} +#endif + +#ifdef USE_FLASH_OCTOSPI +MMFLASH_CODE_NOINLINE static bool flashOctoSpiInit(const flashConfig_t *flashConfig) +{ + bool detected = false; + + enum { + TRY_1LINE = 0, TRY_4LINE, BAIL + } phase = TRY_1LINE; + +#ifdef USE_FLASH_MEMORY_MAPPED + bool memoryMappedModeEnabledOnBoot = isMemoryMappedModeEnabledOnBoot(); +#else + bool memoryMappedModeEnabledOnBoot = false; +#endif + +#ifndef USE_OCTOSPI_EXPERIMENTAL + if (!memoryMappedModeEnabledOnBoot) { + return false; // Not supported yet, enable USE_OCTOSPI_EXPERIMENTAL and test/update implementation as required. + } +#endif + + OCTOSPI_TypeDef *instance = octoSpiInstanceByDevice(OCTOSPI_CFG_TO_DEV(flashConfig->octoSpiDevice)); + + flashDevice.io.handle.octoSpi = instance; + flashDevice.io.mode = FLASHIO_OCTOSPI; + + if (memoryMappedModeEnabledOnBoot) { + flashMemoryMappedModeDisable(); + } + + do { +#ifdef USE_OCTOSPI_EXPERIMENTAL + if (!memoryMappedMode) { + octoSpiSetDivisor(instance, OCTOSPI_CLOCK_INITIALISATION); + } +#endif + // for the memory-mapped use-case, we rely on the bootloader to have already selected the correct speed for the flash chip. + + // 3 bytes for what we need, but some IC's need 8 dummy cycles after the instruction, so read 4 and make two attempts to + // assemble the chip id from the response. + uint8_t readIdResponse[4]; + + bool status = false; + switch (phase) { + case TRY_1LINE: + status = octoSpiReceive1LINE(instance, FLASH_INSTRUCTION_RDID, 0, readIdResponse, 4); + break; + case TRY_4LINE: + status = octoSpiReceive4LINES(instance, FLASH_INSTRUCTION_RDID, 2, readIdResponse, 3); + break; + default: + break; + } + + if (!status) { + phase++; + continue; + } + +#ifdef USE_OCTOSPI_EXPERIMENTAL + if (!memoryMappedModeEnabledOnBoot) { + octoSpiSetDivisor(instance, OCTOSPI_CLOCK_ULTRAFAST); + } +#endif + + for (uint8_t offset = 0; offset <= 1 && !detected; offset++) { + + uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]); + + if (offset == 0) { +#if defined(USE_FLASH_W25Q128FV) + if (!detected && w25q128fv_identify(&flashDevice, jedecID)) { + detected = true; + } +#endif + } + + if (offset == 1) { +#ifdef USE_OCTOSPI_EXPERIMENTAL + if (!memoryMappedModeEnabledOnBoot) { + // These flash chips DO NOT support memory mapped mode; suitable flash read commands must be available. +#if defined(USE_FLASH_W25N01G) + if (!detected && w25n01g_identify(&flashDevice, jedecID)) { + detected = true; + } +#endif +#if defined(USE_FLASH_W25M02G) + if (!detected && w25m_identify(&flashDevice, jedecID)) { + detected = true; + } +#endif + } +#endif + } + } + phase++; + } while (phase != BAIL && !detected); + + if (memoryMappedModeEnabledOnBoot) { + flashMemoryMappedModeEnable(); + } + return detected; + +} +#endif // USE_FLASH_OCTOSPI + +#ifdef USE_FLASH_QUADSPI static bool flashQuadSpiInit(const flashConfig_t *flashConfig) { bool detected = false; @@ -63,6 +197,9 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig) QUADSPI_TypeDef *hqspi = quadSpiInstanceByDevice(QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice)); + flashDevice.io.handle.quadSpi = hqspi; + flashDevice.io.mode = FLASHIO_QUADSPI; + do { quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_INITIALISATION); @@ -87,19 +224,16 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig) continue; } - flashDevice.io.handle.quadSpi = hqspi; - flashDevice.io.mode = FLASHIO_QUADSPI; - quadSpiSetDivisor(hqspi, QUADSPI_CLOCK_ULTRAFAST); for (uint8_t offset = 0; offset <= 1 && !detected; offset++) { - uint32_t chipID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]); + uint32_t jedecID = (readIdResponse[offset + 0] << 16) | (readIdResponse[offset + 1] << 8) | (readIdResponse[offset + 2]); if (offset == 0) { -#ifdef USE_FLASH_W25Q128FV - if (!detected && w25q128fv_detect(&flashDevice, chipID)) { +#if defined(USE_FLASH_W25Q128FV) + if (!detected && w25q128fv_identify(&flashDevice, jedecID)) { detected = true; } #endif @@ -112,20 +246,20 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig) } if (offset == 1) { -#ifdef USE_FLASH_W25N01G - if (!detected && w25n01g_detect(&flashDevice, chipID)) { +#if defined(USE_FLASH_W25N01G) + if (!detected && w25n01g_identify(&flashDevice, jedecID)) { detected = true; } #endif #if defined(USE_FLASH_W25M02G) - if (!detected && w25m_detect(&flashDevice, chipID)) { + if (!detected && w25m_identify(&flashDevice, jedecID)) { detected = true; } #endif } if (detected) { - flashDevice.geometry.jedecId = chipID; + flashDevice.geometry.jedecId = jedecID; } } phase++; @@ -133,15 +267,9 @@ static bool flashQuadSpiInit(const flashConfig_t *flashConfig) return detected; } -#endif // USE_QUADSPI - -#ifdef USE_SPI - -void flashPreInit(const flashConfig_t *flashConfig) -{ - spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1); -} +#endif // USE_FLASH_QUADSPI +#ifdef USE_FLASH_SPI static bool flashSpiInit(const flashConfig_t *flashConfig) { bool detected = false; @@ -186,39 +314,39 @@ static bool flashSpiInit(const flashConfig_t *flashConfig) spiReadRegBuf(dev, FLASH_INSTRUCTION_RDID, readIdResponse, sizeof(readIdResponse)); // Manufacturer, memory type, and capacity - uint32_t chipID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]); + uint32_t jedecID = (readIdResponse[0] << 16) | (readIdResponse[1] << 8) | (readIdResponse[2]); #ifdef USE_FLASH_M25P16 - if (m25p16_detect(&flashDevice, chipID)) { + if (m25p16_identify(&flashDevice, jedecID)) { detected = true; } #endif #if defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25M) - if (!detected && w25m_detect(&flashDevice, chipID)) { + if (!detected && w25m_identify(&flashDevice, jedecID)) { detected = true; } #endif if (!detected) { // Newer chips - chipID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]); + jedecID = (readIdResponse[1] << 16) | (readIdResponse[2] << 8) | (readIdResponse[3]); } #ifdef USE_FLASH_W25N01G - if (!detected && w25n01g_detect(&flashDevice, chipID)) { + if (!detected && w25n01g_identify(&flashDevice, jedecID)) { detected = true; } #endif #ifdef USE_FLASH_W25M02G - if (!detected && w25m_detect(&flashDevice, chipID)) { + if (!detected && w25m_identify(&flashDevice, jedecID)) { detected = true; } #endif if (detected) { - flashDevice.geometry.jedecId = chipID; + flashDevice.geometry.jedecId = jedecID; return detected; } @@ -226,39 +354,65 @@ static bool flashSpiInit(const flashConfig_t *flashConfig) return false; } -#endif // USE_SPI +#endif // USE_FLASH_SPI + +void flashPreInit(const flashConfig_t *flashConfig) +{ + spiPreinitRegister(flashConfig->csTag, IOCFG_IPU, 1); +} bool flashDeviceInit(const flashConfig_t *flashConfig) { -#ifdef USE_SPI + bool haveFlash = false; + +#ifdef USE_FLASH_SPI bool useSpi = (SPI_CFG_TO_DEV(flashConfig->spiDevice) != SPIINVALID); if (useSpi) { - return flashSpiInit(flashConfig); + haveFlash = flashSpiInit(flashConfig); } #endif -#ifdef USE_QUADSPI +#ifdef USE_FLASH_QUADSPI bool useQuadSpi = (QUADSPI_CFG_TO_DEV(flashConfig->quadSpiDevice) != QUADSPIINVALID); if (useQuadSpi) { - return flashQuadSpiInit(flashConfig); + haveFlash = flashQuadSpiInit(flashConfig); } #endif - return false; +#ifdef USE_FLASH_OCTOSPI + bool useOctoSpi = (OCTOSPI_CFG_TO_DEV(flashConfig->octoSpiDevice) != OCTOSPIINVALID); + if (useOctoSpi) { + haveFlash = flashOctoSpiInit(flashConfig); + } +#endif + + if (haveFlash && flashDevice.vTable->configure) { + uint32_t configurationFlags = 0; + +#ifdef USE_FLASH_MEMORY_MAPPED + if (isMemoryMappedModeEnabledOnBoot()) { + configurationFlags |= FLASH_CF_SYSTEM_IS_MEMORY_MAPPED; + } +#endif + + flashDevice.vTable->configure(&flashDevice, configurationFlags); + } + + return haveFlash; } -bool flashIsReady(void) +MMFLASH_CODE bool flashIsReady(void) { return flashDevice.vTable->isReady(&flashDevice); } -bool flashWaitForReady(void) +MMFLASH_CODE bool flashWaitForReady(void) { return flashDevice.vTable->waitForReady(&flashDevice); } -void flashEraseSector(uint32_t address) +MMFLASH_CODE void flashEraseSector(uint32_t address) { flashDevice.callback = NULL; flashDevice.vTable->eraseSector(&flashDevice, address); @@ -273,12 +427,12 @@ void flashEraseCompletely(void) /* The callback, if provided, will receive the totoal number of bytes transfered * by each call to flashPageProgramContinue() once the transfer completes. */ -void flashPageProgramBegin(uint32_t address, void (*callback)(uint32_t length)) +MMFLASH_CODE void flashPageProgramBegin(uint32_t address, void (*callback)(uint32_t length)) { flashDevice.vTable->pageProgramBegin(&flashDevice, address, callback); } -uint32_t flashPageProgramContinue(const uint8_t **buffers, uint32_t *bufferSizes, uint32_t bufferCount) +MMFLASH_CODE uint32_t flashPageProgramContinue(const uint8_t **buffers, uint32_t *bufferSizes, uint32_t bufferCount) { uint32_t maxBytesToWrite = flashDevice.geometry.pageSize - (flashDevice.currentWriteAddress % flashDevice.geometry.pageSize); @@ -299,23 +453,23 @@ uint32_t flashPageProgramContinue(const uint8_t **buffers, uint32_t *bufferSizes return flashDevice.vTable->pageProgramContinue(&flashDevice, buffers, bufferSizes, bufferCount); } -void flashPageProgramFinish(void) +MMFLASH_CODE void flashPageProgramFinish(void) { flashDevice.vTable->pageProgramFinish(&flashDevice); } -void flashPageProgram(uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) +MMFLASH_CODE void flashPageProgram(uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) { flashDevice.vTable->pageProgram(&flashDevice, address, data, length, callback); } -int flashReadBytes(uint32_t address, uint8_t *buffer, uint32_t length) +MMFLASH_CODE int flashReadBytes(uint32_t address, uint8_t *buffer, uint32_t length) { flashDevice.callback = NULL; return flashDevice.vTable->readBytes(&flashDevice, address, buffer, length); } -void flashFlush(void) +MMFLASH_CODE void flashFlush(void) { if (flashDevice.vTable->flush) { flashDevice.vTable->flush(&flashDevice); @@ -381,7 +535,7 @@ static void flashConfigurePartitions(void) startSector = 0; #endif -#if defined(CONFIG_IN_EXTERNAL_FLASH) +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) const uint32_t configSize = EEPROM_SIZE; flashSector_t configSectors = (configSize / flashGeometry->sectorSize); diff --git a/src/main/drivers/flash.h b/src/main/drivers/flash.h index 426f8479fd..da75304bb6 100644 --- a/src/main/drivers/flash.h +++ b/src/main/drivers/flash.h @@ -48,6 +48,16 @@ typedef struct flashGeometry_s { uint32_t jedecId; } flashGeometry_t; + +typedef enum { + /* + * When set it indicates the system was booted in memory mapped mode, flash chip is already configured by + * the bootloader and does not need re-configuration. + * When un-set the system was booted normally and the flash chip needs configuration before use. + */ + FLASH_CF_SYSTEM_IS_MEMORY_MAPPED = (1 << 0), +} flashConfigurationFlags_e; + void flashPreInit(const flashConfig_t *flashConfig); bool flashInit(const flashConfig_t *flashConfig); @@ -63,6 +73,10 @@ int flashReadBytes(uint32_t address, uint8_t *buffer, uint32_t length); void flashFlush(void); const flashGeometry_t *flashGetGeometry(void); +void flashMemoryMappedModeDisable(void); +void flashMemoryMappedModeEnable(void); + + // // flash partitioning api // diff --git a/src/main/drivers/flash_impl.h b/src/main/drivers/flash_impl.h index afa0fdd1a6..6bd88bd8db 100644 --- a/src/main/drivers/flash_impl.h +++ b/src/main/drivers/flash_impl.h @@ -22,6 +22,30 @@ * Author: jflyper */ +/* + * Each flash chip should: + * + * * expose a public `identify` method. + * - return true if the driver supports the passed JEDEC ID and false otherwise. + * - configure the `geometry` member of the flashDevice_t or set all `geometry` members to 0 if driver doesn't support the JEDEC ID. + * - configure the `vTable` member, with an appropriate API. + * - configure remaining flashDevice_t members, as appropriate. + * * not reconfigure the bus or flash chip when in memory mapped mode. + * - the firmware is free to do whatever it wants when memory mapped mode is disabled + * - when memory mapped mode is restored, e.g. after saving config to external flash, it should be in + * the same state that firmware found it in before the firmware disabled memory mapped mode. + * + * When memory mapped mode is disabled the following applies to all flash chip drivers uses in a memory mapped system: + * - do not call any methods or use data from the flash chip. i.e. memory mapped code/data is INACCESSIBLE. + * i.e. when saving the config, *ALL* the code to erase a block and write data should be in RAM, + * this includes any `delay` methods. + * - not require the use of use any ISRs - interrupts are disabled during flash access when memory mapped mode is disabled. + * + * When compiling a driver for use in a memory mapped flash system the following applies: + * - the vTable must live in RAM so it can be used when memory mapped mode is disabled. + * - other constant data structures that usually live in flash memory must be stored in RAM. + * - methods used to erase sectors, write data and read data much live in RAM. + */ #pragma once #include "drivers/bus.h" @@ -32,20 +56,30 @@ struct flashVTable_s; typedef enum { FLASHIO_NONE = 0, FLASHIO_SPI, - FLASHIO_QUADSPI + FLASHIO_QUADSPI, + FLASHIO_OCTOSPI, } flashDeviceIoMode_e; typedef struct flashDeviceIO_s { union { + #ifdef USE_FLASH_SPI extDevice_t *dev; // Device interface dependent handle (spi/i2c) - #ifdef USE_QUADSPI + #endif + #ifdef USE_FLASH_QUADSPI QUADSPI_TypeDef *quadSpi; #endif + #ifdef USE_FLASH_OCTOSPI + OCTOSPI_TypeDef *octoSpi; + #endif } handle; flashDeviceIoMode_e mode; } flashDeviceIO_t; typedef struct flashDevice_s { + // + // members to be configured by the flash chip implementation + // + const struct flashVTable_s *vTable; flashGeometry_t geometry; uint32_t currentWriteAddress; @@ -55,21 +89,33 @@ typedef struct flashDevice_s { // when it is definitely ready already. bool couldBeBusy; uint32_t timeoutAt; + + // + // members configured by the flash detection system, read-only from the flash chip implementation's perspective. + // + flashDeviceIO_t io; void (*callback)(uint32_t arg); uint32_t callbackArg; } flashDevice_t; typedef struct flashVTable_s { + void (*configure)(flashDevice_t *fdevice, uint32_t configurationFlags); + bool (*isReady)(flashDevice_t *fdevice); bool (*waitForReady)(flashDevice_t *fdevice); + void (*eraseSector)(flashDevice_t *fdevice, uint32_t address); void (*eraseCompletely)(flashDevice_t *fdevice); + void (*pageProgramBegin)(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)); uint32_t (*pageProgramContinue)(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount); void (*pageProgramFinish)(flashDevice_t *fdevice); void (*pageProgram)(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)); + void (*flush)(flashDevice_t *fdevice); + int (*readBytes)(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length); + const flashGeometry_t *(*getGeometry)(flashDevice_t *fdevice); } flashVTable_t; diff --git a/src/main/drivers/flash_m25p16.c b/src/main/drivers/flash_m25p16.c index dfa10252f1..c4a24e1bda 100644 --- a/src/main/drivers/flash_m25p16.c +++ b/src/main/drivers/flash_m25p16.c @@ -195,13 +195,13 @@ static bool m25p16_waitForReady(flashDevice_t *fdevice) * * Returns true if we get valid ident, false if something bad happened like there is no M25P16. */ -bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID) +bool m25p16_identify(flashDevice_t *fdevice, uint32_t jedecID) { flashGeometry_t *geometry = &fdevice->geometry; uint8_t index; for (index = 0; m25p16FlashConfig[index].jedecID; index++) { - if (m25p16FlashConfig[index].jedecID == chipID) { + if (m25p16FlashConfig[index].jedecID == jedecID) { maxClkSPIHz = m25p16FlashConfig[index].maxClkSPIMHz * 1000000; maxReadClkSPIHz = m25p16FlashConfig[index].maxReadClkSPIMHz * 1000000; geometry->sectors = m25p16FlashConfig[index].sectors; @@ -224,11 +224,32 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID) geometry->sectorSize = geometry->pagesPerSector * geometry->pageSize; geometry->totalSize = geometry->sectorSize * geometry->sectors; + fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + + if (fdevice->io.mode == FLASHIO_SPI) { + fdevice->vTable = &m25p16_vTable; + } +#ifdef USE_QUADSPI + else if (fdevice->io.mode == FLASHIO_QUADSPI) { + fdevice->vTable = &m25p16Qspi_vTable; + } +#endif + return true; +} + +void m25p16_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +{ + if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { + return; + } + if (fdevice->io.mode == FLASHIO_SPI) { // Adjust the SPI bus clock frequency spiSetClkDivisor(fdevice->io.handle.dev, spiCalculateDivider(maxReadClkSPIHz)); } + flashGeometry_t *geometry = &fdevice->geometry; if (geometry->totalSize > 16 * 1024 * 1024) { fdevice->isLargeFlash = true; @@ -244,20 +265,9 @@ bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID) } #endif } - - fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be - - if (fdevice->io.mode == FLASHIO_SPI) { - fdevice->vTable = &m25p16_vTable; - } -#ifdef USE_QUADSPI - else if (fdevice->io.mode == FLASHIO_QUADSPI) { - fdevice->vTable = &m25p16Qspi_vTable; - } -#endif - return true; } + static void m25p16_setCommandAddress(uint8_t *buf, uint32_t address, bool useLongAddress) { if (useLongAddress) { @@ -612,6 +622,7 @@ static const flashGeometry_t* m25p16_getGeometry(flashDevice_t *fdevice) } const flashVTable_t m25p16_vTable = { + .configure = m25p16_configure, .isReady = m25p16_isReady, .waitForReady = m25p16_waitForReady, .eraseSector = m25p16_eraseSector, diff --git a/src/main/drivers/flash_m25p16.h b/src/main/drivers/flash_m25p16.h index fa606a4947..2e0d186d02 100644 --- a/src/main/drivers/flash_m25p16.h +++ b/src/main/drivers/flash_m25p16.h @@ -22,4 +22,4 @@ #include "flash_impl.h" -bool m25p16_detect(flashDevice_t *fdevice, uint32_t chipID); +bool m25p16_identify(flashDevice_t *fdevice, uint32_t jedecID); diff --git a/src/main/drivers/flash_w25m.c b/src/main/drivers/flash_w25m.c index 9600e54175..34d19ea21a 100644 --- a/src/main/drivers/flash_w25m.c +++ b/src/main/drivers/flash_w25m.c @@ -114,10 +114,10 @@ static bool w25m_waitForReady(flashDevice_t *fdevice) return true; } -bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID) +bool w25m_identify(flashDevice_t *fdevice, uint32_t jedecID) { - switch (chipID) { + switch (jedecID) { #ifdef USE_FLASH_W25M512 case JEDEC_ID_WINBOND_W25M512: // W25Q256 x 2 @@ -127,7 +127,7 @@ bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID) w25m_dieSelect(fdevice->io.handle.dev, die); dieDevice[die].io.handle.dev = fdevice->io.handle.dev; dieDevice[die].io.mode = fdevice->io.mode; - m25p16_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256); + m25p16_identify(&dieDevice[die], JEDEC_ID_WINBOND_W25Q256); } fdevice->geometry.flashType = FLASH_TYPE_NOR; @@ -143,7 +143,7 @@ bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID) w25m_dieSelect(fdevice->io.handle.dev, die); dieDevice[die].io.handle.dev = fdevice->io.handle.dev; dieDevice[die].io.mode = fdevice->io.mode; - w25n01g_detect(&dieDevice[die], JEDEC_ID_WINBOND_W25N01GV); + w25n01g_identify(&dieDevice[die], JEDEC_ID_WINBOND_W25N01GV); } fdevice->geometry.flashType = FLASH_TYPE_NAND; @@ -170,6 +170,14 @@ bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID) return true; } +void w25m_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +{ + for (int dieNumber = 0 ; dieNumber < dieCount ; dieNumber++) { + w25m_dieSelect(fdevice->io.handle.dev, dieNumber); + dieDevice[dieNumber].vTable->configure(&dieDevice[dieNumber], configurationFlags); + } +} + void w25m_eraseSector(flashDevice_t *fdevice, uint32_t address) { int dieNumber = address / dieSize; @@ -255,6 +263,7 @@ const flashGeometry_t* w25m_getGeometry(flashDevice_t *fdevice) } static const flashVTable_t w25m_vTable = { + .configure = w25m_configure, .isReady = w25m_isReady, .waitForReady = w25m_waitForReady, .eraseSector = w25m_eraseSector, diff --git a/src/main/drivers/flash_w25m.h b/src/main/drivers/flash_w25m.h index f778a07eb6..5d35df4a4b 100644 --- a/src/main/drivers/flash_w25m.h +++ b/src/main/drivers/flash_w25m.h @@ -22,4 +22,4 @@ #include "flash_impl.h" -bool w25m_detect(flashDevice_t *fdevice, uint32_t chipID); +bool w25m_identify(flashDevice_t *fdevice, uint32_t jedecID); diff --git a/src/main/drivers/flash_w25n01g.c b/src/main/drivers/flash_w25n01g.c index b69f8f1845..87c3f60419 100644 --- a/src/main/drivers/flash_w25n01g.c +++ b/src/main/drivers/flash_w25n01g.c @@ -124,9 +124,9 @@ #define W25N01G_TIMEOUT_RESET_MS 500 // tRSTmax = 500ms // Sizes (in bits) -#define W28N01G_STATUS_REGISTER_SIZE 8 -#define W28N01G_STATUS_PAGE_ADDRESS_SIZE 16 -#define W28N01G_STATUS_COLUMN_ADDRESS_SIZE 16 +#define W25N01G_STATUS_REGISTER_SIZE 8 +#define W25N01G_STATUS_PAGE_ADDRESS_SIZE 16 +#define W25N01G_STATUS_COLUMN_ADDRESS_SIZE 16 typedef struct bblut_s { uint16_t pba; @@ -188,7 +188,7 @@ static void w25n01g_performCommandWithPageAddress(flashDeviceIO_t *io, uint8_t c else if (io->mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; - quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W28N01G_STATUS_PAGE_ADDRESS_SIZE + 8); + quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, pageAddress & 0xffff, W25N01G_STATUS_PAGE_ADDRESS_SIZE + 8); } #endif } @@ -221,8 +221,8 @@ static uint8_t w25n01g_readRegister(flashDeviceIO_t *io, uint8_t reg) QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; - uint8_t in[1]; - quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, in, sizeof(in)); + uint8_t in[W25N01G_STATUS_REGISTER_SIZE / 8]; + quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_STATUS_REG, 0, reg, W25N01G_STATUS_REGISTER_SIZE, in, sizeof(in)); return in[0]; } @@ -253,7 +253,7 @@ static void w25n01g_writeRegister(flashDeviceIO_t *io, uint8_t reg, uint8_t data else if (io->mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; - quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W28N01G_STATUS_REGISTER_SIZE, &data, 1); + quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_WRITE_STATUS_REG, 0, reg, W25N01G_STATUS_REGISTER_SIZE, &data, 1); } #endif } @@ -311,18 +311,11 @@ static void w25n01g_writeEnable(flashDevice_t *fdevice) fdevice->couldBeBusy = true; } -/** - * Read chip identification and geometry information (into global `geometry`). - * - * Returns true if we get valid ident, false if something bad happened like there is no M25P16. - */ const flashVTable_t w25n01g_vTable; -static void w25n01g_deviceInit(flashDevice_t *flashdev); - -bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID) +bool w25n01g_identify(flashDevice_t *fdevice, uint32_t jedecID) { - switch (chipID) { + switch (jedecID) { case JEDEC_ID_WINBOND_W25N01GV: fdevice->geometry.sectors = 1024; // Blocks fdevice->geometry.pagesPerSector = 64; // Pages/Blocks @@ -348,6 +341,19 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID) W25N01G_BB_MANAGEMENT_START_BLOCK + W25N01G_BB_MANAGEMENT_BLOCKS - 1); fdevice->couldBeBusy = true; // Just for luck we'll assume the chip could be busy even though it isn't specced to be + fdevice->vTable = &w25n01g_vTable; + + return true; +} + +static void w25n01g_deviceInit(flashDevice_t *flashdev); + + +void w25n01g_configure(flashDevice_t *fdevice, uint32_t configurationFlags) +{ + if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { + return; + } w25n01g_deviceReset(fdevice); @@ -366,10 +372,6 @@ bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID) // If it ever run out, the device becomes unusable. w25n01g_deviceInit(fdevice); - - fdevice->vTable = &w25n01g_vTable; - - return true; } /** @@ -422,7 +424,7 @@ static void w25n01g_programDataLoad(flashDevice_t *fdevice, uint16_t columnAddre else if (fdevice->io.mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; - quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); + quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_PROGRAM_DATA_LOAD, 0, columnAddress, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); } #endif @@ -453,7 +455,7 @@ static void w25n01g_randomProgramDataLoad(flashDevice_t *fdevice, uint16_t colum else if (fdevice->io.mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; - quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); + quadSpiTransmitWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_RANDOM_PROGRAM_DATA_LOAD, 0, columnAddress, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, data, length); } #endif @@ -696,8 +698,8 @@ int w25n01g_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, else if (fdevice->io.mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; - //quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); - quadSpiReceiveWithAddress4LINES(quadSpi, W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); + //quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); + quadSpiReceiveWithAddress4LINES(quadSpi, W25N01G_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); } #endif @@ -765,7 +767,7 @@ int w25n01g_readExtensionBytes(flashDevice_t *fdevice, uint32_t address, uint8_t else if (fdevice->io.mode == FLASHIO_QUADSPI) { QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; - quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W28N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); + quadSpiReceiveWithAddress1LINE(quadSpi, W25N01G_INSTRUCTION_READ_DATA, 8, column, W25N01G_STATUS_COLUMN_ADDRESS_SIZE, buffer, length); } #endif @@ -785,6 +787,7 @@ const flashGeometry_t* w25n01g_getGeometry(flashDevice_t *fdevice) } const flashVTable_t w25n01g_vTable = { + .configure = w25n01g_configure, .isReady = w25n01g_isReady, .waitForReady = w25n01g_waitForReady, .eraseSector = w25n01g_eraseSector, diff --git a/src/main/drivers/flash_w25n01g.h b/src/main/drivers/flash_w25n01g.h index 219a3fa466..ef80c7b6e3 100644 --- a/src/main/drivers/flash_w25n01g.h +++ b/src/main/drivers/flash_w25n01g.h @@ -25,4 +25,4 @@ // JEDEC ID #define JEDEC_ID_WINBOND_W25N01GV 0xEFAA21 -bool w25n01g_detect(flashDevice_t *fdevice, uint32_t chipID); +bool w25n01g_identify(flashDevice_t *fdevice, uint32_t jedecID); diff --git a/src/main/drivers/flash_w25q128fv.c b/src/main/drivers/flash_w25q128fv.c index d005f8e8ee..e8fb03bf13 100644 --- a/src/main/drivers/flash_w25q128fv.c +++ b/src/main/drivers/flash_w25q128fv.c @@ -25,7 +25,7 @@ #include "platform.h" -#if defined(USE_FLASH_W25Q128FV) && defined(USE_QUADSPI) +#if defined(USE_FLASH_W25Q128FV) && (defined(USE_QUADSPI) || defined(USE_OCTOSPI)) #define USE_FLASH_WRITES_USING_4LINES #define USE_FLASH_READS_USING_4LINES @@ -33,15 +33,19 @@ #include "build/debug.h" #include "common/utils.h" +#include "drivers/time.h" #include "drivers/flash.h" #include "drivers/flash_impl.h" #include "drivers/flash_w25q128fv.h" #include "drivers/bus_quadspi.h" +#include "drivers/bus_octospi.h" // JEDEC ID -#define JEDEC_ID_WINBOND_W25Q128FV_SPI 0xEF4018 -#define JEDEC_ID_WINBOND_W25Q128FV_QUADSPI 0xEF6018 -#define JEDEC_ID_WINBOND_W25Q128JV_QUADSPI 0xEF7018 +#define JEDEC_ID_WINBOND_W25Q128FV_SPI 0xEF4018 +#define JEDEC_ID_WINBOND_W25Q128FV_QUADSPI 0xEF6018 +#define JEDEC_ID_WINBOND_W25Q128JV_QUADSPI 0xEF7018 +#define JEDEC_ID_WINBOND_W25Q16JV_SPI 0xEF4015 +#define JEDEC_ID_WINBOND_W25Q16JV_DTR_SPI 0xEF7015 // Device size parameters #define W25Q128FV_PAGE_SIZE 2048 @@ -90,14 +94,14 @@ //#define W25Q128FV_INSTRUCTION_WRITE_DISABLE 0x04 //#define W25Q128FV_INSTRUCTION_PAGE_PROGRAM 0x02 -// Timings (2ms minimum to avoid 1 tick advance in consecutive calls to HAL_GetTick). -#define W25Q128FV_TIMEOUT_PAGE_READ_MS 4 -#define W25Q128FV_TIMEOUT_RESET_MS 2 // tRST = 30us +// Values from W25Q128FV Datasheet Rev L. +#define W25Q128FV_TIMEOUT_PAGE_READ_MS 1 // No minimum specified in datasheet +#define W25Q128FV_TIMEOUT_RESET_MS 1 // tRST = 30us #define W25Q128FV_TIMEOUT_BLOCK_ERASE_64KB_MS 2000 // tBE2max = 2000ms, tBE2typ = 150ms #define W25Q128FV_TIMEOUT_CHIP_ERASE_MS (200 * 1000) // tCEmax 200s, tCEtyp = 40s -#define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 2 // tPPmax = 700us, tPPtyp = 250us -#define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 2 +#define W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS 3 // tPPmax = 3ms, tPPtyp = 0.7ms +#define W25Q128FV_TIMEOUT_WRITE_ENABLE_MS 1 typedef enum { @@ -115,45 +119,71 @@ w25q128fvState_t w25q128fvState = { 0 }; static bool w25q128fv_waitForReady(flashDevice_t *fdevice); static void w25q128fv_waitForTimeout(flashDevice_t *fdevice); -static void w25q128fv_setTimeout(flashDevice_t *fdevice, uint32_t timeoutMillis) +MMFLASH_CODE static void w25q128fv_setTimeout(flashDevice_t *fdevice, timeMs_t timeoutMillis) { - uint32_t now = HAL_GetTick(); - fdevice->timeoutAt = now + timeoutMillis; + timeMs_t nowMs = microsISR() / 1000; + fdevice->timeoutAt = nowMs + timeoutMillis; } -static void w25q128fv_performOneByteCommand(flashDeviceIO_t *io, uint8_t command) +MMFLASH_CODE static void w25q128fv_performOneByteCommand(flashDeviceIO_t *io, uint8_t command) { +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; quadSpiTransmit1LINE(quadSpi, command, 0, NULL, 0); +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = io->handle.octoSpi; + octoSpiTransmit1LINE(octoSpi, command, 0, NULL, 0); +#endif + } -static void w25q128fv_performCommandWithAddress(flashDeviceIO_t *io, uint8_t command, uint32_t address) +MMFLASH_CODE static void w25q128fv_performCommandWithAddress(flashDeviceIO_t *io, uint8_t command, uint32_t address) { +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; quadSpiInstructionWithAddress1LINE(quadSpi, command, 0, address & 0xffffff, W25Q128FV_ADDRESS_BITS); +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = io->handle.octoSpi; + + octoSpiInstructionWithAddress1LINE(octoSpi, command, 0, address & 0xffffff, W25Q128FV_ADDRESS_BITS); +#endif } -static void w25q128fv_writeEnable(flashDevice_t *fdevice) +MMFLASH_CODE static void w25q128fv_writeEnable(flashDevice_t *fdevice) { w25q128fv_performOneByteCommand(&fdevice->io, W25Q128FV_INSTRUCTION_WRITE_ENABLE); } -static uint8_t w25q128fv_readRegister(flashDeviceIO_t *io, uint8_t command) +MMFLASH_CODE static uint8_t w25q128fv_readRegister(flashDeviceIO_t *io, uint8_t command) { + uint8_t in[W25Q128FV_STATUS_REGISTER_BITS / 8] = { 0 }; +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; - uint8_t in[1]; quadSpiReceive1LINE(quadSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8); +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = io->handle.octoSpi; + + octoSpiReceive1LINE(octoSpi, command, 0, in, W25Q128FV_STATUS_REGISTER_BITS / 8); +#endif + return in[0]; } static void w25q128fv_writeRegister(flashDeviceIO_t *io, uint8_t command, uint8_t data) { +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = io->handle.quadSpi; - quadSpiTransmit1LINE(quadSpi, command, 0, &data, W25Q128FV_STATUS_REGISTER_BITS / 8); + quadSpiTransmit1LINE(quadSpi, command, 0, &data, W25Q128FV_STATUS_REGISTER_BITS / 8); +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = io->handle.octoSpi; + + octoSpiTransmit1LINE(octoSpi, command, 0, &data, W25Q128FV_STATUS_REGISTER_BITS / 8); +#endif + } static void w25q128fv_deviceReset(flashDevice_t *fdevice) @@ -203,7 +233,7 @@ static void w25q128fv_deviceReset(flashDevice_t *fdevice) #endif } -bool w25q128fv_isReady(flashDevice_t *fdevice) +MMFLASH_CODE bool w25q128fv_isReady(flashDevice_t *fdevice) { uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG); @@ -212,7 +242,7 @@ bool w25q128fv_isReady(flashDevice_t *fdevice) return !busy; } -static bool w25q128fv_isWritable(flashDevice_t *fdevice) +MMFLASH_CODE static bool w25q128fv_isWritable(flashDevice_t *fdevice) { uint8_t status = w25q128fv_readRegister(&fdevice->io, W25Q128FV_INSTRUCTION_READ_STATUS1_REG); @@ -221,23 +251,23 @@ static bool w25q128fv_isWritable(flashDevice_t *fdevice) return writable; } -bool w25q128fv_hasTimedOut(flashDevice_t *fdevice) +MMFLASH_CODE bool w25q128fv_hasTimedOut(flashDevice_t *fdevice) { - uint32_t now = HAL_GetTick(); - if (cmp32(now, fdevice->timeoutAt) >= 0) { + uint32_t nowMs = microsISR() / 1000; + if (cmp32(nowMs, fdevice->timeoutAt) >= 0) { return true; } return false; } -void w25q128fv_waitForTimeout(flashDevice_t *fdevice) +MMFLASH_CODE void w25q128fv_waitForTimeout(flashDevice_t *fdevice) { while (!w25q128fv_hasTimedOut(fdevice)) { } fdevice->timeoutAt = 0; } -bool w25q128fv_waitForReady(flashDevice_t *fdevice) +MMFLASH_CODE bool w25q128fv_waitForReady(flashDevice_t *fdevice) { bool ready = true; while (!w25q128fv_isReady(fdevice)) { @@ -255,15 +285,24 @@ const flashVTable_t w25q128fv_vTable; static void w25q128fv_deviceInit(flashDevice_t *flashdev); -bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID) +MMFLASH_CODE_NOINLINE bool w25q128fv_identify(flashDevice_t *fdevice, uint32_t jedecID) { - switch (chipID) { + switch (jedecID) { case JEDEC_ID_WINBOND_W25Q128FV_SPI: case JEDEC_ID_WINBOND_W25Q128FV_QUADSPI: case JEDEC_ID_WINBOND_W25Q128JV_QUADSPI: fdevice->geometry.sectors = 256; fdevice->geometry.pagesPerSector = 256; fdevice->geometry.pageSize = 256; + // = 16777216 128MBit 16MB + break; + + case JEDEC_ID_WINBOND_W25Q16JV_DTR_SPI: + case JEDEC_ID_WINBOND_W25Q16JV_SPI: + fdevice->geometry.sectors = 32; + fdevice->geometry.pagesPerSector = 256; + fdevice->geometry.pageSize = 256; + // = 2097152 16MBit 2MB break; default: @@ -276,7 +315,9 @@ bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID) } // use the chip id to determine the initial interface mode on cold-boot. - switch (chipID) { + switch (jedecID) { + case JEDEC_ID_WINBOND_W25Q16JV_SPI: + case JEDEC_ID_WINBOND_W25Q16JV_DTR_SPI: case JEDEC_ID_WINBOND_W25Q128FV_SPI: w25q128fvState.initialMode = INITIAL_MODE_SPI; break; @@ -294,18 +335,24 @@ bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID) fdevice->geometry.sectorSize = fdevice->geometry.pagesPerSector * fdevice->geometry.pageSize; fdevice->geometry.totalSize = fdevice->geometry.sectorSize * fdevice->geometry.sectors; - w25q128fv_deviceReset(fdevice); - - w25q128fv_deviceInit(fdevice); - fdevice->vTable = &w25q128fv_vTable; return true; } -static void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address) +void w25q128fv_configure(flashDevice_t *fdevice, uint32_t configurationFlags) { + if (configurationFlags & FLASH_CF_SYSTEM_IS_MEMORY_MAPPED) { + return; + } + w25q128fv_deviceReset(fdevice); + + w25q128fv_deviceInit(fdevice); +} + +MMFLASH_CODE static void w25q128fv_eraseSector(flashDevice_t *fdevice, uint32_t address) +{ w25q128fv_waitForReady(fdevice); w25q128fv_writeEnable(fdevice); @@ -326,17 +373,26 @@ static void w25q128fv_eraseCompletely(flashDevice_t *fdevice) w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_CHIP_ERASE_MS); } - -static void w25q128fv_loadProgramData(flashDevice_t *fdevice, const uint8_t *data, int length) +MMFLASH_CODE static void w25q128fv_loadProgramData(flashDevice_t *fdevice, const uint8_t *data, int length) { w25q128fv_waitForReady(fdevice); +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; #ifdef USE_FLASH_WRITES_USING_4LINES quadSpiTransmitWithAddress4LINES(quadSpi, W25Q128FV_INSTRUCTION_QUAD_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length); #else quadSpiTransmitWithAddress1LINE(quadSpi, W25Q128FV_INSTRUCTION_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length); +#endif +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = fdevice->io.handle.octoSpi; + +#ifdef USE_FLASH_WRITES_USING_4LINES + octoSpiTransmitWithAddress4LINES(octoSpi, W25Q128FV_INSTRUCTION_QUAD_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length); +#else + octoSpiTransmitWithAddress1LINE(octoSpi, W25Q128FV_INSTRUCTION_PAGE_PROGRAM, 0, w25q128fvState.currentWriteAddress, W25Q128FV_ADDRESS_BITS, data, length); +#endif #endif w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_PAGE_PROGRAM_MS); @@ -344,13 +400,13 @@ static void w25q128fv_loadProgramData(flashDevice_t *fdevice, const uint8_t *dat w25q128fvState.currentWriteAddress += length; } -static void w25q128fv_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) +MMFLASH_CODE static void w25q128fv_pageProgramBegin(flashDevice_t *fdevice, uint32_t address, void (*callback)(uint32_t length)) { fdevice->callback = callback; w25q128fvState.currentWriteAddress = address; } -static uint32_t w25q128fv_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount) +MMFLASH_CODE static uint32_t w25q128fv_pageProgramContinue(flashDevice_t *fdevice, uint8_t const **buffers, uint32_t *bufferSizes, uint32_t bufferCount) { for (uint32_t i = 0; i < bufferCount; i++) { w25q128fv_waitForReady(fdevice); @@ -374,35 +430,45 @@ static uint32_t w25q128fv_pageProgramContinue(flashDevice_t *fdevice, uint8_t co return fdevice->callbackArg; } -static void w25q128fv_pageProgramFinish(flashDevice_t *fdevice) +MMFLASH_CODE static void w25q128fv_pageProgramFinish(flashDevice_t *fdevice) { UNUSED(fdevice); } -static void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) +MMFLASH_CODE static void w25q128fv_pageProgram(flashDevice_t *fdevice, uint32_t address, const uint8_t *data, uint32_t length, void (*callback)(uint32_t length)) { w25q128fv_pageProgramBegin(fdevice, address, callback); w25q128fv_pageProgramContinue(fdevice, &data, &length, 1); w25q128fv_pageProgramFinish(fdevice); } -void w25q128fv_flush(flashDevice_t *fdevice) +MMFLASH_CODE void w25q128fv_flush(flashDevice_t *fdevice) { UNUSED(fdevice); } -static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) +MMFLASH_CODE static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t *buffer, uint32_t length) { if (!w25q128fv_waitForReady(fdevice)) { return 0; } +#if defined(USE_QUADSPI) QUADSPI_TypeDef *quadSpi = fdevice->io.handle.quadSpi; #ifdef USE_FLASH_READS_USING_4LINES bool status = quadSpiReceiveWithAddress4LINES(quadSpi, W25Q128FV_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length); #else bool status = quadSpiReceiveWithAddress1LINE(quadSpi, W25Q128FV_INSTRUCTION_FAST_READ, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length); #endif +#elif defined(USE_OCTOSPI) + OCTOSPI_TypeDef *octoSpi = fdevice->io.handle.octoSpi; +#ifdef USE_FLASH_READS_USING_4LINES + bool status = octoSpiReceiveWithAddress4LINES(octoSpi, W25Q128FV_INSTRUCTION_FAST_READ_QUAD_OUTPUT, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length); +#else + bool status = octoSpiReceiveWithAddress1LINE(octoSpi, W25Q128FV_INSTRUCTION_FAST_READ, 8, address, W25Q128FV_ADDRESS_BITS, buffer, length); +#endif +#endif + w25q128fv_setTimeout(fdevice, W25Q128FV_TIMEOUT_PAGE_READ_MS); if (!status) { @@ -412,14 +478,13 @@ static int w25q128fv_readBytes(flashDevice_t *fdevice, uint32_t address, uint8_t return length; } - - const flashGeometry_t* w25q128fv_getGeometry(flashDevice_t *fdevice) { return &fdevice->geometry; } -const flashVTable_t w25q128fv_vTable = { +MMFLASH_DATA const flashVTable_t w25q128fv_vTable = { + .configure = w25q128fv_configure, .isReady = w25q128fv_isReady, .waitForReady = w25q128fv_waitForReady, .eraseSector = w25q128fv_eraseSector, diff --git a/src/main/drivers/flash_w25q128fv.h b/src/main/drivers/flash_w25q128fv.h index d28de244fa..4a82c0d998 100644 --- a/src/main/drivers/flash_w25q128fv.h +++ b/src/main/drivers/flash_w25q128fv.h @@ -3,5 +3,5 @@ #ifdef USE_FLASH_W25Q128FV -bool w25q128fv_detect(flashDevice_t *fdevice, uint32_t chipID); +bool w25q128fv_identify(flashDevice_t *fdevice, uint32_t jedecID); #endif diff --git a/src/main/drivers/motor.c b/src/main/drivers/motor.c index f6917d0b47..e604303f0d 100644 --- a/src/main/drivers/motor.c +++ b/src/main/drivers/motor.c @@ -60,15 +60,49 @@ void motorWriteAll(float *values) { #ifdef USE_PWM_OUTPUT if (motorDevice->enabled) { +#ifdef USE_DSHOT_BITBANG + if (isDshotBitbangActive(&motorConfig()->dev)) { + // Initialise the output buffers + if (motorDevice->vTable.updateInit) { + motorDevice->vTable.updateInit(); + } + + // Update the motor data + for (int i = 0; i < motorDevice->count; i++) { + motorDevice->vTable.write(i, values[i]); + } + + // Don't attempt to write commands to the motors if telemetry is still being received + if (motorDevice->vTable.telemetryWait) { + (void)motorDevice->vTable.telemetryWait(); + } + + // Trigger the transmission of the motor data + motorDevice->vTable.updateComplete(); + + // Perform the decode of the last data received + // New data will be received once the send of motor data, triggered above, completes #if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY) - if (!motorDevice->vTable.updateStart()) { - return; - } + motorDevice->vTable.decodeTelemetry(); #endif - for (int i = 0; i < motorDevice->count; i++) { - motorDevice->vTable.write(i, values[i]); + } else +#endif + { + // Perform the decode of the last data received + // New data will be received once the send of motor data, triggered above, completes +#if defined(USE_DSHOT) && defined(USE_DSHOT_TELEMETRY) + motorDevice->vTable.decodeTelemetry(); +#endif + + // Update the motor data + for (int i = 0; i < motorDevice->count; i++) { + motorDevice->vTable.write(i, values[i]); + } + + // Trigger the transmission of the motor data + motorDevice->vTable.updateComplete(); + } - motorDevice->vTable.updateComplete(); } #else UNUSED(values); @@ -193,7 +227,7 @@ static bool motorIsEnabledNull(uint8_t index) return false; } -bool motorUpdateStartNull(void) +bool motorDecodeTelemetryNull(void) { return true; } @@ -235,7 +269,7 @@ static const motorVTable_t motorNullVTable = { .enable = motorEnableNull, .disable = motorDisableNull, .isMotorEnabled = motorIsEnabledNull, - .updateStart = motorUpdateStartNull, + .decodeTelemetry = motorDecodeTelemetryNull, .write = motorWriteNull, .writeInt = motorWriteIntNull, .updateComplete = motorUpdateCompleteNull, diff --git a/src/main/drivers/motor.h b/src/main/drivers/motor.h index b8dcabaf39..fb9846aa6f 100644 --- a/src/main/drivers/motor.h +++ b/src/main/drivers/motor.h @@ -50,7 +50,9 @@ typedef struct motorVTable_s { bool (*enable)(void); void (*disable)(void); bool (*isMotorEnabled)(uint8_t index); - bool (*updateStart)(void); + bool (*telemetryWait)(void); + bool (*decodeTelemetry)(void); + void (*updateInit)(void); void (*write)(uint8_t index, float value); void (*writeInt)(uint8_t index, uint16_t value); void (*updateComplete)(void); @@ -70,7 +72,7 @@ typedef struct motorDevice_s { void motorPostInitNull(); void motorWriteNull(uint8_t index, float value); -bool motorUpdateStartNull(void); +bool motorDecodeTelemetryNull(void); void motorUpdateCompleteNull(void); void motorPostInit(); diff --git a/src/main/drivers/pwm_output.c b/src/main/drivers/pwm_output.c index 1a031322f0..5c996b7bbd 100644 --- a/src/main/drivers/pwm_output.c +++ b/src/main/drivers/pwm_output.c @@ -215,7 +215,7 @@ motorDevice_t *motorPwmDevInit(const motorDevConfig_t *motorConfig, uint16_t idl } motorPwmDevice.vTable.write = pwmWriteStandard; - motorPwmDevice.vTable.updateStart = motorUpdateStartNull; + motorPwmDevice.vTable.decodeTelemetry = motorDecodeTelemetryNull; motorPwmDevice.vTable.updateComplete = useUnsyncedPwm ? motorUpdateCompleteNull : pwmCompleteOneshotMotorUpdate; for (int motorIndex = 0; motorIndex < MAX_SUPPORTED_MOTORS && motorIndex < motorCount; motorIndex++) { diff --git a/src/main/drivers/pwm_output_dshot_shared.c b/src/main/drivers/pwm_output_dshot_shared.c index 6d92deb338..c32d3ae366 100644 --- a/src/main/drivers/pwm_output_dshot_shared.c +++ b/src/main/drivers/pwm_output_dshot_shared.c @@ -176,7 +176,11 @@ static uint32_t decodeTelemetryPacket(uint32_t buffer[], uint32_t count) #endif #ifdef USE_DSHOT_TELEMETRY -FAST_CODE_NOINLINE bool pwmStartDshotMotorUpdate(void) +/** + * Process dshot telemetry packets before switching the channels back to outputs + * +*/ +FAST_CODE_NOINLINE bool pwmTelemetryDecode(void) { if (!useDshotTelemetry) { return true; diff --git a/src/main/drivers/pwm_output_dshot_shared.h b/src/main/drivers/pwm_output_dshot_shared.h index 9e4ef0faf8..7c282d5008 100644 --- a/src/main/drivers/pwm_output_dshot_shared.h +++ b/src/main/drivers/pwm_output_dshot_shared.h @@ -59,7 +59,7 @@ void pwmDshotSetDirectionOutput( #endif ); -bool pwmStartDshotMotorUpdate(void); +bool pwmTelemetryDecode(void); #endif #endif diff --git a/src/main/drivers/rx/rx_sx1280.c b/src/main/drivers/rx/rx_sx1280.c index 34546b8dff..b3f7ba988f 100644 --- a/src/main/drivers/rx/rx_sx1280.c +++ b/src/main/drivers/rx/rx_sx1280.c @@ -572,7 +572,7 @@ static void sx1280StartTransmittingDMA(extiCallbackRec_t *cb); FAST_IRQ_HANDLER void sx1280ISR(void) { // Only attempt to access the SX1280 if it is currently idle to avoid any race condition - ATOMIC_BLOCK(NVIC_PRIO_MAX) { + ATOMIC_BLOCK(NVIC_PRIO_RX_INT_EXTI) { if (sx1280EnableBusy()) { pendingISR = false; sx1280SetBusyFn(sx1280IrqGetStatus); diff --git a/src/main/drivers/system.c b/src/main/drivers/system.c index b17522d848..ec16015e1e 100644 --- a/src/main/drivers/system.c +++ b/src/main/drivers/system.c @@ -103,7 +103,7 @@ void SysTick_Handler(void) // Return system uptime in microseconds (rollover in 70minutes) -uint32_t microsISR(void) +MMFLASH_CODE_NOINLINE uint32_t microsISR(void) { register uint32_t ms, pending, cycle_cnt; @@ -262,7 +262,7 @@ void failureMode(failureMode_e mode) void initialiseMemorySections(void) { #ifdef USE_ITCM_RAM - /* Load functions into ITCM RAM */ + /* Load fast-functions into ITCM RAM */ extern uint8_t tcm_code_start; extern uint8_t tcm_code_end; extern uint8_t tcm_code; @@ -284,6 +284,15 @@ void initialiseMemorySections(void) extern uint8_t _sfastram_idata; memcpy(&_sfastram_data, &_sfastram_idata, (size_t) (&_efastram_data - &_sfastram_data)); #endif + +#ifdef USE_RAM_CODE + /* Load slow-functions into ITCM RAM */ + extern uint8_t ram_code_start; + extern uint8_t ram_code_end; + extern uint8_t ram_code; + memcpy(&ram_code_start, &ram_code, (size_t) (&ram_code_end - &ram_code_start)); +#endif + } #ifdef STM32H7 diff --git a/src/main/drivers/system.h b/src/main/drivers/system.h index 2760928384..21b1719c67 100644 --- a/src/main/drivers/system.h +++ b/src/main/drivers/system.h @@ -73,6 +73,10 @@ uint32_t getCycleCounter(void); void systemProcessResetReason(void); #endif +// memory +void memoryMappedModeInit(void); +bool isMemoryMappedModeEnabledOnBoot(void); + void initialiseMemorySections(void); #ifdef STM32H7 void initialiseD2MemorySections(void); diff --git a/src/main/drivers/system_stm32h7xx.c b/src/main/drivers/system_stm32h7xx.c index 49f96f831b..8f4f8ce79b 100644 --- a/src/main/drivers/system_stm32h7xx.c +++ b/src/main/drivers/system_stm32h7xx.c @@ -62,6 +62,41 @@ bool isMPUSoftReset(void) return false; } +#if defined(USE_FLASH_MEMORY_MAPPED) + +/* + * Memory mapped targets use a bootloader which enables memory mapped mode before running the firmware directly from external flash. + * Code running from external flash, i.e. most of the firmware, must not disable peripherals or reconfigure pins used by the CPU to access the flash chip. + * Refer to reference manuals and linker scripts for addresses of memory mapped regions. + * STM32H830 - RM0468 "Table 6. Memory map and default device memory area attributes" + * + * If the config is also stored on the same flash chip that code is running from then VERY special care must be taken when detecting the flash chip + * and when writing an updated config back to the flash. + */ + +static bool memoryMappedModeEnabledOnBoot = false; + +bool isMemoryMappedModeEnabledOnBoot(void) +{ + return memoryMappedModeEnabledOnBoot; +} + +void memoryMappedModeInit(void) +{ +#if defined(STM32H730xx) || defined(STM32H723xx) + // Smaller MCU packages have ONE OCTOSPI interface which supports memory mapped mode. + memoryMappedModeEnabledOnBoot = READ_BIT(OCTOSPI1->CR, OCTOSPI_CR_FMODE) == OCTOSPI_CR_FMODE; +#else +#error No Memory Mapped implementation on current MCU. +#endif +} +#else +bool isMemoryMappedModeEnabledOnBoot(void) +{ + return false; +} +#endif + void systemInit(void) { // Configure NVIC preempt/priority groups diff --git a/src/main/fc/core.c b/src/main/fc/core.c index 1010285e59..3445aa5543 100644 --- a/src/main/fc/core.c +++ b/src/main/fc/core.c @@ -495,7 +495,7 @@ void tryArm(void) const timeUs_t currentTimeUs = micros(); #ifdef USE_DSHOT - if (currentTimeUs - getLastDshotBeaconCommandTimeUs() < DSHOT_BEACON_GUARD_DELAY_US) { + if (cmpTimeUs(currentTimeUs, getLastDshotBeaconCommandTimeUs()) < DSHOT_BEACON_GUARD_DELAY_US) { if (tryingToArm == ARMING_DELAYED_DISARMED) { if (IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) { tryingToArm = ARMING_DELAYED_CRASHFLIP; diff --git a/src/main/fc/init.c b/src/main/fc/init.c index 3ab56faf26..f6aa8f59b1 100644 --- a/src/main/fc/init.c +++ b/src/main/fc/init.c @@ -47,6 +47,7 @@ #include "drivers/adc.h" #include "drivers/bus.h" #include "drivers/bus_i2c.h" +#include "drivers/bus_octospi.h" #include "drivers/bus_quadspi.h" #include "drivers/bus_spi.h" #include "drivers/buttons.h" @@ -195,8 +196,7 @@ void busSwitchInit(void) } #endif - -static void configureSPIAndQuadSPI(void) +static void configureSPIBusses(void) { #ifdef USE_SPI spiPinConfigure(spiPinConfig(0)); @@ -226,7 +226,10 @@ static void configureSPIAndQuadSPI(void) spiInit(SPIDEV_6); #endif #endif // USE_SPI +} +static void configureQuadSPIBusses(void) +{ #ifdef USE_QUADSPI quadSpiPinConfigure(quadSpiConfig(0)); @@ -236,6 +239,15 @@ static void configureSPIAndQuadSPI(void) #endif // USE_QUAD_SPI } +static void configureOctoSPIBusses(void) +{ +#ifdef USE_OCTOSPI +#ifdef USE_OCTOSPI_DEVICE_1 + octoSpiInit(OCTOSPIDEV_1); +#endif +#endif +} + #ifdef USE_SDCARD static void sdCardAndFSInit(void) { @@ -291,9 +303,10 @@ void init(void) #endif enum { - FLASH_INIT_ATTEMPTED = (1 << 0), - SD_INIT_ATTEMPTED = (1 << 1), - SPI_AND_QSPI_INIT_ATTEMPTED = (1 << 2), + FLASH_INIT_ATTEMPTED = (1 << 0), + SD_INIT_ATTEMPTED = (1 << 1), + SPI_BUSSES_INIT_ATTEMPTED = (1 << 2), + QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED = (1 << 3), }; uint8_t initFlags = 0; @@ -303,19 +316,17 @@ void init(void) // Config in sdcard presents an issue with pin configuration since the pin and sdcard configs for the // sdcard are in the config which is on the sdcard which we can't read yet! // - // FIXME We need to add configuration somewhere, e.g. bootloader image or reserved flash area, that can be read by the firmware. - // it's currently possible for the firmware resource allocation to be wrong after the config is loaded if the user changes the settings. - // This would cause undefined behaviour once the config is loaded. so for now, users must NOT change sdio/spi configs needed for - // the system to boot and/or to save the config. + // FIXME For now, users must NOT change flash/pin configs needed for the system to boot and/or to save the config. + // One possible solution is to lock the pins for the flash chip so they cannot be modified post-boot. // - // note that target specific SDCARD/SDIO/SPI/QUADSPI configs are + // note that target specific SDCARD/SDIO/SPI/QUADSPI/OCTOSPI configs are // also not supported in USE_TARGET_CONFIG/targetConfigure() when using CONFIG_IN_SDCARD. // // // IMPORTANT: all default flash and pin configurations must be valid for the target after pgResetAll() is called. - // Target designers must ensure other devices connected the same SPI/QUADSPI interface as the flash chip do not - // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI CS lines. + // Target designers must ensure other devices connected the same SPI/QUADSPI/OCTOSPI interface as the flash chip do not + // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI/OCTOSPI CS lines. // #ifdef TARGET_BUS_INIT @@ -325,8 +336,8 @@ void init(void) pgResetAll(); #ifdef USE_SDCARD_SPI - configureSPIAndQuadSPI(); - initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED; + configureSPIBusses(); + initFlags |= SPI_BUSSES_INIT_ATTEMPTED; #endif sdCardAndFSInit(); @@ -346,37 +357,42 @@ void init(void) #endif // CONFIG_IN_SDCARD -#ifdef CONFIG_IN_EXTERNAL_FLASH +#if defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) // // Config on external flash presents an issue with pin configuration since the pin and flash configs for the // external flash are in the config which is on a chip which we can't read yet! // - // FIXME We need to add configuration somewhere, e.g. bootloader image or reserved flash area, that can be read by the firmware. - // it's currently possible for the firmware resource allocation to be wrong after the config is loaded if the user changes the settings. - // This would cause undefined behaviour once the config is loaded. so for now, users must NOT change flash/pin configs needed for - // the system to boot and/or to save the config. + // FIXME For now, users must NOT change flash/pin configs needed for the system to boot and/or to save the config. + // One possible solution is to lock the pins for the flash chip so they cannot be modified post-boot. // - // note that target specific FLASH/SPI/QUADSPI configs are - // also not supported in USE_TARGET_CONFIG/targetConfigure() when using CONFIG_IN_EXTERNAL_FLASH. + // note that target specific FLASH/SPI/QUADSPI/OCTOSPI configs are + // also not supported in USE_TARGET_CONFIG/targetConfigure() when using CONFIG_IN_EXTERNAL_FLASH/CONFIG_IN_MEMORY_MAPPED_FLASH. // // // IMPORTANT: all default flash and pin configurations must be valid for the target after pgResetAll() is called. - // Target designers must ensure other devices connected the same SPI/QUADSPI interface as the flash chip do not - // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI CS lines. + // Target designers must ensure other devices connected the same SPI/QUADSPI/OCTOSPI interface as the flash chip do not + // cause communication issues with the flash chip. e.g. use external pullups on SPI/QUADSPI/OCTOSPI CS lines. // pgResetAll(); #ifdef TARGET_BUS_INIT -#error "CONFIG_IN_EXTERNAL_FLASH and TARGET_BUS_INIT are mutually exclusive" +#error "CONFIG_IN_EXTERNAL_FLASH/CONFIG_IN_MEMORY_MAPPED_FLASH and TARGET_BUS_INIT are mutually exclusive" #endif - configureSPIAndQuadSPI(); - initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED; +#if defined(CONFIG_IN_EXTERNAL_FLASH) + configureSPIBusses(); + initFlags |= SPI_BUSSES_INIT_ATTEMPTED; +#endif +#if defined(CONFIG_IN_MEMORY_MAPPED_FLASH) || defined(CONFIG_IN_EXTERNAL_FLASH) + configureQuadSPIBusses(); + configureOctoSPIBusses(); + initFlags |= QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED; +#endif #ifndef USE_FLASH_CHIP -#error "CONFIG_IN_EXTERNAL_FLASH requires USE_FLASH_CHIP to be defined." +#error "CONFIG_IN_EXTERNAL_FLASH/CONFIG_IN_MEMORY_MAPPED_FLASH requires USE_FLASH_CHIP to be defined." #endif bool haveFlash = flashInit(flashConfig()); @@ -386,7 +402,8 @@ void init(void) } initFlags |= FLASH_INIT_ATTEMPTED; -#endif // CONFIG_IN_EXTERNAL_FLASH +#endif // CONFIG_IN_EXTERNAL_FLASH || CONFIG_IN_MEMORY_MAPPED_FLASH + initEEPROM(); @@ -588,10 +605,16 @@ void init(void) #else - // Depending on compilation options SPI/QSPI initialisation may already be done. - if (!(initFlags & SPI_AND_QSPI_INIT_ATTEMPTED)) { - configureSPIAndQuadSPI(); - initFlags |= SPI_AND_QSPI_INIT_ATTEMPTED; + // Depending on compilation options SPI/QSPI/OSPI initialisation may already be done. + if (!(initFlags & SPI_BUSSES_INIT_ATTEMPTED)) { + configureSPIBusses(); + initFlags |= SPI_BUSSES_INIT_ATTEMPTED; + } + + if (!(initFlags & QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED)) { + configureQuadSPIBusses(); + configureOctoSPIBusses(); + initFlags |= QUAD_OCTO_SPI_BUSSES_INIT_ATTEMPTED; } #if defined(USE_SDCARD_SDIO) && !defined(CONFIG_IN_SDCARD) && defined(STM32H7) diff --git a/src/main/fc/parameter_names.h b/src/main/fc/parameter_names.h index dab828d8de..b87d784c50 100644 --- a/src/main/fc/parameter_names.h +++ b/src/main/fc/parameter_names.h @@ -142,12 +142,14 @@ #define PARAM_NAME_GPS_RESCUE_RETURN_ALT "gps_rescue_return_alt" #define PARAM_NAME_GPS_RESCUE_RETURN_SPEED "gps_rescue_ground_speed" -#define PARAM_NAME_GPS_RESCUE_PITCH_ANGLE_MAX "gps_rescue_pitch_angle_max" +#define PARAM_NAME_GPS_RESCUE_MAX_RESCUE_ANGLE "gps_rescue_max_angle" #define PARAM_NAME_GPS_RESCUE_ROLL_MIX "gps_rescue_roll_mix" +#define PARAM_NAME_GPS_RESCUE_PITCH_CUTOFF "gps_rescue_pitch_cutoff" #define PARAM_NAME_GPS_RESCUE_DESCENT_DIST "gps_rescue_descent_dist" #define PARAM_NAME_GPS_RESCUE_DESCEND_RATE "gps_rescue_descend_rate" #define PARAM_NAME_GPS_RESCUE_LANDING_ALT "gps_rescue_landing_alt" +#define PARAM_NAME_GPS_RESCUE_DISARM_THRESHOLD "gps_rescue_disarm_threshold" #define PARAM_NAME_GPS_RESCUE_THROTTLE_MIN "gps_rescue_throttle_min" #define PARAM_NAME_GPS_RESCUE_THROTTLE_MAX "gps_rescue_throttle_max" diff --git a/src/main/fc/rc_controls.c b/src/main/fc/rc_controls.c index 0872abea86..167df0e737 100644 --- a/src/main/fc/rc_controls.c +++ b/src/main/fc/rc_controls.c @@ -177,10 +177,16 @@ void processRcStickPositions(void) resetTryingToArm(); // Disarming via ARM BOX resetArmingDisabled(); - const bool switchFailsafe = (failsafeIsActive() && (IS_RC_MODE_ACTIVE(BOXFAILSAFE) || IS_RC_MODE_ACTIVE(BOXGPSRESCUE))); - if (ARMING_FLAG(ARMED) && (failsafeIsReceivingRxData() || switchFailsafe)) { + const bool boxFailsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); + if (ARMING_FLAG(ARMED) && (failsafeIsReceivingRxData() || boxFailsafeSwitchIsOn)) { + // in a true signal loss situation, allow disarm only once we regain validated RxData (failsafeIsReceivingRxData = true), + // to avoid potentially false disarm signals soon after link recover + // Note that BOXFAILSAFE will also drive failsafeIsReceivingRxData false (immediately at start or end) + // That's why we explicitly allow disarm here BOXFAILSAFE switch is active + // Note that BOXGPSRESCUE mode does not trigger failsafe - we can always disarm in that mode rcDisarmTicks++; if (rcDisarmTicks > 3) { + // require three duplicate disarm values in a row before we disarm disarm(DISARM_REASON_SWITCH); } } diff --git a/src/main/flight/failsafe.c b/src/main/flight/failsafe.c index 94aa551e18..d1a9aac1cc 100644 --- a/src/main/flight/failsafe.c +++ b/src/main/flight/failsafe.c @@ -104,7 +104,7 @@ void failsafeReset(void) failsafeState.receivingRxDataPeriodPreset = failsafeState.rxDataRecoveryPeriod; failsafeState.phase = FAILSAFE_IDLE; failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN; - failsafeState.failsafeSwitchWasOn = false; + failsafeState.boxFailsafeSwitchWasOn = false; } void failsafeInit(void) @@ -125,7 +125,7 @@ bool failsafeIsMonitoring(void) return failsafeState.monitoring; } -bool failsafeIsActive(void) // real or switch-induced stage 2 failsafe +bool failsafeIsActive(void) // real or BOXFAILSAFE induced stage 2 failsafe is currently active { return failsafeState.active; } @@ -143,9 +143,9 @@ static bool failsafeShouldHaveCausedLandingByNow(void) bool failsafeIsReceivingRxData(void) { return (failsafeState.rxLinkState == FAILSAFE_RXLINK_UP); - // False with failsafe switch or when no valid packets for 100ms or any flight channel invalid for 300ms, - // stays false until after recovery period expires - // Link down is the trigger for the various failsafe stage 2 outcomes. + // False with BOXFAILSAFE switch or when no valid packets for 100ms or any flight channel invalid for 300ms, + // becomes true immediately BOXFAILSAFE switch reverts, or after recovery period expires when valid packets are received + // rxLinkState RXLINK_DOWN (not up) is the trigger for the various failsafe stage 2 outcomes. } void failsafeOnRxSuspend(uint32_t usSuspendPeriod) @@ -160,7 +160,10 @@ void failsafeOnRxResume(void) } void failsafeOnValidDataReceived(void) -// runs when packets are received for more than the signal validation period (100ms) +// enters stage 2 +// runs, after prior a signal loss, immediately when packets are received or the BOXFAILSAFE switch is reverted +// rxLinkState will go RXLINK_UP immediately if BOXFAILSAFE goes back ON since receivingRxDataPeriodPreset is set to zero in that case +// otherwise RXLINK_UP is delayed for the recovery period (failsafe_recovery_delay, default 1s, 0-20, min 0.2s) { unsetArmingDisabled(ARMING_DISABLED_RX_FAILSAFE); // clear RXLOSS in OSD immediately we get a good packet, and un-set its arming block @@ -188,14 +191,16 @@ void failsafeOnValidDataReceived(void) } void failsafeOnValidDataFailed(void) -// runs when packets are lost for more than the signal validation period (100ms) +// run from rc.c when packets are lost for more than the signal validation period (100ms), or immediately BOXFAILSAFE switch is active +// after the stage 1 delay has expired, sets the rxLinkState to RXLINK_DOWN, ie not up, causing failsafeIsReceivingRxData to become false +// if failsafe is configured to go direct to stage 2, this is emulated immediately in failsafeUpdateState() { setArmingDisabled(ARMING_DISABLED_RX_FAILSAFE); // set RXLOSS in OSD and block arming after 100ms of signal loss (is restored in rx.c immediately signal returns) failsafeState.validRxDataFailedAt = millis(); if ((cmp32(failsafeState.validRxDataFailedAt, failsafeState.validRxDataReceivedAt) > (int32_t)failsafeState.rxDataFailurePeriod)) { - // sets rxLinkState = DOWN to initiate stage 2 failsafe, if no validated signal for the stage 1 period + // sets rxLinkState = DOWN to initiate stage 2 failsafe failsafeState.rxLinkState = FAILSAFE_RXLINK_DOWN; // show RXLOSS and block arming } @@ -225,19 +230,18 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) } bool receivingRxData = failsafeIsReceivingRxData(); - // returns state of FAILSAFE_RXLINK_UP - // FAILSAFE_RXLINK_UP is set in failsafeOnValidDataReceived, after the various Stage 1 and recovery delays - // failsafeOnValidDataReceived runs from detectAndApplySignalLossBehaviour + // returns state of FAILSAFE_RXLINK_UP, which + // goes false after the stage 1 delay, whether from signal loss or BOXFAILSAFE switch activation + // goes true immediately BOXFAILSAFE switch is reverted, or after recovery delay once signal recovers + // essentially means 'should be in failsafe stage 2' DEBUG_SET(DEBUG_FAILSAFE, 2, receivingRxData); // from Rx alone, not considering switch bool armed = ARMING_FLAG(ARMED); - bool failsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); beeperMode_e beeperMode = BEEPER_SILENCE; - if (failsafeSwitchIsOn && (failsafeConfig()->failsafe_switch_mode == FAILSAFE_SWITCH_MODE_STAGE2)) { - // Aux switch set to failsafe stage2 emulates immediate loss of signal without waiting - failsafeOnValidDataFailed(); + if (IS_RC_MODE_ACTIVE(BOXFAILSAFE) && (failsafeConfig()->failsafe_switch_mode == FAILSAFE_SWITCH_MODE_STAGE2)) { + // Force immediate stage 2 responses if mode is failsafe stage2 to emulate immediate loss of signal without waiting receivingRxData = false; } @@ -253,13 +257,14 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) switch (failsafeState.phase) { case FAILSAFE_IDLE: - failsafeState.failsafeSwitchWasOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); + failsafeState.boxFailsafeSwitchWasOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); + // store and use the switch state as it was at the start of the failsafe if (armed) { // Track throttle command below minimum time if (calculateThrottleStatus() != THROTTLE_LOW) { failsafeState.throttleLowPeriod = millis() + failsafeConfig()->failsafe_throttle_low_delay * MILLIS_PER_TENTH_SECOND; } - if (failsafeState.failsafeSwitchWasOn && (failsafeConfig()->failsafe_switch_mode == FAILSAFE_SWITCH_MODE_KILL)) { + if (failsafeState.boxFailsafeSwitchWasOn && (failsafeConfig()->failsafe_switch_mode == FAILSAFE_SWITCH_MODE_KILL)) { // Failsafe switch is configured as KILL switch and is switched ON failsafeState.active = true; failsafeState.events++; @@ -291,7 +296,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) } } else { // When NOT armed, enable failsafe mode to show warnings in OSD - if (failsafeState.failsafeSwitchWasOn) { + if (failsafeState.boxFailsafeSwitchWasOn) { ENABLE_FLIGHT_MODE(FAILSAFE_MODE); } else { DISABLE_FLIGHT_MODE(FAILSAFE_MODE); @@ -327,7 +332,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) break; #endif } - if (failsafeState.failsafeSwitchWasOn) { + if (failsafeState.boxFailsafeSwitchWasOn) { failsafeState.receivingRxDataPeriodPreset = 0; // recover immediately if failsafe was triggered by a switch } else { @@ -359,7 +364,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) #ifdef USE_GPS_RESCUE case FAILSAFE_GPS_RESCUE: if (receivingRxData) { - if (areSticksActive(failsafeConfig()->failsafe_stick_threshold) || failsafeState.failsafeSwitchWasOn) { + if (areSticksActive(failsafeConfig()->failsafe_stick_threshold) || failsafeState.boxFailsafeSwitchWasOn) { // exits the rescue immediately if failsafe was initiated by switch, otherwise // requires stick input to exit the rescue after a true Rx loss failsafe // NB this test requires stick inputs to be received during GPS Rescue see PR #7936 for rationale @@ -418,7 +423,7 @@ FAST_CODE_NOINLINE void failsafeUpdateState(void) break; } - DEBUG_SET(DEBUG_FAILSAFE, 0, failsafeState.failsafeSwitchWasOn); + DEBUG_SET(DEBUG_FAILSAFE, 0, failsafeState.boxFailsafeSwitchWasOn); DEBUG_SET(DEBUG_FAILSAFE, 3, failsafeState.phase); } while (reprocessState); diff --git a/src/main/flight/failsafe.h b/src/main/flight/failsafe.h index 350c9e2df2..959ab9644f 100644 --- a/src/main/flight/failsafe.h +++ b/src/main/flight/failsafe.h @@ -90,7 +90,7 @@ typedef struct failsafeState_s { uint32_t receivingRxDataPeriodPreset; // preset for the required period of valid rxData failsafePhase_e phase; failsafeRxLinkState_e rxLinkState; - bool failsafeSwitchWasOn; + bool boxFailsafeSwitchWasOn; } failsafeState_t; void failsafeInit(void); diff --git a/src/main/flight/gps_rescue.c b/src/main/flight/gps_rescue.c index b8e44b4e3c..14a18932b7 100644 --- a/src/main/flight/gps_rescue.c +++ b/src/main/flight/gps_rescue.c @@ -89,6 +89,11 @@ typedef struct { float descentRateModifier; float yawAttenuator; float disarmThreshold; + float velocityITermAccumulator; + float velocityPidCutoff; + float velocityPidCutoffModifier; + float proximityToLandingArea; + float velocityItermRelax; } rescueIntent_s; typedef struct { @@ -102,6 +107,7 @@ typedef struct { float errorAngle; float gpsDataIntervalSeconds; float altitudeDataIntervalSeconds; + float gpsRescueTaskIntervalSeconds; float velocityToHomeCmS; float alitutudeStepCm; float maxPitchStep; @@ -118,10 +124,7 @@ typedef struct { #define GPS_RESCUE_MAX_YAW_RATE 180 // deg/sec max yaw rate #define GPS_RESCUE_MIN_DESCENT_DIST_M 5 // minimum descent distance -#define GPS_RESCUE_MAX_ITERM_VELOCITY 1000 // max iterm value for velocity -#define GPS_RESCUE_MAX_ITERM_THROTTLE 200 // max iterm value for throttle -#define GPS_RESCUE_MAX_PITCH_RATE 3000 // max change in pitch per second in degrees * 100 -#define GPS_RESCUE_DISARM_THRESHOLD 2.0f // disarm threshold in G's +#define GPS_RESCUE_MAX_THROTTLE_ITERM 200 // max iterm value for throttle in degrees * 100 static float rescueThrottle; static float rescueYaw; @@ -129,27 +132,29 @@ float gpsRescueAngle[ANGLE_INDEX_COUNT] = { 0, 0 }; bool magForceDisable = false; static bool newGPSData = false; static pt2Filter_t throttleDLpf; -static pt2Filter_t velocityDLpf; -static pt3Filter_t pitchLpf; +static pt1Filter_t velocityDLpf; +static pt3Filter_t velocityUpsampleLpf; rescueState_s rescueState; void gpsRescueInit(void) { - const float sampleTimeS = HZ_TO_INTERVAL(TASK_GPS_RESCUE_RATE_HZ); - float cutoffHz, gain; + rescueState.sensor.gpsRescueTaskIntervalSeconds = HZ_TO_INTERVAL(TASK_GPS_RESCUE_RATE_HZ); + float cutoffHz, gain; cutoffHz = positionConfig()->altitude_d_lpf / 100.0f; - gain = pt2FilterGain(cutoffHz, sampleTimeS); + gain = pt2FilterGain(cutoffHz, rescueState.sensor.gpsRescueTaskIntervalSeconds); pt2FilterInit(&throttleDLpf, gain); - cutoffHz = 0.8f; - gain = pt2FilterGain(cutoffHz, 1.0f); - pt2FilterInit(&velocityDLpf, gain); + cutoffHz = gpsRescueConfig()->pitchCutoffHz / 100.0f; + rescueState.intent.velocityPidCutoff = cutoffHz; + rescueState.intent.velocityPidCutoffModifier = 1.0f; + gain = pt1FilterGain(cutoffHz, 1.0f); + pt1FilterInit(&velocityDLpf, gain); - cutoffHz = 4.0f; - gain = pt3FilterGain(cutoffHz, sampleTimeS); - pt3FilterInit(&pitchLpf, gain); + cutoffHz *= 4.0f; + gain = pt3FilterGain(cutoffHz, rescueState.sensor.gpsRescueTaskIntervalSeconds); + pt3FilterInit(&velocityUpsampleLpf, gain); } /* @@ -210,7 +215,6 @@ static void rescueAttainPosition(void) // runs at 100hz, but only updates RPYT settings when new GPS Data arrives and when not in idle phase. static float previousVelocityError = 0.0f; static float velocityI = 0.0f; - static float previousPitchAdjustment = 0.0f; static float throttleI = 0.0f; static float previousAltitudeError = 0.0f; static int16_t throttleAdjustment = 0; @@ -226,11 +230,10 @@ static void rescueAttainPosition(void) // Initialize internal variables each time GPS Rescue is started previousVelocityError = 0.0f; velocityI = 0.0f; - previousPitchAdjustment = 0.0f; throttleI = 0.0f; previousAltitudeError = 0.0f; throttleAdjustment = 0; - rescueState.intent.disarmThreshold = GPS_RESCUE_DISARM_THRESHOLD; + rescueState.intent.disarmThreshold = gpsRescueConfig()->disarmThreshold / 10.0f; return; case RESCUE_DO_NOTHING: // 20s of slow descent for switch induced sanity failures to allow time to recover @@ -255,7 +258,7 @@ static void rescueAttainPosition(void) // I component throttleI += 0.1f * gpsRescueConfig()->throttleI * altitudeError * rescueState.sensor.altitudeDataIntervalSeconds; - throttleI = constrainf(throttleI, -1.0f * GPS_RESCUE_MAX_ITERM_THROTTLE, 1.0f * GPS_RESCUE_MAX_ITERM_THROTTLE); + throttleI = constrainf(throttleI, -1.0f * GPS_RESCUE_MAX_THROTTLE_ITERM, 1.0f * GPS_RESCUE_MAX_THROTTLE_ITERM); // up to 20% increase in throttle from I alone // D component is error based, so includes positive boost when climbing and negative boost on descent @@ -266,8 +269,6 @@ static void rescueAttainPosition(void) float throttleD = pt2FilterApply(&throttleDLpf, verticalSpeed); - rescueState.intent.disarmThreshold = GPS_RESCUE_DISARM_THRESHOLD - throttleD / 15.0f; // make disarm more likely if throttle D is high - throttleD = gpsRescueConfig()->throttleD * throttleD; // acceleration component not currently implemented - was needed previously due to GPS lag, maybe not needed now. @@ -294,12 +295,13 @@ static void rescueAttainPosition(void) // if the course over ground, due to wind or pre-exiting movement, is different from the attitude of the quad, the GPS correction will be less accurate // the craft should not return much less than 5m/s during the rescue or the GPS corrections may be inaccurate. // the faster the return speed, the more accurate the IMU will be, but the consequences of IMU error at the start are greater - // A compass (magnetometer) is vital for accurate GPS rescue at slow speeds, but must be calibrated and validated. - + // A compass (magnetometer) is vital for accurate GPS rescue at slow speeds, but must be calibrated and validated + // WARNING: Some GPS units give false Home values! Always check the arrow points to home on leaving home. rescueYaw = rescueState.sensor.errorAngle * gpsRescueConfig()->yawP * rescueState.intent.yawAttenuator * 0.1f; rescueYaw = constrainf(rescueYaw, -GPS_RESCUE_MAX_YAW_RATE, GPS_RESCUE_MAX_YAW_RATE); // rescueYaw is the yaw rate in deg/s to correct the heading error + // *** mix in some roll. very important for heading tracking, since a yaw rate means the quad has drifted sideways const float rollMixAttenuator = constrainf(1.0f - fabsf(rescueYaw) * 0.01f, 0.0f, 1.0f); // less roll at higher yaw rates, no roll at 100 deg/s of yaw const float rollAdjustment = -rescueYaw * gpsRescueConfig()->rollMix * rollMixAttenuator; @@ -307,12 +309,12 @@ static void rescueAttainPosition(void) // when gpsRescueConfig()->rollMix is zero, there is no roll adjustment // rollAdjustment is degrees * 100 // note that the roll element has the opposite sign to the yaw element *before* GET_DIRECTION - const float rollLimit = 100.0f * rescueState.intent.rollAngleLimitDeg; gpsRescueAngle[AI_ROLL] = constrainf(rollAdjustment, -rollLimit, rollLimit); // gpsRescueAngle is added to the normal roll Angle Mode corrections in pid.c rescueYaw *= GET_DIRECTION(rcControlsConfig()->yaw_control_reversed); + // rescueYaw is the yaw rate in deg/s to correct the heading error /** Pitch / velocity controller @@ -322,51 +324,53 @@ static void rescueAttainPosition(void) const float sampleIntervalNormaliseFactor = rescueState.sensor.gpsDataIntervalSeconds * 10.0f; - const float velocityError = (rescueState.intent.targetVelocityCmS - rescueState.sensor.velocityToHomeCmS); + const float velocityError = rescueState.intent.targetVelocityCmS - rescueState.sensor.velocityToHomeCmS; // velocityError is in cm per second, positive means too slow. // NB positive pitch setpoint means nose down. + // target velocity can be very negative leading to large error before the start, with overshoot // P component const float velocityP = velocityError * gpsRescueConfig()->velP; // I component - velocityI += 0.01f * gpsRescueConfig()->velI * velocityError * sampleIntervalNormaliseFactor; - // increase amount added when GPS sample rate is slower - velocityI = constrainf(velocityI, -1.0f * GPS_RESCUE_MAX_ITERM_VELOCITY, 1.0f * GPS_RESCUE_MAX_ITERM_VELOCITY); - // I component alone cannot exceed a pitch angle of 10% + velocityI += 0.01f * gpsRescueConfig()->velI * velocityError * sampleIntervalNormaliseFactor * rescueState.intent.velocityItermRelax; + // velocityItermRelax is a time-based factor, 0->1 with time constant of 1s from when we start to fly home + // avoids excess iTerm during the initial acceleration phase. + velocityI *= rescueState.intent.proximityToLandingArea; + // reduce iTerm sharply when velocity decreases in landing phase, to minimise overshoot during deceleration + + const float pitchAngleLimit = rescueState.intent.pitchAngleLimitDeg * 100.0f; + const float velocityPILimit = 0.5f * pitchAngleLimit; + velocityI = constrainf(velocityI, -velocityPILimit, velocityPILimit); + // I component alone cannot exceed half the max pitch angle // D component float velocityD = ((velocityError - previousVelocityError) / sampleIntervalNormaliseFactor); previousVelocityError = velocityError; - const float gain = pt2FilterGain(0.8f, HZ_TO_INTERVAL(gpsGetSampleRateHz())); - pt2FilterUpdateCutoff(&velocityDLpf, gain); - velocityD = pt2FilterApply(&velocityDLpf, velocityD); velocityD *= gpsRescueConfig()->velD; - const float velocityIAttenuator = rescueState.intent.targetVelocityCmS / gpsRescueConfig()->rescueGroundspeed; - // reduces iTerm as target velocity decreases, to minimise overshoot during deceleration to landing phase + // smooth the D steps + const float cutoffHz = rescueState.intent.velocityPidCutoff * rescueState.intent.velocityPidCutoffModifier; + // note that this cutoff is increased up to 2x as we get closer to landing point in descend() + const float gain = pt1FilterGain(cutoffHz, rescueState.sensor.gpsDataIntervalSeconds); + pt1FilterUpdateCutoff(&velocityDLpf, gain); + velocityD = pt1FilterApply(&velocityDLpf, velocityD); - pitchAdjustment = velocityP + velocityD; - if (rescueState.phase == RESCUE_FLY_HOME) { - pitchAdjustment *= 0.7f; // attenuate pitch PIDs during main fly home phase, tighten up in descent. - } - pitchAdjustment += velocityI * velocityIAttenuator; + pitchAdjustment = velocityP + velocityI + velocityD; + pitchAdjustment = constrainf(pitchAdjustment, -pitchAngleLimit, pitchAngleLimit); + // limit to maximum allowed angle - const float movingAvgPitchAdjustment = 0.5f * (previousPitchAdjustment + pitchAdjustment); - // moving average seems to work best here, a lot of sequential up and down in velocity data - previousPitchAdjustment = pitchAdjustment; - pitchAdjustment = movingAvgPitchAdjustment; // pitchAdjustment is the absolute Pitch angle adjustment value in degrees * 100 // it gets added to the normal level mode Pitch adjustments in pid.c DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY, 0, lrintf(velocityP)); DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY, 1, lrintf(velocityD)); } - const float pitchAdjustmentFiltered = pt3FilterApply(&pitchLpf, pitchAdjustment); // upsampling and smoothing of pitch angle steps + float pitchAdjustmentFiltered = pt3FilterApply(&velocityUpsampleLpf, pitchAdjustment); - const float pitchAngleLimit = rescueState.intent.pitchAngleLimitDeg * 100.0f; - gpsRescueAngle[AI_PITCH] = constrainf(pitchAdjustmentFiltered, -pitchAngleLimit, pitchAngleLimit); + + gpsRescueAngle[AI_PITCH] = pitchAdjustmentFiltered; // this angle gets added to the normal pitch Angle Mode control values in pid.c - will be seen in pitch setpoint DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY, 3, lrintf(rescueState.intent.targetVelocityCmS)); @@ -447,7 +451,7 @@ static void performSanityChecks(void) // if the quad is stuck, or if GPS data packets stop, there will be no change in distance to home // we can't use rescueState.sensor.currentVelocity because it will be held at the last good value if GPS data updates stop if (rescueState.phase == RESCUE_FLY_HOME) { - const float velocityToHomeCmS = previousDistanceToHomeCm- rescueState.sensor.distanceToHomeCm; // cm/s + const float velocityToHomeCmS = previousDistanceToHomeCm - rescueState.sensor.distanceToHomeCm; // cm/s previousDistanceToHomeCm = rescueState.sensor.distanceToHomeCm; rescueState.intent.secondsFailing += (velocityToHomeCmS < 0.5f * rescueState.intent.targetVelocityCmS) ? 1 : -1; rescueState.intent.secondsFailing = constrain(rescueState.intent.secondsFailing, 0, 15); @@ -540,7 +544,8 @@ static void sensorUpdate(void) if (rescueState.phase == RESCUE_LANDING) { // do this at sensor update rate, not the much slower GPS rate, for quick disarm - rescueState.sensor.accMagnitude = (float) sqrtf(sq(acc.accADC[Z]) + sq(acc.accADC[X]) + sq(acc.accADC[Y])) * acc.dev.acc_1G_rec; + rescueState.sensor.accMagnitude = (float) sqrtf(sq(acc.accADC[Z] - acc.dev.acc_1G) + sq(acc.accADC[X]) + sq(acc.accADC[Y])) * acc.dev.acc_1G_rec; + // Note: subtracting 1G from Z assumes the quad is 'flat' with respect to the horizon. A true non-gravity acceleration value, regardless of attitude, may be better. } rescueState.sensor.directionToHome = GPS_directionToHome; @@ -562,21 +567,15 @@ static void sensorUpdate(void) rescueState.sensor.distanceToHomeM = rescueState.sensor.distanceToHomeCm / 100.0f; rescueState.sensor.groundSpeedCmS = gpsSol.groundSpeed; // cm/s - static timeUs_t previousGPSDataTimeUs = 0; - const timeDelta_t gpsDataIntervalUs = cmpTimeUs(currentTimeUs, previousGPSDataTimeUs); - rescueState.sensor.gpsDataIntervalSeconds = constrainf(gpsDataIntervalUs * 0.000001f, 0.01f, 1.0f); + rescueState.sensor.gpsDataIntervalSeconds = getGpsDataIntervalSeconds(); // Range from 10ms (100hz) to 1000ms (1Hz). Intended to cover common GPS data rates and exclude unusual values. - previousGPSDataTimeUs = currentTimeUs; - rescueState.sensor.velocityToHomeCmS = (prevDistanceToHomeCm - rescueState.sensor.distanceToHomeCm) / rescueState.sensor.gpsDataIntervalSeconds; + rescueState.sensor.velocityToHomeCmS = ((prevDistanceToHomeCm - rescueState.sensor.distanceToHomeCm) / rescueState.sensor.gpsDataIntervalSeconds); // positive = towards home. First value is useless since prevDistanceToHomeCm was zero. prevDistanceToHomeCm = rescueState.sensor.distanceToHomeCm; - rescueState.sensor.maxPitchStep = rescueState.sensor.gpsDataIntervalSeconds * GPS_RESCUE_MAX_PITCH_RATE; - DEBUG_SET(DEBUG_GPS_RESCUE_VELOCITY, 2, lrintf(rescueState.sensor.velocityToHomeCmS)); DEBUG_SET(DEBUG_GPS_RESCUE_TRACKING, 0, lrintf(rescueState.sensor.velocityToHomeCmS)); - } // This function flashes "RESCUE N/A" in the OSD if: @@ -643,15 +642,17 @@ void descend(void) if (newGPSData) { const float distanceToLandingAreaM = rescueState.sensor.distanceToHomeM - (rescueState.intent.targetLandingAltitudeCm / 200.0f); // considers home to be a circle half landing height around home to avoid overshooting home point - const float proximityToLandingArea = constrainf(distanceToLandingAreaM / rescueState.intent.descentDistanceM, 0.0f, 1.0f); - rescueState.intent.targetVelocityCmS = gpsRescueConfig()->rescueGroundspeed * proximityToLandingArea; + rescueState.intent.proximityToLandingArea = constrainf(distanceToLandingAreaM / rescueState.intent.descentDistanceM, 0.0f, 1.0f); + rescueState.intent.velocityPidCutoffModifier = 2.5f - rescueState.intent.proximityToLandingArea; + // 1.5 when starting descent, 2.5 when almost landed; multiplier for velocity step cutoff filter + rescueState.intent.targetVelocityCmS = gpsRescueConfig()->rescueGroundspeed * rescueState.intent.proximityToLandingArea; // reduce target velocity as we get closer to home. Zero within 2m of home, reducing risk of overshooting. // if quad drifts further than 2m away from home, should by then have rotated towards home, so pitch is allowed - rescueState.intent.rollAngleLimitDeg = gpsRescueConfig()->angle * proximityToLandingArea; + rescueState.intent.rollAngleLimitDeg = gpsRescueConfig()->maxRescueAngle * rescueState.intent.proximityToLandingArea; // reduce roll capability when closer to home, none within final 2m } - // adjust altitude step for interval between altitude readings + // configure altitude step for descent, considering interval between altitude readings rescueState.intent.altitudeStep = -1.0f * rescueState.sensor.altitudeDataIntervalSeconds * gpsRescueConfig()->descendRate; // descend more slowly if return altitude is less than 20m @@ -665,15 +666,8 @@ void descend(void) // increase descent rate to max of 3x default above 50m, 2x above 25m, 1.2 at 5m, default by ground level. } -void altitudeAchieved(void) -{ - rescueState.intent.targetAltitudeCm = rescueState.intent.returnAltitudeCm; - rescueState.intent.altitudeStep = 0; - rescueState.phase = RESCUE_ROTATE; -} - void gpsRescueUpdate(void) -// this runs a lot faster than the GPS Data update rate, and runs whether or not rescue is active +// runs at gpsRescueTaskIntervalSeconds, and runs whether or not rescue is active { if (!FLIGHT_MODE(GPS_RESCUE_MODE)) { rescueStop(); // sets phase to RESCUE_IDLE; does nothing else. RESCUE_IDLE tasks still run. @@ -687,7 +681,8 @@ void gpsRescueUpdate(void) sensorUpdate(); // always get latest GPS and Altitude data, update ascend and descend rates - bool startedLow = true; + static bool initialAltitudeLow = true; + static bool initialVelocityLow = true; rescueState.isAvailable = checkGPSRescueIsAvailable(); switch (rescueState.phase) { @@ -700,32 +695,41 @@ void gpsRescueUpdate(void) // target altitude is always set to current altitude. case RESCUE_INITIALIZE: - // Things that should abort the start of a Rescue + // Things that should be done at the start of a Rescue + rescueState.intent.targetLandingAltitudeCm = 100.0f * gpsRescueConfig()->targetLandingAltitudeM; if (!STATE(GPS_FIX_HOME)) { // we didn't get a home point on arming rescueState.failure = RESCUE_NO_HOME_POINT; // will result in a disarm via the sanity check system, with delay if switch induced // alternative is to prevent the rescue by returning to IDLE, but this could cause flyaways } else if (rescueState.sensor.distanceToHomeM < gpsRescueConfig()->minRescueDth) { - // Attempt to initiate inside minimum activation distance -> landing mode - rescueState.intent.altitudeStep = -rescueState.sensor.altitudeDataIntervalSeconds * gpsRescueConfig()->descendRate; - rescueState.intent.targetVelocityCmS = 0; // zero forward velocity - rescueState.intent.pitchAngleLimitDeg = 0; // flat on pitch - rescueState.intent.rollAngleLimitDeg = 0.0f; // flat on roll also - rescueState.intent.targetAltitudeCm = rescueState.sensor.currentAltitudeCm + rescueState.intent.altitudeStep; - rescueState.phase = RESCUE_LANDING; - // start landing from current altitude + if (rescueState.sensor.distanceToHomeM < 5.0f && rescueState.sensor.currentAltitudeCm < rescueState.intent.targetLandingAltitudeCm) { + // attempted initiation within 5m of home, and 'on the ground' -> instant disarm, for safety reasons + rescueState.phase = RESCUE_ABORT; + } else { + // Otherwise, attempted initiation inside minimum activation distance, at any height -> landing mode + rescueState.intent.altitudeStep = -rescueState.sensor.altitudeDataIntervalSeconds * gpsRescueConfig()->descendRate; + rescueState.intent.targetVelocityCmS = 0; // zero forward velocity + rescueState.intent.pitchAngleLimitDeg = 0; // flat on pitch + rescueState.intent.rollAngleLimitDeg = 0.0f; // flat on roll also + rescueState.intent.proximityToLandingArea = 0.0f; // force velocity iTerm to zero + rescueState.intent.targetAltitudeCm = rescueState.sensor.currentAltitudeCm + rescueState.intent.altitudeStep; + rescueState.phase = RESCUE_LANDING; + // start landing from current altitude + } } else { rescueState.phase = RESCUE_ATTAIN_ALT; rescueState.intent.secondsFailing = 0; // reset the sanity check timer for the climb - rescueState.intent.targetLandingAltitudeCm = 100.0f * gpsRescueConfig()->targetLandingAltitudeM; - startedLow = (rescueState.sensor.currentAltitudeCm <= rescueState.intent.returnAltitudeCm); + initialAltitudeLow = (rescueState.sensor.currentAltitudeCm < rescueState.intent.returnAltitudeCm); rescueState.intent.yawAttenuator = 0.0f; - rescueState.intent.targetVelocityCmS = 0.0f; // zero forward velocity while climbing + rescueState.intent.targetVelocityCmS = rescueState.sensor.velocityToHomeCmS; rescueState.intent.pitchAngleLimitDeg = 0.0f; // no pitch rescueState.intent.rollAngleLimitDeg = 0.0f; // no roll until flying home rescueState.intent.altitudeStep = 0.0f; rescueState.intent.descentRateModifier = 0.0f; + rescueState.intent.velocityPidCutoffModifier = 1.0f; // normal cutoff until descending when increases 150->250% during descent + rescueState.intent.proximityToLandingArea = 0.0f; // force velocity iTerm to zero + rescueState.intent.velocityItermRelax = 0.0f; // and don't accumulate any } break; @@ -733,46 +737,61 @@ void gpsRescueUpdate(void) // gradually increment the target altitude until the craft reaches target altitude // note that this can mean the target altitude may increase above returnAltitude if the craft lags target // sanity check will abort if altitude gain is blocked for a cumulative period - if (startedLow) { - if (rescueState.intent.targetAltitudeCm < rescueState.intent.returnAltitudeCm) { - rescueState.intent.altitudeStep = rescueState.sensor.altitudeDataIntervalSeconds * gpsRescueConfig()->ascendRate; - } else if (rescueState.sensor.currentAltitudeCm > rescueState.intent.returnAltitudeCm) { - altitudeAchieved(); - } + rescueState.intent.altitudeStep = ((initialAltitudeLow) ? gpsRescueConfig()->ascendRate : -1.0f * gpsRescueConfig()->descendRate) * rescueState.sensor.gpsRescueTaskIntervalSeconds; + const bool currentAltitudeLow = rescueState.sensor.currentAltitudeCm < rescueState.intent.returnAltitudeCm; + if (initialAltitudeLow == currentAltitudeLow) { + // we started low, and still are low; also true if we started high, and still are too high + rescueState.intent.targetAltitudeCm += rescueState.intent.altitudeStep; } else { - if (rescueState.intent.targetAltitudeCm > rescueState.intent.returnAltitudeCm) { - rescueState.intent.altitudeStep = -rescueState.sensor.altitudeDataIntervalSeconds * gpsRescueConfig()->descendRate; - } else if (rescueState.sensor.currentAltitudeCm < rescueState.intent.returnAltitudeCm) { - altitudeAchieved(); - } + // target altitude achieved - move on to ROTATE phase, returning at target altitude + rescueState.intent.targetAltitudeCm = rescueState.intent.returnAltitudeCm; + rescueState.intent.altitudeStep = 0.0f; + rescueState.phase = RESCUE_ROTATE; } - rescueState.intent.targetAltitudeCm += rescueState.intent.altitudeStep; + + rescueState.intent.targetVelocityCmS = rescueState.sensor.velocityToHomeCmS; + // gives velocity P and I no error that otherwise would be present due to velocity drift at the start of the rescue break; case RESCUE_ROTATE: - if (rescueState.intent.yawAttenuator < 1.0f) { // gradually acquire yaw authority - rescueState.intent.yawAttenuator += 0.01f; + if (rescueState.intent.yawAttenuator < 1.0f) { // acquire yaw authority over one second + rescueState.intent.yawAttenuator += rescueState.sensor.gpsRescueTaskIntervalSeconds; } if (rescueState.sensor.absErrorAngle < 30.0f) { - rescueState.intent.pitchAngleLimitDeg = gpsRescueConfig()->angle; // allow pitch + rescueState.intent.pitchAngleLimitDeg = gpsRescueConfig()->maxRescueAngle; // allow pitch rescueState.phase = RESCUE_FLY_HOME; // enter fly home phase rescueState.intent.secondsFailing = 0; // reset sanity timer for flight home + rescueState.intent.proximityToLandingArea = 1.0f; // velocity iTerm activated, initialise proximity for descent phase at 1.0 } + initialVelocityLow = rescueState.sensor.velocityToHomeCmS < gpsRescueConfig()->rescueGroundspeed; // used to set direction of velocity target change + rescueState.intent.targetVelocityCmS = rescueState.sensor.velocityToHomeCmS; break; case RESCUE_FLY_HOME: if (rescueState.intent.yawAttenuator < 1.0f) { // be sure to accumulate full yaw authority - rescueState.intent.yawAttenuator += 0.01f; + rescueState.intent.yawAttenuator += rescueState.sensor.gpsRescueTaskIntervalSeconds; } - // steadily increase target velocity target until full return velocity is acquired - if (rescueState.intent.targetVelocityCmS < gpsRescueConfig()->rescueGroundspeed) { - rescueState.intent.targetVelocityCmS += 0.01f * gpsRescueConfig()->rescueGroundspeed; + + // velocity PIDs are now active + // update target velocity gradually, aiming for rescueGroundspeed with a time constant of 1.0s + const float targetVelocityError = gpsRescueConfig()->rescueGroundspeed - rescueState.intent.targetVelocityCmS; + const float velocityTargetStep = rescueState.sensor.gpsRescueTaskIntervalSeconds * targetVelocityError; + // velocityTargetStep is positive when starting low, negative when starting high + const bool targetVelocityIsLow = rescueState.intent.targetVelocityCmS < gpsRescueConfig()->rescueGroundspeed; + if (initialVelocityLow == targetVelocityIsLow) { + // also true if started faster than target velocity and target is still high + rescueState.intent.targetVelocityCmS += velocityTargetStep; } - // acquire full roll authority slowly when pointing to home - if (rescueState.sensor.absErrorAngle < 10.0f && rescueState.intent.rollAngleLimitDeg < gpsRescueConfig()->angle) { - // roll is primarily intended to deal with wind drift causing small yaw errors during return - rescueState.intent.rollAngleLimitDeg += 0.1f; - } + + rescueState.intent.velocityItermRelax += 0.5f * rescueState.sensor.gpsRescueTaskIntervalSeconds * (1.0f - rescueState.intent.velocityItermRelax); + // slowly introduce velocity iTerm accumulation at start, goes 0 ->1 with time constant 2.0s + // there is always a lot of lag at the start + + rescueState.intent.velocityPidCutoffModifier = 2.0f - rescueState.intent.velocityItermRelax; + // higher velocity cutoff for initial few seconds to improve accuracy; can be smoother later + + rescueState.intent.rollAngleLimitDeg = 0.5f * rescueState.intent.velocityItermRelax * gpsRescueConfig()->maxRescueAngle; + // gradually gain roll capability to max of half of max pitch angle if (newGPSData) { if (rescueState.sensor.distanceToHomeM <= rescueState.intent.descentDistanceM) { @@ -795,6 +814,7 @@ void gpsRescueUpdate(void) case RESCUE_LANDING: // Reduce altitude target steadily until impact, then disarm. // control yaw angle and throttle and pitch, attenuate velocity, roll and pitch iTerm + // increase velocity smoothing cutoff as we get closer to ground descend(); disarmOnImpact(); break; @@ -806,6 +826,7 @@ void gpsRescueUpdate(void) case RESCUE_ABORT: setArmingDisabled(ARMING_DISABLED_ARM_SWITCH); disarm(DISARM_REASON_FAILSAFE); + rescueState.intent.secondsFailing = 0; // reset sanity timers so we can re-arm rescueStop(); break; diff --git a/src/main/io/beeper.c b/src/main/io/beeper.c index 83d0315236..d6a60ae9ee 100644 --- a/src/main/io/beeper.c +++ b/src/main/io/beeper.c @@ -400,19 +400,22 @@ void beeperUpdate(timeUs_t currentTimeUs) return; } - if (!beeperIsOn) { #ifdef USE_DSHOT - if (!areMotorsRunning() - && ((currentBeeperEntry->mode == BEEPER_RX_SET && !(beeperConfig()->dshotBeaconOffFlags & BEEPER_GET_FLAG(BEEPER_RX_SET))) - || (currentBeeperEntry->mode == BEEPER_RX_LOST && !(beeperConfig()->dshotBeaconOffFlags & BEEPER_GET_FLAG(BEEPER_RX_LOST))))) { - - if ((currentTimeUs - getLastDisarmTimeUs() > DSHOT_BEACON_GUARD_DELAY_US) && !isTryingToArm()) { + if (!areMotorsRunning() && (currentBeeperEntry->mode == BEEPER_RX_SET || currentBeeperEntry->mode == BEEPER_RX_LOST) + && !(beeperConfig()->dshotBeaconOffFlags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) { + if (cmpTimeUs(currentTimeUs, getLastDisarmTimeUs()) > DSHOT_BEACON_GUARD_DELAY_US && !isTryingToArm()) { + const timeDelta_t dShotBeaconInterval = (currentBeeperEntry->mode == BEEPER_RX_SET) ? DSHOT_BEACON_MODE_INTERVAL_US : DSHOT_BEACON_RXLOSS_INTERVAL_US; + if (cmpTimeUs(currentTimeUs, lastDshotBeaconCommandTimeUs) > dShotBeaconInterval) { + // at least 500ms between DShot beacons to allow time for the sound to fully complete + // the DShot Beacon tone duration is determined by the ESC, and should not exceed 250ms lastDshotBeaconCommandTimeUs = currentTimeUs; dshotCommandWrite(ALL_MOTORS, getMotorCount(), beeperConfig()->dshotBeaconTone, DSHOT_CMD_TYPE_INLINE); } } + } #endif + if (!beeperIsOn) { if (currentBeeperEntry->sequence[beeperPos] != 0) { if (!(beeperConfig()->beeper_off_flags & BEEPER_GET_FLAG(currentBeeperEntry->mode))) { BEEP_ON; diff --git a/src/main/io/beeper.h b/src/main/io/beeper.h index 2b177964e5..af71926f07 100644 --- a/src/main/io/beeper.h +++ b/src/main/io/beeper.h @@ -27,6 +27,9 @@ #ifdef USE_DSHOT #define DSHOT_BEACON_GUARD_DELAY_US 1200000 // Time to separate dshot beacon and armining/disarming events // to prevent interference with motor direction commands +#define DSHOT_BEACON_MODE_INTERVAL_US 450000 // at least 450ms between successive DShot beacon iterations to allow time for ESC to play tone +#define DSHOT_BEACON_RXLOSS_INTERVAL_US 950000 // at least 950ms between successive DShot beacon iterations to allow time for ESC to play tone + // we check beeper every 100ms, so these result in 500ms and 1.0s in practice #endif typedef enum { diff --git a/src/main/io/displayport_crsf.c b/src/main/io/displayport_crsf.c index cd056ce0fa..68a49ee5c2 100644 --- a/src/main/io/displayport_crsf.c +++ b/src/main/io/displayport_crsf.c @@ -96,7 +96,7 @@ static int crsfWriteString(displayPort_t *displayPort, uint8_t col, uint8_t row, static int crsfWriteChar(displayPort_t *displayPort, uint8_t col, uint8_t row, uint8_t attr, uint8_t c) { - char s[1]; + char s[2]; tfp_sprintf(s, "%c", c); return crsfWriteString(displayPort, col, row, attr, s); } diff --git a/src/main/io/displayport_hott.c b/src/main/io/displayport_hott.c index 1dec6bab01..03161b8188 100644 --- a/src/main/io/displayport_hott.c +++ b/src/main/io/displayport_hott.c @@ -56,7 +56,7 @@ static int hottWriteString(displayPort_t *displayPort, uint8_t col, uint8_t row, UNUSED(attr); while (*s) { - hottWriteChar(displayPort, col++, row, DISPLAYPORT_ATTR_NORMAL, *(s++)); + hottWriteChar(displayPort, col++, row, DISPLAYPORT_SEVERITY_NORMAL, *(s++)); } return 0; } @@ -67,7 +67,7 @@ static int hottClearScreen(displayPort_t *displayPort, displayClearOption_e opti for (int row = 0; row < displayPort->rows; row++) { for (int col= 0; col < displayPort->cols; col++) { - hottWriteChar(displayPort, col, row, DISPLAYPORT_ATTR_NORMAL, ' '); + hottWriteChar(displayPort, col, row, DISPLAYPORT_SEVERITY_NORMAL, ' '); } } return 0; diff --git a/src/main/io/displayport_msp.c b/src/main/io/displayport_msp.c index 4f0ccebb06..52dff222f4 100644 --- a/src/main/io/displayport_msp.c +++ b/src/main/io/displayport_msp.c @@ -119,9 +119,9 @@ static int writeString(displayPort_t *displayPort, uint8_t col, uint8_t row, uin buf[0] = MSP_DP_WRITE_STRING; buf[1] = row; buf[2] = col; - buf[3] = displayPortProfileMsp()->fontSelection[attr] & ~DISPLAYPORT_MSP_ATTR_BLINK & DISPLAYPORT_MSP_ATTR_MASK; + buf[3] = displayPortProfileMsp()->fontSelection[attr & (DISPLAYPORT_SEVERITY_COUNT - 1)] & DISPLAYPORT_MSP_ATTR_FONT; - if (attr & DISPLAYPORT_ATTR_BLINK) { + if (attr & DISPLAYPORT_BLINK) { buf[3] |= DISPLAYPORT_MSP_ATTR_BLINK; } diff --git a/src/main/io/displayport_msp.h b/src/main/io/displayport_msp.h index e60184382a..2d89616ad8 100644 --- a/src/main/io/displayport_msp.h +++ b/src/main/io/displayport_msp.h @@ -42,7 +42,7 @@ typedef enum { #define DISPLAYPORT_MSP_ATTR_VERSION BIT(7) // Format indicator; must be zero for V2 (and V1) #define DISPLAYPORT_MSP_ATTR_BLINK BIT(6) // Device local blink #define DISPLAYPORT_MSP_ATTR_FONT (BIT(0) | BIT(1)) // Select bank of 256 characters as per displayPortSeverity_e -#define DISPLAYPORT_MSP_ATTR_MASK (~(DISPLAYPORT_MSP_ATTR_VERSION | DISPLAYPORT_MSP_ATTR_BLINK | DISPLAYPORT_MSP_ATTR_FONT)) +#define DISPLAYPORT_MSP_ATTR_MASK (DISPLAYPORT_MSP_ATTR_VERSION | DISPLAYPORT_MSP_ATTR_BLINK | DISPLAYPORT_MSP_ATTR_FONT) struct displayPort_s *displayPortMspInit(void); void displayPortMspSetSerial(serialPortIdentifier_e serialPort); diff --git a/src/main/io/displayport_srxl.c b/src/main/io/displayport_srxl.c index 2e9d2e946e..d12767d479 100644 --- a/src/main/io/displayport_srxl.c +++ b/src/main/io/displayport_srxl.c @@ -71,15 +71,15 @@ static int srxlClearScreen(displayPort_t *displayPort, displayClearOption_e opti UNUSED(options); for (int row = 0; row < SPEKTRUM_SRXL_TEXTGEN_BUFFER_ROWS; row++) { for (int col= 0; col < SPEKTRUM_SRXL_TEXTGEN_BUFFER_COLS; col++) { - srxlWriteChar(displayPort, col, row, DISPLAYPORT_ATTR_NORMAL, ' '); + srxlWriteChar(displayPort, col, row, DISPLAYPORT_SEVERITY_NORMAL, ' '); } } - srxlWriteString(displayPort, 1, 0, DISPLAYPORT_ATTR_NORMAL, "BETAFLIGHT"); + srxlWriteString(displayPort, 1, 0, DISPLAYPORT_SEVERITY_NORMAL, "BETAFLIGHT"); if (displayPort->grabCount == 0) { - srxlWriteString(displayPort, 0, 2, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT1); - srxlWriteString(displayPort, 2, 3, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT2); - srxlWriteString(displayPort, 2, 4, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT3); + srxlWriteString(displayPort, 0, 2, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT1); + srxlWriteString(displayPort, 2, 3, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT2); + srxlWriteString(displayPort, 2, 4, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT3); } return 0; } diff --git a/src/main/io/gps.c b/src/main/io/gps.c index 7d548c98f8..1fc0072cde 100644 --- a/src/main/io/gps.c +++ b/src/main/io/gps.c @@ -82,7 +82,6 @@ uint16_t GPS_distanceToHome; // distance to home point in meters uint32_t GPS_distanceToHomeCm; int16_t GPS_directionToHome; // direction to home or hol point in degrees * 10 uint32_t GPS_distanceFlownInCm; // distance flown since armed in centimeters -int16_t GPS_verticalSpeedInCmS; // vertical speed in cm/s int16_t nav_takeoff_bearing; #define GPS_DISTANCE_FLOWN_MIN_SPEED_THRESHOLD_CM_S 15 // 0.54 km/h 0.335 mph @@ -107,7 +106,7 @@ uint8_t GPS_svinfo_cno[GPS_SV_MAXSATS_M8N]; #define UBLOX_ACK_TIMEOUT_MAX_COUNT (25) static serialPort_t *gpsPort; -static float gpsSampleRateHz; +static float gpsDataIntervalSeconds; typedef struct gpsInitData_s { uint8_t index; @@ -308,8 +307,7 @@ static void gpsSetState(gpsState_e state) void gpsInit(void) { - gpsSampleRateHz = 0.0f; - + gpsDataIntervalSeconds = 0.1f; gpsData.baudrateIndex = 0; gpsData.errors = 0; gpsData.timeouts = 0; @@ -1824,19 +1822,15 @@ void GPS_calc_longitude_scaling(int32_t lat) } //////////////////////////////////////////////////////////////////////////////////// -// Calculate the distance flown and vertical speed from gps position data +// Calculate the distance flown from gps position data // -static void GPS_calculateDistanceFlownVerticalSpeed(bool initialize) +static void GPS_calculateDistanceFlown(bool initialize) { static int32_t lastCoord[2] = { 0, 0 }; static int32_t lastAlt; - static int32_t lastMillis; - - int currentMillis = millis(); if (initialize) { GPS_distanceFlownInCm = 0; - GPS_verticalSpeedInCmS = 0; } else { if (STATE(GPS_FIX_HOME) && ARMING_FLAG(ARMED)) { uint16_t speed = gpsConfig()->gps_use_3d_speed ? gpsSol.speed3d : gpsSol.groundSpeed; @@ -1851,13 +1845,10 @@ static void GPS_calculateDistanceFlownVerticalSpeed(bool initialize) GPS_distanceFlownInCm += dist; } } - GPS_verticalSpeedInCmS = (gpsSol.llh.altCm - lastAlt) * 1000 / (currentMillis - lastMillis); - GPS_verticalSpeedInCmS = constrain(GPS_verticalSpeedInCmS, -1500, 1500); } lastCoord[GPS_LONGITUDE] = gpsSol.llh.lon; lastCoord[GPS_LATITUDE] = gpsSol.llh.lat; lastAlt = gpsSol.llh.altCm; - lastMillis = currentMillis; } void GPS_reset_home_position(void) @@ -1876,7 +1867,7 @@ void GPS_reset_home_position(void) // PS: to test for gyro cal, check for !ARMED, since we cannot be here while disarmed other than via gyro cal } } - GPS_calculateDistanceFlownVerticalSpeed(true); // Initialize + GPS_calculateDistanceFlown(true); // Initialize } //////////////////////////////////////////////////////////////////////////////////// @@ -1901,8 +1892,8 @@ void GPS_calculateDistanceAndDirectionToHome(void) uint32_t dist; int32_t dir; GPS_distance_cm_bearing(&gpsSol.llh.lat, &gpsSol.llh.lon, &GPS_home[GPS_LATITUDE], &GPS_home[GPS_LONGITUDE], &dist, &dir); - GPS_distanceToHome = dist / 100; // m/s - GPS_distanceToHomeCm = dist; // cm/sec + GPS_distanceToHome = dist / 100; // m + GPS_distanceToHomeCm = dist; // cm GPS_directionToHome = dir / 10; // degrees * 10 or decidegrees } else { // If we don't have home set, do not display anything @@ -1914,11 +1905,21 @@ void GPS_calculateDistanceAndDirectionToHome(void) void onGpsNewData(void) { - static timeUs_t timeUs, lastTimeUs = 0; + static timeUs_t lastTimeUs = 0; + const timeUs_t timeUs = micros(); + + // calculate GPS solution interval + // !!! TOO MUCH JITTER TO BE USEFUL - need an exact time !!! + const float gpsDataIntervalS = cmpTimeUs(timeUs, lastTimeUs) / 1e6f; + // dirty hack to remove jitter from interval + if (gpsDataIntervalS < 0.15f) { + gpsDataIntervalSeconds = 0.1f; + } else if (gpsDataIntervalS < 0.4f) { + gpsDataIntervalSeconds = 0.2f; + } else { + gpsDataIntervalSeconds = 1.0f; + } - // Detect current sample rate of GPS solution - timeUs = micros(); - gpsSampleRateHz = 1e6f / cmpTimeUs(timeUs, lastTimeUs); lastTimeUs = timeUs; if (!(STATE(GPS_FIX) && gpsSol.numSat >= GPS_MIN_SAT_COUNT)) { @@ -1928,7 +1929,7 @@ void onGpsNewData(void) GPS_calculateDistanceAndDirectionToHome(); if (ARMING_FLAG(ARMED)) { - GPS_calculateDistanceFlownVerticalSpeed(false); + GPS_calculateDistanceFlown(false); } #ifdef USE_GPS_RESCUE @@ -1946,9 +1947,9 @@ void gpsSetFixState(bool state) } } -float gpsGetSampleRateHz(void) +float getGpsDataIntervalSeconds(void) { - return gpsSampleRateHz; + return gpsDataIntervalSeconds; } #endif // USE_GPS diff --git a/src/main/io/gps.h b/src/main/io/gps.h index ae609a931e..ecb1460a59 100644 --- a/src/main/io/gps.h +++ b/src/main/io/gps.h @@ -150,7 +150,6 @@ extern uint16_t GPS_distanceToHome; // distance to home point in meters extern uint32_t GPS_distanceToHomeCm; // distance to home point in cm extern int16_t GPS_directionToHome; // direction to home or hol point in degrees extern uint32_t GPS_distanceFlownInCm; // distance flown since armed in centimeters -extern int16_t GPS_verticalSpeedInCmS; // vertical speed in cm/s extern int16_t GPS_angle[ANGLE_INDEX_COUNT]; // it's the angles that must be applied for GPS correction extern float GPS_scaleLonDown; // this is used to offset the shrinking longitude as we go towards the poles extern int16_t nav_takeoff_bearing; @@ -214,4 +213,4 @@ void GPS_reset_home_position(void); void GPS_calc_longitude_scaling(int32_t lat); void GPS_distance_cm_bearing(int32_t *currentLat1, int32_t *currentLon1, int32_t *destinationLat2, int32_t *destinationLon2, uint32_t *dist, int32_t *bearing); void gpsSetFixState(bool state); -float gpsGetSampleRateHz(void); +float getGpsDataIntervalSeconds(void); diff --git a/src/main/msp/msp.c b/src/main/msp/msp.c index 7662e98a3c..7c0440fc51 100644 --- a/src/main/msp/msp.c +++ b/src/main/msp/msp.c @@ -938,6 +938,7 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce break; } +#if defined(USE_OSD) case MSP_OSD_CONFIG: { #define OSD_FLAGS_OSD_FEATURE (1 << 0) //#define OSD_FLAGS_OSD_SLAVE (1 << 1) @@ -948,7 +949,7 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce #define OSD_FLAGS_OSD_MSP_DEVICE (1 << 6) uint8_t osdFlags = 0; -#if defined(USE_OSD) + osdFlags |= OSD_FLAGS_OSD_FEATURE; osdDisplayPortDevice_e deviceType; @@ -979,7 +980,7 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce default: break; } -#endif + sbufWriteU8(dst, osdFlags); #ifdef USE_OSD_SD @@ -987,9 +988,8 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce sbufWriteU8(dst, vcdProfile()->video_system); #else sbufWriteU8(dst, VIDEO_SYSTEM_HD); -#endif +#endif // USE_OSD_SD -#ifdef USE_OSD // OSD specific, not applicable to OSD slaves. // Configuration @@ -1052,9 +1052,9 @@ static bool mspCommonProcessOutCommand(int16_t cmdMSP, sbuf_t *dst, mspPostProce sbufWriteU8(dst, osdConfig()->camera_frame_width); sbufWriteU8(dst, osdConfig()->camera_frame_height); -#endif // USE_OSD break; } +#endif // USE_OSD case MSP_OSD_CANVAS: { #ifdef USE_OSD @@ -1312,7 +1312,7 @@ case MSP_NAME: const uint8_t warningsLen = strlen(warningsBuffer); if (isBlinking) { - displayAttr |= DISPLAYPORT_ATTR_BLINK; + displayAttr |= DISPLAYPORT_BLINK; } sbufWriteU8(dst, displayAttr); // see displayPortSeverity_e sbufWriteU8(dst, warningsLen); // length byte followed by the actual characters @@ -1538,7 +1538,7 @@ case MSP_NAME: #ifdef USE_GPS_RESCUE case MSP_GPS_RESCUE: - sbufWriteU16(dst, gpsRescueConfig()->angle); + sbufWriteU16(dst, gpsRescueConfig()->maxRescueAngle); sbufWriteU16(dst, gpsRescueConfig()->initialAltitudeM); sbufWriteU16(dst, gpsRescueConfig()->descentDistanceM); sbufWriteU16(dst, gpsRescueConfig()->rescueGroundspeed); @@ -2808,7 +2808,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP, #ifdef USE_GPS_RESCUE case MSP_SET_GPS_RESCUE: - gpsRescueConfigMutable()->angle = sbufReadU16(src); + gpsRescueConfigMutable()->maxRescueAngle = sbufReadU16(src); gpsRescueConfigMutable()->initialAltitudeM = sbufReadU16(src); gpsRescueConfigMutable()->descentDistanceM = sbufReadU16(src); gpsRescueConfigMutable()->rescueGroundspeed = sbufReadU16(src); @@ -3565,7 +3565,7 @@ static mspResult_e mspProcessInCommand(mspDescriptor_t srcDesc, int16_t cmdMSP, } break; -#ifdef USE_FLASHFS +#if defined(USE_FLASHFS) && defined(USE_BLACKBOX) case MSP_DATAFLASH_ERASE: blackboxEraseAll(); diff --git a/src/main/osd/osd.c b/src/main/osd/osd.c index 37b339468b..57c3ceeb2e 100644 --- a/src/main/osd/osd.c +++ b/src/main/osd/osd.c @@ -449,7 +449,7 @@ static void osdDrawLogo(int x, int y) for (int row = 0; row < OSD_LOGO_ROWS; row++) { for (int column = 0; column < OSD_LOGO_COLS; column++) { if (fontOffset <= SYM_END_OF_FONT) - displayWriteChar(osdDisplayPort, x + column, y + row, DISPLAYPORT_ATTR_NORMAL, fontOffset++); + displayWriteChar(osdDisplayPort, x + column, y + row, DISPLAYPORT_SEVERITY_NORMAL, fontOffset++); } } } @@ -473,17 +473,17 @@ static void osdCompleteInitialization(void) char string_buffer[30]; tfp_sprintf(string_buffer, "V%s", FC_VERSION_STRING); - displayWrite(osdDisplayPort, midCol + 5, midRow, DISPLAYPORT_ATTR_NORMAL, string_buffer); + displayWrite(osdDisplayPort, midCol + 5, midRow, DISPLAYPORT_SEVERITY_NORMAL, string_buffer); #ifdef USE_CMS - displayWrite(osdDisplayPort, midCol - 8, midRow + 2, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT1); - displayWrite(osdDisplayPort, midCol - 4, midRow + 3, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT2); - displayWrite(osdDisplayPort, midCol - 4, midRow + 4, DISPLAYPORT_ATTR_NORMAL, CMS_STARTUP_HELP_TEXT3); + displayWrite(osdDisplayPort, midCol - 8, midRow + 2, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT1); + displayWrite(osdDisplayPort, midCol - 4, midRow + 3, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT2); + displayWrite(osdDisplayPort, midCol - 4, midRow + 4, DISPLAYPORT_SEVERITY_NORMAL, CMS_STARTUP_HELP_TEXT3); #endif #ifdef USE_RTC_TIME char dateTimeBuffer[FORMATTED_DATE_TIME_BUFSIZE]; if (osdFormatRtcDateTime(&dateTimeBuffer[0])) { - displayWrite(osdDisplayPort, midCol - 10, midRow + 6, DISPLAYPORT_ATTR_NORMAL, dateTimeBuffer); + displayWrite(osdDisplayPort, midCol - 10, midRow + 6, DISPLAYPORT_SEVERITY_NORMAL, dateTimeBuffer); } #endif @@ -732,9 +732,9 @@ static void osdGetBlackboxStatusString(char * buff) static void osdDisplayStatisticLabel(uint8_t x, uint8_t y, const char * text, const char * value) { - displayWrite(osdDisplayPort, x - 13, y, DISPLAYPORT_ATTR_NORMAL, text); - displayWrite(osdDisplayPort, x + 5, y, DISPLAYPORT_ATTR_NORMAL, ":"); - displayWrite(osdDisplayPort, x + 7, y, DISPLAYPORT_ATTR_NORMAL, value); + displayWrite(osdDisplayPort, x - 13, y, DISPLAYPORT_SEVERITY_NORMAL, text); + displayWrite(osdDisplayPort, x + 5, y, DISPLAYPORT_SEVERITY_NORMAL, ":"); + displayWrite(osdDisplayPort, x + 7, y, DISPLAYPORT_SEVERITY_NORMAL, value); } /* @@ -767,7 +767,7 @@ static bool osdDisplayStat(int statistic, uint8_t displayRow) tfp_sprintf(buff, "NO RTC"); } - displayWrite(osdDisplayPort, midCol - 13, displayRow, DISPLAYPORT_ATTR_NORMAL, buff); + displayWrite(osdDisplayPort, midCol - 13, displayRow, DISPLAYPORT_SEVERITY_NORMAL, buff); return true; } @@ -1021,7 +1021,7 @@ static bool osdRenderStatsContinue(void) } if (displayLabel) { - displayWrite(osdDisplayPort, midCol - (strlen("--- STATS ---") / 2), osdStatsRenderingState.row++, DISPLAYPORT_ATTR_NORMAL, "--- STATS ---"); + displayWrite(osdDisplayPort, midCol - (strlen("--- STATS ---") / 2), osdStatsRenderingState.row++, DISPLAYPORT_SEVERITY_NORMAL, "--- STATS ---"); return false; } } @@ -1128,10 +1128,10 @@ static timeDelta_t osdShowArmed(void) } else { ret = (REFRESH_1S / 2); } - displayWrite(osdDisplayPort, midCol - (strlen("ARMED") / 2), midRow, DISPLAYPORT_ATTR_NORMAL, "ARMED"); + displayWrite(osdDisplayPort, midCol - (strlen("ARMED") / 2), midRow, DISPLAYPORT_SEVERITY_NORMAL, "ARMED"); if (isFlipOverAfterCrashActive()) { - displayWrite(osdDisplayPort, midCol - (strlen(CRASH_FLIP_WARNING) / 2), midRow + 1, DISPLAYPORT_ATTR_NORMAL, CRASH_FLIP_WARNING); + displayWrite(osdDisplayPort, midCol - (strlen(CRASH_FLIP_WARNING) / 2), midRow + 1, DISPLAYPORT_SEVERITY_NORMAL, CRASH_FLIP_WARNING); } return ret; diff --git a/src/main/osd/osd_elements.c b/src/main/osd/osd_elements.c index 279299e010..e5f022791f 100644 --- a/src/main/osd/osd_elements.c +++ b/src/main/osd/osd_elements.c @@ -239,7 +239,7 @@ enum {UP, DOWN}; static int osdDisplayWrite(osdElementParms_t *element, uint8_t x, uint8_t y, uint8_t attr, const char *s) { if (IS_BLINK(element->item)) { - attr |= DISPLAYPORT_ATTR_BLINK; + attr |= DISPLAYPORT_BLINK; } return displayWrite(element->osdDisplayPort, x, y, attr, s); @@ -287,7 +287,7 @@ static void renderOsdEscRpmOrFreq(getEscRpmOrFreqFnPtr escFnPtr, osdElementParms const int rpm = MIN((*escFnPtr)(i),99999); const int len = tfp_sprintf(rpmStr, "%d", rpm); rpmStr[len] = '\0'; - osdDisplayWrite(element, x, y + i, DISPLAYPORT_ATTR_NORMAL, rpmStr); + osdDisplayWrite(element, x, y + i, DISPLAYPORT_SEVERITY_NORMAL, rpmStr); } element->drawElement = false; } @@ -666,7 +666,7 @@ static void osdElementAltitude(osdElementParms_t *element) int32_t alt = osdGetMetersToSelectedUnit(getEstimatedAltitudeCm()) / 100; if ((alt >= osdConfig()->alt_alarm) && ARMING_FLAG(ARMED)) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } if (haveBaro || haveGps) { @@ -713,7 +713,7 @@ static void osdElementArtificialHorizon(osdElementParms_t *element) for (int x = -4; x <= 4; x++) { const int y = ((-rollAngle * x) / 64) - pitchAngle; if (y >= 0 && y <= 81) { - osdDisplayWriteChar(element, element->elemPosX + x, element->elemPosY + (y / AH_SYMBOL_COUNT), DISPLAYPORT_ATTR_NORMAL, (SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT))); + osdDisplayWriteChar(element, element->elemPosX + x, element->elemPosY + (y / AH_SYMBOL_COUNT), DISPLAYPORT_SEVERITY_NORMAL, (SYM_AH_BAR9_0 + (y % AH_SYMBOL_COUNT))); } } @@ -743,7 +743,7 @@ static void osdElementUpDownReference(osdElementParms_t *element) int posX = element->elemPosX + lrintf(scaleRangef(psiB, -M_PIf / 4, M_PIf / 4, -14, 14)); int posY = element->elemPosY + lrintf(scaleRangef(thetaB, -M_PIf / 4, M_PIf / 4, -8, 8)); - osdDisplayWrite(element, posX, posY, DISPLAYPORT_ATTR_NORMAL, symbol[direction]); + osdDisplayWrite(element, posX, posY, DISPLAYPORT_SEVERITY_NORMAL, symbol[direction]); } element->drawElement = false; // element already drawn } @@ -756,10 +756,10 @@ static void osdElementAverageCellVoltage(osdElementParms_t *element) switch (batteryState) { case BATTERY_WARNING: - element->attr = DISPLAYPORT_ATTR_WARNING; + element->attr = DISPLAYPORT_SEVERITY_WARNING; break; case BATTERY_CRITICAL: - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; break; default: break; @@ -795,12 +795,12 @@ static void osdBackgroundCameraFrame(osdElementParms_t *element) element->buff[width - 1] = SYM_STICK_OVERLAY_CENTER; element->buff[width] = 0; // string terminator - osdDisplayWrite(element, xpos, ypos, DISPLAYPORT_ATTR_NORMAL, element->buff); + osdDisplayWrite(element, xpos, ypos, DISPLAYPORT_SEVERITY_NORMAL, element->buff); for (int i = 1; i < (height - 1); i++) { - osdDisplayWriteChar(element, xpos, ypos + i, DISPLAYPORT_ATTR_NORMAL, SYM_STICK_OVERLAY_VERTICAL); - osdDisplayWriteChar(element, xpos + width - 1, ypos + i, DISPLAYPORT_ATTR_NORMAL, SYM_STICK_OVERLAY_VERTICAL); + osdDisplayWriteChar(element, xpos, ypos + i, DISPLAYPORT_SEVERITY_NORMAL, SYM_STICK_OVERLAY_VERTICAL); + osdDisplayWriteChar(element, xpos + width - 1, ypos + i, DISPLAYPORT_SEVERITY_NORMAL, SYM_STICK_OVERLAY_VERTICAL); } - osdDisplayWrite(element, xpos, ypos + height - 1, DISPLAYPORT_ATTR_NORMAL, element->buff); + osdDisplayWrite(element, xpos, ypos + height - 1, DISPLAYPORT_SEVERITY_NORMAL, element->buff); element->drawElement = false; // element already drawn } @@ -1080,15 +1080,15 @@ static void osdElementGpsCoordinate(osdElementParms_t *element) static void osdElementGpsSats(osdElementParms_t *element) { if ((STATE(GPS_FIX) == 0) || (gpsSol.numSat < GPS_MIN_SAT_COUNT) ) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } #ifdef USE_GPS_RESCUE else if ((gpsSol.numSat < gpsRescueConfig()->minSats) && gpsRescueIsConfigured()) { - element->attr = DISPLAYPORT_ATTR_WARNING; + element->attr = DISPLAYPORT_SEVERITY_WARNING; } #endif else { - element->attr = DISPLAYPORT_ATTR_INFO; + element->attr = DISPLAYPORT_SEVERITY_INFO; } if (!gpsIsHealthy()) { @@ -1135,13 +1135,13 @@ static void osdBackgroundHorizonSidebars(osdElementParms_t *element) const int8_t hudwidth = AH_SIDEBAR_WIDTH_POS; const int8_t hudheight = AH_SIDEBAR_HEIGHT_POS; for (int y = -hudheight; y <= hudheight; y++) { - osdDisplayWriteChar(element, element->elemPosX - hudwidth, element->elemPosY + y, DISPLAYPORT_ATTR_NORMAL, SYM_AH_DECORATION); - osdDisplayWriteChar(element, element->elemPosX + hudwidth, element->elemPosY + y, DISPLAYPORT_ATTR_NORMAL, SYM_AH_DECORATION); + osdDisplayWriteChar(element, element->elemPosX - hudwidth, element->elemPosY + y, DISPLAYPORT_SEVERITY_NORMAL, SYM_AH_DECORATION); + osdDisplayWriteChar(element, element->elemPosX + hudwidth, element->elemPosY + y, DISPLAYPORT_SEVERITY_NORMAL, SYM_AH_DECORATION); } // AH level indicators - osdDisplayWriteChar(element, element->elemPosX - hudwidth + 1, element->elemPosY, DISPLAYPORT_ATTR_NORMAL, SYM_AH_LEFT); - osdDisplayWriteChar(element, element->elemPosX + hudwidth - 1, element->elemPosY, DISPLAYPORT_ATTR_NORMAL, SYM_AH_RIGHT); + osdDisplayWriteChar(element, element->elemPosX - hudwidth + 1, element->elemPosY, DISPLAYPORT_SEVERITY_NORMAL, SYM_AH_LEFT); + osdDisplayWriteChar(element, element->elemPosX + hudwidth - 1, element->elemPosY, DISPLAYPORT_SEVERITY_NORMAL, SYM_AH_RIGHT); element->drawElement = false; // element already drawn } @@ -1152,7 +1152,7 @@ static void osdElementLinkQuality(osdElementParms_t *element) uint16_t osdLinkQuality = 0; if (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } if (linkQualitySource == LQ_SOURCE_RX_PROTOCOL_CRSF) { // 0-99 @@ -1209,7 +1209,7 @@ static void osdElementMahDrawn(osdElementParms_t *element) const int mAhDrawn = getMAhDrawn(); if (mAhDrawn >= osdConfig()->cap_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } tfp_sprintf(element->buff, "%4d%c", mAhDrawn, SYM_MAH); @@ -1221,7 +1221,7 @@ static void osdElementWattHoursDrawn(osdElementParms_t *element) const float wattHoursDrawn = getWhDrawn(); if (mAhDrawn >= osdConfig()->cap_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } if (wattHoursDrawn < 1.0f) { @@ -1243,7 +1243,7 @@ static void osdElementMainBatteryUsage(osdElementParms_t *element) int displayBasis = usedCapacity; if (mAhDrawn >= osdConfig()->cap_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } switch (element->type) { @@ -1298,10 +1298,10 @@ static void osdElementMainBatteryVoltage(osdElementParms_t *element) switch (batteryState) { case BATTERY_WARNING: - element->attr = DISPLAYPORT_ATTR_WARNING; + element->attr = DISPLAYPORT_SEVERITY_WARNING; break; case BATTERY_CRITICAL: - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; break; default: break; @@ -1402,7 +1402,7 @@ static void osdElementRcChannels(osdElementParms_t *element) // Decimal notation can be added when tfp_sprintf supports float among fancy options. char fmtbuf[6]; tfp_sprintf(fmtbuf, "%5d", data); - osdDisplayWrite(element, xpos, ypos + i, DISPLAYPORT_ATTR_NORMAL, fmtbuf); + osdDisplayWrite(element, xpos, ypos + i, DISPLAYPORT_SEVERITY_NORMAL, fmtbuf); } } @@ -1414,7 +1414,7 @@ static void osdElementRemainingTimeEstimate(osdElementParms_t *element) const int mAhDrawn = getMAhDrawn(); if (mAhDrawn >= osdConfig()->cap_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } if (mAhDrawn <= 0.1 * osdConfig()->cap_alarm) { // also handles the mAhDrawn == 0 condition @@ -1435,7 +1435,7 @@ static void osdElementRssi(osdElementParms_t *element) } if (getRssiPercent() < osdConfig()->rssi_alarm) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } tfp_sprintf(element->buff, "%c%2d", SYM_RSSI, osdRssi); @@ -1473,11 +1473,11 @@ static void osdBackgroundStickOverlay(osdElementParms_t *element) for (unsigned y = 0; y < OSD_STICK_OVERLAY_HEIGHT; y++) { // draw the axes, vertical and horizonal if ((x == ((OSD_STICK_OVERLAY_WIDTH - 1) / 2)) && (y == (OSD_STICK_OVERLAY_HEIGHT - 1) / 2)) { - osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_ATTR_NORMAL, SYM_STICK_OVERLAY_CENTER); + osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_SEVERITY_NORMAL, SYM_STICK_OVERLAY_CENTER); } else if (x == ((OSD_STICK_OVERLAY_WIDTH - 1) / 2)) { - osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_ATTR_NORMAL, SYM_STICK_OVERLAY_VERTICAL); + osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_SEVERITY_NORMAL, SYM_STICK_OVERLAY_VERTICAL); } else if (y == ((OSD_STICK_OVERLAY_HEIGHT - 1) / 2)) { - osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_ATTR_NORMAL, SYM_STICK_OVERLAY_HORIZONTAL); + osdDisplayWriteChar(element, xpos + x, ypos + y, DISPLAYPORT_SEVERITY_NORMAL, SYM_STICK_OVERLAY_HORIZONTAL); } } } @@ -1505,7 +1505,7 @@ static void osdElementStickOverlay(osdElementParms_t *element) const uint8_t cursorY = OSD_STICK_OVERLAY_VERTICAL_POSITIONS - 1 - scaleRange(constrain(rcData[vertical_channel], PWM_RANGE_MIN, PWM_RANGE_MAX - 1), PWM_RANGE_MIN, PWM_RANGE_MAX, 0, OSD_STICK_OVERLAY_VERTICAL_POSITIONS); const char cursor = SYM_STICK_OVERLAY_SPRITE_HIGH + (cursorY % OSD_STICK_OVERLAY_SPRITE_HEIGHT); - osdDisplayWriteChar(element, xpos + cursorX, ypos + cursorY / OSD_STICK_OVERLAY_SPRITE_HEIGHT, DISPLAYPORT_ATTR_NORMAL, cursor); + osdDisplayWriteChar(element, xpos + cursorX, ypos + cursorY / OSD_STICK_OVERLAY_SPRITE_HEIGHT, DISPLAYPORT_SEVERITY_NORMAL, cursor); element->drawElement = false; // element already drawn } @@ -1523,7 +1523,7 @@ static void osdElementTimer(osdElementParms_t *element) const timeUs_t time = osdGetTimerValue(OSD_TIMER_SRC(timer)); const timeUs_t alarmTime = OSD_TIMER_ALARM(timer) * 60000000; // convert from minutes to us if (alarmTime != 0 && time >= alarmTime) { - element->attr = DISPLAYPORT_ATTR_CRITICAL; + element->attr = DISPLAYPORT_SEVERITY_CRITICAL; } } @@ -1951,7 +1951,7 @@ static void osdDrawSingleElement(displayPort_t *osdDisplayPort, uint8_t item) element.buff = (char *)&buff; element.osdDisplayPort = osdDisplayPort; element.drawElement = true; - element.attr = DISPLAYPORT_ATTR_NORMAL; + element.attr = DISPLAYPORT_SEVERITY_NORMAL; // Call the element drawing function if ((item >= OSD_SYS_GOGGLE_VOLTAGE) && (item < OSD_ITEM_COUNT)) { @@ -1987,7 +1987,7 @@ static void osdDrawSingleElementBackground(displayPort_t *osdDisplayPort, uint8_ // Call the element background drawing function osdElementBackgroundFunction[item](&element); if (element.drawElement) { - osdDisplayWrite(&element, elemPosX, elemPosY, DISPLAYPORT_ATTR_NORMAL, buff); + osdDisplayWrite(&element, elemPosX, elemPosY, DISPLAYPORT_SEVERITY_NORMAL, buff); } } diff --git a/src/main/osd/osd_warnings.c b/src/main/osd/osd_warnings.c index 28fed2b8fb..6a1e8a2225 100644 --- a/src/main/osd/osd_warnings.c +++ b/src/main/osd/osd_warnings.c @@ -76,7 +76,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) static unsigned armingDisabledDisplayIndex; warningText[0] = '\0'; - *displayAttr = DISPLAYPORT_ATTR_NORMAL; + *displayAttr = DISPLAYPORT_SEVERITY_NORMAL; *blinking = false; // Cycle through the arming disabled reasons @@ -106,7 +106,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) } tfp_sprintf(warningText, "%s", armingDisableFlagNames[armingDisabledDisplayIndex]); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; return; } else { armingDisabledUpdateTimeUs = 0; @@ -124,13 +124,13 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) } else { tfp_sprintf(warningText, "ARM IN %d.%d", armingDelayTime / 10, armingDelayTime % 10); } - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } #endif // USE_DSHOT if (osdWarnGetState(OSD_WARNING_FAIL_SAFE) && failsafeIsActive()) { tfp_sprintf(warningText, "FAIL SAFE"); - *displayAttr = DISPLAYPORT_ATTR_CRITICAL; + *displayAttr = DISPLAYPORT_SEVERITY_CRITICAL; *blinking = true; return; } @@ -139,11 +139,11 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) if (osdWarnGetState(OSD_WARNING_CRASH_FLIP) && IS_RC_MODE_ACTIVE(BOXFLIPOVERAFTERCRASH)) { if (isFlipOverAfterCrashActive()) { // if was armed in crash flip mode tfp_sprintf(warningText, CRASH_FLIP_WARNING); - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } else if (!ARMING_FLAG(ARMED)) { // if disarmed, but crash flip mode is activated tfp_sprintf(warningText, "CRASH FLIP SWITCH"); - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } } @@ -166,7 +166,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) *blinking = true; } - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } #endif // USE_LAUNCH_CONTROL @@ -174,7 +174,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // RSSI if (osdWarnGetState(OSD_WARNING_RSSI) && (getRssiPercent() < osdConfig()->rssi_alarm)) { tfp_sprintf(warningText, "RSSI LOW"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -182,7 +182,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // rssi dbm if (osdWarnGetState(OSD_WARNING_RSSI_DBM) && (getRssiDbm() < osdConfig()->rssi_dbm_alarm)) { tfp_sprintf(warningText, "RSSI DBM"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -191,7 +191,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // rsnr if (osdWarnGetState(OSD_WARNING_RSNR) && (getRsnr() < osdConfig()->rsnr_alarm)) { tfp_sprintf(warningText, "RSNR LOW"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -201,7 +201,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // Link Quality if (osdWarnGetState(OSD_WARNING_LINK_QUALITY) && (rxGetLinkQualityPercent() < osdConfig()->link_quality_alarm)) { tfp_sprintf(warningText, "LINK QUALITY"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -209,7 +209,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) if (osdWarnGetState(OSD_WARNING_BATTERY_CRITICAL) && batteryState == BATTERY_CRITICAL) { tfp_sprintf(warningText, " LAND NOW"); - *displayAttr = DISPLAYPORT_ATTR_CRITICAL; + *displayAttr = DISPLAYPORT_SEVERITY_CRITICAL; *blinking = true; return; } @@ -221,7 +221,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) !gpsRescueIsDisabled() && !gpsRescueIsAvailable()) { tfp_sprintf(warningText, "RESCUE N/A"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -234,7 +234,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) statistic_t *stats = osdGetStats(); if (cmpTimeUs(stats->armed_time, OSD_GPS_RESCUE_DISABLED_WARNING_DURATION_US) < 0) { tfp_sprintf(warningText, "RESCUE OFF"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -245,7 +245,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // Show warning if in HEADFREE flight mode if (FLIGHT_MODE(HEADFREE_MODE)) { tfp_sprintf(warningText, "HEADFREE"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -254,7 +254,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) const int16_t coreTemperature = getCoreTemperatureCelsius(); if (osdWarnGetState(OSD_WARNING_CORE_TEMPERATURE) && coreTemperature >= osdConfig()->core_temp_alarm) { tfp_sprintf(warningText, "CORE %c: %3d%c", SYM_TEMPERATURE, osdConvertTemperatureToSelectedUnit(coreTemperature), osdGetTemperatureSymbolForSelectedUnit()); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -306,7 +306,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) if (escWarningCount > 0) { tfp_sprintf(warningText, "%s", escWarningMsg); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -362,7 +362,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // If warning exists then notify, otherwise clear warning message if (dshotEscErrorLength > 3) { warningText[dshotEscErrorLength] = 0; // End string - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } else { @@ -373,7 +373,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) if (osdWarnGetState(OSD_WARNING_BATTERY_WARNING) && batteryState == BATTERY_WARNING) { tfp_sprintf(warningText, "LOW BATTERY"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; }/*else if (mixerRuntime.afterburnerInitiated) { @@ -386,7 +386,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // Show warning if rc smoothing hasn't initialized the filters if (osdWarnGetState(OSD_WARNING_RC_SMOOTHING) && ARMING_FLAG(ARMED) && !rcSmoothingInitializationComplete()) { tfp_sprintf(warningText, "RCSMOOTHING"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -395,7 +395,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // Show warning if mah consumed is over the configured limit if (osdWarnGetState(OSD_WARNING_OVER_CAP) && ARMING_FLAG(ARMED) && osdConfig()->cap_alarm > 0 && getMAhDrawn() >= osdConfig()->cap_alarm) { tfp_sprintf(warningText, "OVER CAP"); - *displayAttr = DISPLAYPORT_ATTR_WARNING; + *displayAttr = DISPLAYPORT_SEVERITY_WARNING; *blinking = true; return; } @@ -404,7 +404,7 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) // Show warning if battery is not fresh and battery continue is active if (hasUsedMAh()) { tfp_sprintf(warningText, "BATTERY CONTINUE"); - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } #endif // USE_BATTERY_CONTINUE @@ -413,14 +413,14 @@ void renderOsdWarning(char *warningText, bool *blinking, uint8_t *displayAttr) if (osdWarnGetState(OSD_WARNING_BATTERY_NOT_FULL) && !(ARMING_FLAG(ARMED) || ARMING_FLAG(WAS_EVER_ARMED)) && (getBatteryState() == BATTERY_OK) && getBatteryAverageCellVoltage() < batteryConfig()->vbatfullcellvoltage) { tfp_sprintf(warningText, "BATT < FULL"); - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; return; } // Visual beeper if (osdWarnGetState(OSD_WARNING_VISUAL_BEEPER) && osdGetVisualBeeperState()) { tfp_sprintf(warningText, " * * * *"); - *displayAttr = DISPLAYPORT_ATTR_INFO; + *displayAttr = DISPLAYPORT_SEVERITY_INFO; osdSetVisualBeeperState(false); return; } diff --git a/src/main/pg/displayport_profiles.h b/src/main/pg/displayport_profiles.h index 585d6fc412..22a7968c00 100644 --- a/src/main/pg/displayport_profiles.h +++ b/src/main/pg/displayport_profiles.h @@ -32,7 +32,7 @@ typedef struct displayPortProfile_s { // For attribute-rich OSDs - uint8_t fontSelection[DISPLAYPORT_ATTR_COUNT]; + uint8_t fontSelection[DISPLAYPORT_SEVERITY_COUNT]; uint8_t useDeviceBlink; // Use device local blink capability } displayPortProfile_t; diff --git a/src/main/pg/flash.c b/src/main/pg/flash.c index 1b3b8b4297..e28b570744 100644 --- a/src/main/pg/flash.c +++ b/src/main/pg/flash.c @@ -27,6 +27,7 @@ #include "drivers/bus_spi.h" #include "drivers/bus_quadspi.h" +#include "drivers/bus_octospi.h" #include "drivers/io.h" #include "pg/pg.h" @@ -42,12 +43,17 @@ PG_REGISTER_WITH_RESET_FN(flashConfig_t, flashConfig, PG_FLASH_CONFIG, 0); void pgResetFn_flashConfig(flashConfig_t *flashConfig) { + // CS pin can be used by all IO interfaces, not just SPI. flashConfig->csTag = IO_TAG(FLASH_CS_PIN); -#if defined(USE_SPI) && defined(FLASH_SPI_INSTANCE) + +#if defined(USE_FLASH_SPI) && defined(FLASH_SPI_INSTANCE) flashConfig->spiDevice = SPI_DEV_TO_CFG(spiDeviceByInstance(FLASH_SPI_INSTANCE)); #endif -#if defined(USE_QUADSPI) && defined(FLASH_QUADSPI_INSTANCE) +#if defined(USE_FLASH_QUADSPI) && defined(FLASH_QUADSPI_INSTANCE) flashConfig->quadSpiDevice = QUADSPI_DEV_TO_CFG(quadSpiDeviceByInstance(FLASH_QUADSPI_INSTANCE)); #endif +#if defined(USE_FLASH_OCTOSPI) && defined(FLASH_OCTOSPI_INSTANCE) + flashConfig->octoSpiDevice = OCTOSPI_DEV_TO_CFG(octoSpiDeviceByInstance(FLASH_OCTOSPI_INSTANCE)); +#endif } #endif diff --git a/src/main/pg/flash.h b/src/main/pg/flash.h index 20fc618b5a..96b0bb7643 100644 --- a/src/main/pg/flash.h +++ b/src/main/pg/flash.h @@ -30,6 +30,7 @@ typedef struct flashConfig_s { ioTag_t csTag; uint8_t spiDevice; uint8_t quadSpiDevice; + uint8_t octoSpiDevice; } flashConfig_t; PG_DECLARE(flashConfig_t, flashConfig); diff --git a/src/main/pg/gps_rescue.c b/src/main/pg/gps_rescue.c index d0ade463fe..525c32ca43 100644 --- a/src/main/pg/gps_rescue.c +++ b/src/main/pg/gps_rescue.c @@ -29,26 +29,28 @@ #include "gps_rescue.h" -PG_REGISTER_WITH_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 3); +PG_REGISTER_WITH_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, PG_GPS_RESCUE, 4); PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, .minRescueDth = 30, .altitudeMode = GPS_RESCUE_ALT_MODE_MAX, .rescueAltitudeBufferM = 10, - .ascendRate = 500, // cm/s, for altitude corrections on ascent + .ascendRate = 750, // cm/s, for altitude corrections on ascent .initialAltitudeM = 30, - .rescueGroundspeed = 500, - .angle = 40, + .rescueGroundspeed = 750, + .maxRescueAngle = 70, .rollMix = 150, + .pitchCutoffHz = 75, .descentDistanceM = 20, - .descendRate = 100, // cm/s, minimum for descent and landing phase, or for descending if starting high ascent + .descendRate = 150, // cm/s, minimum for descent and landing phase, or for descending if starting high ascent .targetLandingAltitudeM = 4, + .disarmThreshold = 20, .throttleMin = 1100, - .throttleMax = 1600, + .throttleMax = 1700, .throttleHover = 1275, .allowArmingWithoutFix = false, @@ -57,10 +59,10 @@ PG_RESET_TEMPLATE(gpsRescueConfig_t, gpsRescueConfig, .throttleP = 15, .throttleI = 15, - .throttleD = 15, + .throttleD = 20, .velP = 8, - .velI = 30, - .velD = 20, + .velI = 40, + .velD = 12, .yawP = 20, .useMag = GPS_RESCUE_USE_MAG diff --git a/src/main/pg/gps_rescue.h b/src/main/pg/gps_rescue.h index 0a78dbbc89..4d9bed050d 100644 --- a/src/main/pg/gps_rescue.h +++ b/src/main/pg/gps_rescue.h @@ -26,7 +26,7 @@ typedef struct gpsRescue_s { - uint16_t angle; // degrees + uint16_t maxRescueAngle; // degrees uint16_t initialAltitudeM; // meters uint16_t descentDistanceM; // meters uint16_t rescueGroundspeed; // centimeters per second @@ -47,6 +47,8 @@ typedef struct gpsRescue_s { uint16_t descendRate; uint16_t rescueAltitudeBufferM; // meters uint8_t rollMix; + uint8_t disarmThreshold; + uint8_t pitchCutoffHz; } gpsRescueConfig_t; diff --git a/src/main/pg/sdcard.c b/src/main/pg/sdcard.c index c19b71ee81..292203cb8f 100644 --- a/src/main/pg/sdcard.c +++ b/src/main/pg/sdcard.c @@ -30,6 +30,7 @@ #include "sdcard.h" #include "drivers/bus_spi.h" +#include "drivers/sdio.h" #include "drivers/io.h" #include "drivers/dma.h" #include "drivers/dma_reqmap.h" @@ -71,5 +72,11 @@ void pgResetFn_sdcardConfig(sdcardConfig_t *config) config->mode = SDCARD_MODE_SPI; } #endif + +#if defined(USE_SDCARD_SDIO) + if (SDIO_DEVICE != SDIOINVALID) { + config->mode = SDCARD_MODE_SDIO; + } +#endif } #endif diff --git a/src/main/platform.h b/src/main/platform.h index 3b3e19dd44..fb408352f0 100644 --- a/src/main/platform.h +++ b/src/main/platform.h @@ -118,8 +118,8 @@ #include "target/common_pre.h" -#ifdef __BOARD__ -#include "board.h" +#ifdef USE_CONFIG +#include "config.h" #endif #include "target.h" diff --git a/src/main/rx/rx.c b/src/main/rx/rx.c index 2c117a40ab..cbfef3c593 100644 --- a/src/main/rx/rx.c +++ b/src/main/rx/rx.c @@ -599,7 +599,7 @@ static uint16_t calculateChannelMovingAverage(uint8_t chan, uint16_t sample) static uint16_t getRxfailValue(uint8_t channel) { const rxFailsafeChannelConfig_t *channelFailsafeConfig = rxFailsafeChannelConfigs(channel); - const bool failsafeAuxSwitch = IS_RC_MODE_ACTIVE(BOXFAILSAFE); + const bool boxFailsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); switch (channelFailsafeConfig->mode) { case RX_FAILSAFE_MODE_AUTO: @@ -620,7 +620,7 @@ static uint16_t getRxfailValue(uint8_t channel) default: case RX_FAILSAFE_MODE_INVALID: case RX_FAILSAFE_MODE_HOLD: - if (failsafeAuxSwitch) { + if (boxFailsafeSwitchIsOn) { return rcRaw[channel]; // current values are allowed through on held channels with switch induced failsafe } else { return rcData[channel]; // last good value @@ -671,41 +671,46 @@ static void readRxChannelsApplyRanges(void) void detectAndApplySignalLossBehaviour(void) { const uint32_t currentTimeMs = millis(); - const bool failsafeAuxSwitch = IS_RC_MODE_ACTIVE(BOXFAILSAFE); - rxFlightChannelsValid = rxSignalReceived && !failsafeAuxSwitch; - // set rxFlightChannelsValid false when a packet is bad or we use a failsafe switch + const bool boxFailsafeSwitchIsOn = IS_RC_MODE_ACTIVE(BOXFAILSAFE); + rxFlightChannelsValid = rxSignalReceived && !boxFailsafeSwitchIsOn; + // rxFlightChannelsValid is false after 100ms of no packets, or as soon as use the BOXFAILSAFE switch is actioned + // rxFlightChannelsValid is true the instant we get a good packet or the BOXFAILSAFE switch is reverted + // can also go false with good packets but where one flight channel is bad > 300ms (PPM type receiver error) for (int channel = 0; channel < rxChannelCount; channel++) { float sample = rcRaw[channel]; // sample has latest RC value, rcData has last 'accepted valid' value const bool thisChannelValid = rxFlightChannelsValid && isPulseValid(sample); - // if the whole packet is bad, consider all channels bad - + // if the whole packet is bad, or BOXFAILSAFE switch is actioned, consider all channels bad if (thisChannelValid) { // reset the invalid pulse period timer for every good channel validRxSignalTimeout[channel] = currentTimeMs + MAX_INVALID_PULSE_TIME_MS; } - if (ARMING_FLAG(ARMED) && failsafeIsActive()) { - // while in failsafe Stage 2, whether Rx loss or switch induced, pass valid incoming flight channel values - // this allows GPS Rescue to detect the 30% requirement for termination + if (failsafeIsActive()) { + // we are in failsafe Stage 2, whether Rx loss or BOXFAILSAFE induced + // pass valid incoming flight channel values to FC, + // so that GPS Rescue can get the 30% requirement for termination of the rescue if (channel < NON_AUX_CHANNEL_COUNT) { if (!thisChannelValid) { if (channel == THROTTLE ) { - sample = failsafeConfig()->failsafe_throttle; // stage 2 failsafe throttle value + sample = failsafeConfig()->failsafe_throttle; + // stage 2 failsafe throttle value. In GPS Rescue Flight mode, gpsRescueGetThrottle overrides, late in mixer.c } else { sample = rxConfig()->midrc; } } } else { - // During Stage 2, set aux channels as per Stage 1 configuration + // set aux channels as per Stage 1 failsafe hold/set values, allow all for Failsafe and GPS rescue MODE switches sample = getRxfailValue(channel); } } else { - if (failsafeAuxSwitch) { + // we are normal, or in failsafe stage 1 + if (boxFailsafeSwitchIsOn) { + // BOXFAILSAFE active, but not in stage 2 yet, use stage 1 values sample = getRxfailValue(channel); // set channels to Stage 1 values immediately failsafe switch is activated } else if (!thisChannelValid) { - // everything was normal and this channel was invalid + // everything is normal but this channel was invalid if (cmp32(currentTimeMs, validRxSignalTimeout[channel]) < 0) { // first 300ms of Stage 1 failsafe sample = rcData[channel]; @@ -720,6 +725,7 @@ void detectAndApplySignalLossBehaviour(void) // set channels that are invalid for more than 300ms to Stage 1 values } } + // everything is normal, ie rcData[channel] will be set to rcRaw(channel) via 'sample' } sample = constrainf(sample, PWM_PULSE_MIN, PWM_PULSE_MAX); @@ -739,10 +745,10 @@ void detectAndApplySignalLossBehaviour(void) if (rxFlightChannelsValid) { failsafeOnValidDataReceived(); - // --> start the timer to exit stage 2 failsafe + // --> start the timer to exit stage 2 failsafe 100ms after losing all packets or the BOXFAILSAFE switch is actioned } else { failsafeOnValidDataFailed(); - // -> start timer to enter stage2 failsafe + // -> start timer to enter stage2 failsafe the instant we get a good packet or the BOXFAILSAFE switch is reverted } DEBUG_SET(DEBUG_RX_SIGNAL_LOSS, 3, rcData[THROTTLE]); diff --git a/src/main/startup/system_stm32h7xx.c b/src/main/startup/system_stm32h7xx.c index 890ed7ee57..c22fc2f19b 100644 --- a/src/main/startup/system_stm32h7xx.c +++ b/src/main/startup/system_stm32h7xx.c @@ -735,6 +735,12 @@ void SystemInit (void) systemProcessResetReason(); #endif +#if defined(USE_FLASH_MEMORY_MAPPED) + memoryMappedModeInit(); + + // !IMPORTANT! Do NOT reset peripherals, clocks and GPIO pins used by the MCU to access the memory-mapped flash!!! +#endif + // FPU settings #if (__FPU_PRESENT == 1) && (__FPU_USED == 1) SCB->CPACR |= ((3UL << 10*2)|(3UL << 11*2)); // Set CP10 and CP11 Full Access diff --git a/src/main/target/SITL/target.c b/src/main/target/SITL/target.c index 0a550430a1..24987e560c 100644 --- a/src/main/target/SITL/target.c +++ b/src/main/target/SITL/target.c @@ -520,7 +520,7 @@ static motorDevice_t motorPwmDevice = { .enable = pwmEnableMotors, .disable = pwmDisableMotors, .isMotorEnabled = pwmIsMotorEnabled, - .updateStart = motorUpdateStartNull, + .decodeTelemetry = motorDecodeTelemetryNull, .write = pwmWriteMotor, .writeInt = pwmWriteMotorInt, .updateComplete = pwmCompleteMotorUpdate, diff --git a/src/main/target/STM32H723/target.h b/src/main/target/STM32H723/target.h index a60a97fd65..3283a66969 100644 --- a/src/main/target/STM32H723/target.h +++ b/src/main/target/STM32H723/target.h @@ -20,15 +20,35 @@ #pragma once +#ifndef TARGET_BOARD_IDENTIFIER #define TARGET_BOARD_IDENTIFIER "SH72" +#endif +#ifndef USBD_PRODUCT_STRING #define USBD_PRODUCT_STRING "Betaflight STM32H723" +#endif +#if !defined(USE_I2C) +#define USE_I2C #define USE_I2C_DEVICE_1 #define USE_I2C_DEVICE_2 #define USE_I2C_DEVICE_3 #define USE_I2C_DEVICE_4 #define USE_I2C_DEVICE_5 +#define I2C_FULL_RECONFIGURABILITY +#endif + +// Provide a default so that this target builds on the build server. +#if !defined(USE_SPI) +#define USE_SPI +#define USE_SPI_DEVICE_1 +#define USE_SPI_DEVICE_2 +#define USE_SPI_DEVICE_3 +#define USE_SPI_DEVICE_4 +#define USE_SPI_DEVICE_5 +#define USE_SPI_DEVICE_6 +#define SPI_FULL_RECONFIGURABILITY +#endif #define USE_UART1 #define USE_UART2 @@ -43,13 +63,6 @@ #define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 10) -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 -#define USE_SPI_DEVICE_3 -#define USE_SPI_DEVICE_4 -#define USE_SPI_DEVICE_5 -#define USE_SPI_DEVICE_6 - #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff #define TARGET_IO_PORTC 0xffff @@ -58,9 +71,6 @@ #define TARGET_IO_PORTF 0xffff #define TARGET_IO_PORTG 0xffff -#define USE_I2C -#define I2C_FULL_RECONFIGURABILITY - #define USE_BEEPER #ifdef USE_SDCARD @@ -68,8 +78,6 @@ #define USE_SDCARD_SDIO #endif -#define USE_SPI -#define SPI_FULL_RECONFIGURABILITY #define USE_VCP @@ -84,4 +92,6 @@ #define USE_ADC +#if !defined(USE_EXST) #define USE_CUSTOM_DEFAULTS +#endif diff --git a/src/main/target/STM32H723/target.mk b/src/main/target/STM32H723/target.mk index 0930806cba..5fb733e16d 100644 --- a/src/main/target/STM32H723/target.mk +++ b/src/main/target/STM32H723/target.mk @@ -19,7 +19,9 @@ RX_SRC = \ H723xG_TARGETS += $(TARGET) +ifneq ($(EXST),yes) CUSTOM_DEFAULTS_EXTENDED = yes +endif FEATURES += VCP SDCARD_SPI SDCARD_SDIO ONBOARDFLASH diff --git a/src/main/target/STM32H730/target.h b/src/main/target/STM32H730/target.h index 4f1404b846..8d54f3b26b 100644 --- a/src/main/target/STM32H730/target.h +++ b/src/main/target/STM32H730/target.h @@ -74,7 +74,7 @@ #define USE_UART8 #define USE_UART9 #define USE_UART10 -#define USE_LP_UART1 +#define USE_LPUART1 #define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 11) diff --git a/src/main/target/STM32H750/target.h b/src/main/target/STM32H750/target.h index 71b442528a..ca656b9b2d 100644 --- a/src/main/target/STM32H750/target.h +++ b/src/main/target/STM32H750/target.h @@ -84,9 +84,9 @@ #define USE_UART6 #define USE_UART7 #define USE_UART8 -#define USE_LP_UART1 +#define USE_LPUART1 -#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 8) +#define SERIAL_PORT_COUNT (UNIFIED_SERIAL_PORT_COUNT + 9) #define TARGET_IO_PORTA 0xffff #define TARGET_IO_PORTB 0xffff diff --git a/src/main/target/common_post.h b/src/main/target/common_post.h index 61049fccc2..c9ac977397 100644 --- a/src/main/target/common_post.h +++ b/src/main/target/common_post.h @@ -151,8 +151,13 @@ #undef USE_TELEMETRY_SRXL #ifdef USE_SERIALRX_FPORT +#ifndef USE_TELEMETRY #define USE_TELEMETRY #endif +#ifndef USE_TELEMETRY_SMARTPORT +#define USE_TELEMETRY_SMARTPORT +#endif +#endif #endif #if !defined(USE_SERIALRX_CRSF) @@ -233,6 +238,10 @@ #undef USE_ADC_INTERNAL #endif +#if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX) +#define USE_BLACKBOX +#endif + #ifdef USE_FLASH #define USE_FLASHFS #define USE_FLASH_TOOLS @@ -254,6 +263,18 @@ #define USE_FLASH_CHIP #endif +#if defined(USE_SPI) && (defined(USE_FLASH_M25P16) || defined(USE_FLASH_W25M512) || defined(USE_FLASH_W25N01G) || defined(USE_FLASH_W25M02G)) +#define USE_FLASH_SPI +#endif + +#if defined(USE_QUADSPI) && (defined(USE_FLASH_W25Q128FV) || defined(USE_FLASH_W25N01G)) +#define USE_FLASH_QUADSPI +#endif + +#if defined(USE_OCTOSPI) && (defined(USE_FLASH_W25Q128FV)) +#define USE_FLASH_OCTOSPI +#endif + #ifndef USE_FLASH_CHIP #undef USE_FLASHFS #endif @@ -306,6 +327,16 @@ #define USE_SPI_GYRO #endif +#ifndef SIMULATOR_BUILD +#ifndef USE_ACC +#define USE_ACC +#endif + +#ifndef USE_GYRO +#define USE_GYRO +#endif +#endif + // CX10 is a special case of SPI RX which requires XN297 #if defined(USE_RX_CX10) #define USE_RX_XN297 @@ -426,7 +457,7 @@ #undef USE_ESCSERIAL #endif -#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) +#if defined(CONFIG_IN_RAM) || defined(CONFIG_IN_FILE) || defined(CONFIG_IN_EXTERNAL_FLASH) || defined(CONFIG_IN_SDCARD) || defined(CONFIG_IN_MEMORY_MAPPED_FLASH) #ifndef EEPROM_SIZE #define EEPROM_SIZE 4096 #endif @@ -445,6 +476,29 @@ extern uint8_t __config_end; #define USE_FLASH_BOOT_LOADER #endif +#if defined(USE_FLASH_MEMORY_MAPPED) +#if !defined(USE_RAM_CODE) +#define USE_RAM_CODE +#endif + +#define MMFLASH_CODE RAM_CODE +#define MMFLASH_CODE_NOINLINE RAM_CODE NOINLINE + +#define MMFLASH_DATA FAST_DATA +#define MMFLASH_DATA_ZERO_INIT FAST_DATA_ZERO_INIT +#else +#define MMFLASH_CODE +#define MMFLASH_CODE_NOINLINE +#define MMFLASH_DATA +#define MMFLASH_DATA_ZERO_INIT +#endif + +#ifdef USE_RAM_CODE +// RAM_CODE for methods that need to be in RAM, but don't need to be in the fastest type of memory. +// Note: if code is marked as RAM_CODE it *MUST* be in RAM, there is no alternative unlike functions marked with FAST_CODE/CCM_CODE +#define RAM_CODE __attribute__((section(".ram_code"))) +#endif + #if !defined(USE_RPM_FILTER) #undef USE_DYN_IDLE #endif diff --git a/src/main/target/common_pre.h b/src/main/target/common_pre.h index ab2971733d..801504944c 100644 --- a/src/main/target/common_pre.h +++ b/src/main/target/common_pre.h @@ -421,7 +421,7 @@ extern uint8_t _dmaram_end__; #endif // !defined(CLOUD_BUILD) #if !defined(LED_MAX_STRIP_LENGTH) -#ifdef USE_LEDSTRIP_64 +#ifdef USE_LED_STRIP_64 #define LED_MAX_STRIP_LENGTH 64 #else #define LED_MAX_STRIP_LENGTH 32 @@ -439,10 +439,6 @@ extern uint8_t _dmaram_end__; #endif #endif -#if (defined(USE_SDCARD) || defined(USE_FLASH)) && !defined(USE_BLACKBOX) -#define USE_BLACKBOX -#endif - #if defined(USE_PINIO) #define USE_PINIOBOX #define USE_PIN_PULL_UP_DOWN diff --git a/src/test/unit/arming_prevention_unittest.cc b/src/test/unit/arming_prevention_unittest.cc index 6c1a8d672c..2fceb23724 100644 --- a/src/test/unit/arming_prevention_unittest.cc +++ b/src/test/unit/arming_prevention_unittest.cc @@ -97,8 +97,10 @@ extern "C" { bool mockIsUpright = false; uint8_t activePidLoopDenom = 1; - float gpsGetSampleRateHz(void) { return 10.0f; } + float getGpsDataIntervalSeconds(void) { return 0.1f; } + void pt1FilterUpdateCutoff(pt1Filter_t *filter, float k) { filter->k = k; } void pt2FilterUpdateCutoff(pt2Filter_t *filter, float k) { filter->k = k; } + void pt3FilterUpdateCutoff(pt3Filter_t *filter, float k) { filter->k = k; } } uint32_t simulationFeatureFlags = 0; @@ -1143,11 +1145,18 @@ extern "C" { UNUSED(throttleDLpf); return 0.0f; } - void pt3FilterInit(pt3Filter_t *pitchLpf, float) { - UNUSED(pitchLpf); + void pt1FilterInit(pt1Filter_t *velocityDLpf, float) { + UNUSED(velocityDLpf); } - float pt3FilterApply(pt3Filter_t *pitchLpf, float) { - UNUSED(pitchLpf); + float pt1FilterApply(pt1Filter_t *velocityDLpf, float) { + UNUSED(velocityDLpf); + return 0.0f; + } + void pt3FilterInit(pt3Filter_t *velocityUpsampleLpf, float) { + UNUSED(velocityUpsampleLpf); + } + float pt3FilterApply(pt3Filter_t *velocityUpsampleLpf, float) { + UNUSED(velocityUpsampleLpf); return 0.0f; } void getRcDeflectionAbs(void) {} diff --git a/src/test/unit/flight_imu_unittest.cc b/src/test/unit/flight_imu_unittest.cc index c901df0fb0..a78daf0421 100644 --- a/src/test/unit/flight_imu_unittest.cc +++ b/src/test/unit/flight_imu_unittest.cc @@ -213,7 +213,6 @@ extern "C" { mag_t mag; gpsSolutionData_t gpsSol; - int16_t GPS_verticalSpeedInCmS; uint8_t debugMode; int16_t debug[DEBUG16_VALUE_COUNT]; diff --git a/src/test/unit/platform.h b/src/test/unit/platform.h index 2a01524310..72355cf6c9 100644 --- a/src/test/unit/platform.h +++ b/src/test/unit/platform.h @@ -44,7 +44,7 @@ #define USE_TRANSPONDER #ifndef LED_MAX_STRIP_LENGTH - #ifdef USE_LEDSTRIP_64 + #ifdef USE_LED_STRIP_64 #define LED_MAX_STRIP_LENGTH 64 #else #define LED_MAX_STRIP_LENGTH 32 diff --git a/support/scripts/build_nucleoh723zg_mmapped.sh b/support/scripts/build_nucleoh723zg_mmapped.sh new file mode 100644 index 0000000000..35cc3088b7 --- /dev/null +++ b/support/scripts/build_nucleoh723zg_mmapped.sh @@ -0,0 +1,108 @@ +#!/bin/sh +set -x + +make DEBUG=INFO EXST=yes EXST_ADJUST_VMA=0x90100000 TARGET=STM32H723 EXTRA_FLAGS="\ +-D'TARGET_BOARD_IDENTIFIER=\"H723\"' \ +-D'USBD_PRODUCT_STRING=\"Nucleo-H723-MMAPPED\"' \ +\ +-D'EEPROM_SIZE=8192' \ +\ +-DUSE_BUTTONS \ +-D'BUTTON_A_PIN=PC13' \ +-DBUTTON_A_PIN_INVERTED \ +-D'BUTTON_B_PIN=PC13' \ +-DBUTTON_B_PIN_INVERTED \ +\ +-DUSE_OCTOSPI \ +-DUSE_OCTOSPI_DEVICE_1 \ +-D'OCTOSPIM_P1_SCK_PIN=PB2' \ +-D'OCTOSPIM_P1_CS_PIN=PB6' \ +-D'OCTOSPIM_P1_IO0_PIN=PD11' \ +-D'OCTOSPIM_P1_IO1_PIN=PD12' \ +-D'OCTOSPIM_P1_IO2_PIN=PE2' \ +-D'OCTOSPIM_P1_IO3_PIN=PD13' \ +-D'OCTOSPIM_P1_IO4_PIN=NONE' \ +-D'OCTOSPIM_P1_IO5_PIN=NONE' \ +-D'OCTOSPIM_P1_IO6_PIN=NONE' \ +-D'OCTOSPIM_P1_IO7_PIN=NONE' \ +\ +-D'OCTOSPIM_P1_MODE=OCTOSPIM_P1_MODE_IO03_ONLY' \ +-D'OCTOSPIM_P1_CS_FLAGS=(OCTOSPIM_P1_CS_HARDWARE)' \ +\ +-DUSE_SPI \ +\ +-DUSE_SPI_DEVICE_1 \ +-D'SPI1_SCK_PIN=PB3' \ +-D'SPI1_MISO_PIN=PB4' \ +-D'SPI1_MOSI_PIN=PB5' \ +\ +-DUSE_SPI_DEVICE_2 \ +-D'SPI2_SCK_PIN=NONE' \ +-D'SPI2_MISO_PIN=NONE' \ +-D'SPI2_MOSI_PIN=NONE' \ +\ +-DUSE_SPI_DEVICE_3 \ +-D'SPI3_SCK_PIN=PC10' \ +-D'SPI3_MISO_PIN=PC11' \ +-D'SPI3_MOSI_PIN=PC12' \ +\ +-DUSE_SPI_DEVICE_4 \ +-D'SPI4_SCK_PIN=NONE' \ +-D'SPI4_MISO_PIN=NONE' \ +-D'SPI4_MOSI_PIN=NONE' \ +\ +-DUSE_SPI_DEVICE_5 \ +-D'SPI5_SCK_PIN=NONE' \ +-D'SPI5_MISO_PIN=NONE' \ +-D'SPI5_MOSI_PIN=NONE' \ +\ +-DUSE_SPI_DEVICE_6 \ +-D'SPI6_SCK_PIN=NONE' \ +-D'SPI6_MISO_PIN=NONE' \ +-D'SPI6_MOSI_PIN=NONE' \ +\ +-DUSE_FLASH_TOOLS \ +-DUSE_FLASH_W25Q128FV \ +-DUSE_FLASH_MEMORY_MAPPED \ +-DCONFIG_IN_MEMORY_MAPPED_FLASH \ +-D'FLASH_SPI_INSTANCE=NULL' \ +-D'FLASH_CS_PINS=NONE' \ +\ +-DUSE_SDCARD \ +-D'SDCARD_DETECT_PIN=NONE' \ +-D'SDIO_DEVICE=SDIODEV_2' \ +-D'SDIO_USE_4BIT=false' \ +-D'SDIO_CK_PIN=PD6' \ +-D'SDIO_CMD_PIN=PD7' \ +-D'SDIO_D0_PIN=PB14' \ +-D'SDIO_D1_PIN=NONE' \ +-D'SDIO_D2_PIN=NONE' \ +-D'SDIO_D3_PIN=NONE' \ +\ +-D'TARGET_IO_PORTA=0xffff' \ +-D'TARGET_IO_PORTB=0xffff' \ +-D'TARGET_IO_PORTC=0xffff' \ +-D'TARGET_IO_PORTD=0xffff' \ +-D'TARGET_IO_PORTE=0xffff' \ +-D'TARGET_IO_PORTF=0xffff' \ +-D'TARGET_IO_PORTG=0xffff' \ +\ +-DUSE_USB_ID \ +\ +-DUSE_I2C \ +-DUSE_I2C_DEVICE_1 \ +-D'I2C1_SCL=PB8' \ +-D'I2C1_SDA=PB9' \ +-D'I2C_DEVICE=(I2CDEV_1)' \ +\ +-DUSE_ACC \ +-DUSE_ACC_SPI_MPU6500 \ +-DUSE_GYRO \ +-DUSE_GYRO_SPI_MPU6500 \ +\ +-D'ADC1_DMA_OPT=8' \ +-D'ADC2_DMA_OPT=9' \ +-D'ADC3_DMA_OPT=10' \ +\ +-DENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT \ +" \ No newline at end of file diff --git a/support/scripts/build_spracingh7rf.sh b/support/scripts/build_spracingh7rf.sh new file mode 100644 index 0000000000..9f51863e54 --- /dev/null +++ b/support/scripts/build_spracingh7rf.sh @@ -0,0 +1,145 @@ +#!/bin/sh +set -x + +make DEBUG=INFO TARGET=STM32H730 EXTRA_FLAGS="\ +-D'TARGET_BOARD_IDENTIFIER=\"SP7R\"' \ +-D'USBD_PRODUCT_STRING=\"SPRacingH7RF\"' \ +\ +-D'EEPROM_SIZE=8192' \ +-DUSE_SPRACING_PERSISTENT_RTC_WORKAROUND \ +\ +-DUSE_BUTTONS \ +-D'BUTTON_A_PIN=PC14' \ +-DBUTTON_A_PIN_INVERTED \ +-D'BUTTON_B_PIN=PC14' \ +-DBUTTON_B_PIN_INVERTED \ +\ +-DUSE_OCTOSPI \ +-DUSE_OCTOSPI_DEVICE_1 \ +-D'OCTOSPIM_P1_SCK_PIN=PB2' \ +-D'OCTOSPIM_P1_CS_PIN=PB10' \ +-D'OCTOSPIM_P1_IO0_PIN=PD11' \ +-D'OCTOSPIM_P1_IO1_PIN=PD12' \ +-D'OCTOSPIM_P1_IO2_PIN=PE2' \ +-D'OCTOSPIM_P1_IO3_PIN=PD13' \ +-D'OCTOSPIM_P1_IO4_PIN=NONE' \ +-D'OCTOSPIM_P1_IO5_PIN=NONE' \ +-D'OCTOSPIM_P1_IO6_PIN=NONE' \ +-D'OCTOSPIM_P1_IO7_PIN=NONE' \ +-D'OCTOSPIM_P1_MODE=OCTOSPIM_P1_MODE_IO03_ONLY' \ +-D'OCTOSPIM_P1_CS_FLAGS=(OCTOSPIM_P1_CS_HARDWARE)' \ +\ +-DUSE_SPI \ +\ +-DUSE_SPI_DEVICE_2 \ +-D'SPI2_SCK_PIN=PD3' \ +-D'SPI2_MISO_PIN=PB14' \ +-D'SPI2_MOSI_PIN=PB15' \ +-D'SPI2_NSS_PIN=PB12' \ +\ +-DUSE_SPI_DEVICE_6 \ +-D'SPI6_SCK_PIN=PB3' \ +-D'SPI6_MISO_PIN=PB4' \ +-D'SPI6_MOSI_PIN=PB5' \ +-D'SPI6_NSS_PIN=PA15' \ +\ +-D'SX1280_BUSY_PIN=PC7' \ +-D'SX1280_DIO1_PIN=PC6' \ +-D'SX1280_DIO2_PIN=PD4' \ +-D'SX1280_DIO3_PIN=NONE' \ +-D'SX1280_NRESET_PIN=PD10' \ +-DUSE_RX_SPI \ +-DUSE_RX_EXPRESSLRS \ +-DUSE_RX_SX1280 \ +-D'RX_SPI_INSTANCE=SPI2' \ +-D'RX_NSS_PIN=SPI2_NSS_PIN' \ +-D'RX_SPI_EXTI_PIN=SX1280_DIO1_PIN' \ +-D'RX_EXPRESSLRS_SPI_RESET_PIN=SX1280_NRESET_PIN' \ +-D'RX_EXPRESSLRS_SPI_BUSY_PIN=SX1280_BUSY_PIN' \ +-D'RX_EXPRESSLRS_TIMER_INSTANCE=TIM6' \ +-D'DEFAULT_RX_FEATURE=FEATURE_RX_SPI' \ +-D'RX_SPI_DEFAULT_PROTOCOL=RX_SPI_EXPRESSLRS' \ +\ +-D'VTX_ENABLE_PIN=PC15' \ +-D'PINIO1_PIN=VTX_ENABLE_PIN' \ +\ +-DUSE_FLASH_MEMORY_MAPPED \ +-DUSE_FLASH_W25Q128FV \ +-D'FLASH_OCTOSPI_INSTANCE=OCTOSPI1' \ +-DCONFIG_IN_MEMORY_MAPPED_FLASH \ +-DUSE_FIRMWARE_PARTITION \ +\ +-D'SDCARD_DETECT_PIN=PC13' \ +-DSDCARD_DETECT_INVERTED \ +-D'SDIO_DEVICE=SDIODEV_1' \ +-D'SDIO_USE_4BIT=true' \ +-D'SDIO_CK_PIN=PC12' \ +-D'SDIO_CMD_PIN=PD2' \ +-D'SDIO_D0_PIN=PC8' \ +-D'SDIO_D1_PIN=PC9' \ +-D'SDIO_D2_PIN=PC10' \ +-D'SDIO_D3_PIN=PC11' \ +\ +-D'TARGET_IO_PORTA=0xffff' \ +-D'TARGET_IO_PORTB=(0xffff & ~(BIT(2)|BIT(6)))' \ +-D'TARGET_IO_PORTC=0xffff' \ +-D'TARGET_IO_PORTD=(0xffff & ~(BIT(11)|BIT(12)|BIT(13)))' \ +-D'TARGET_IO_PORTE=(0xffff & ~(BIT(2)|BIT(7)|BIT(8)|BIT(9)|BIT(10)))' \ +-D'TARGET_IO_PORTF=0xffff' \ +-D'TARGET_IO_PORTG=0xffff' \ +-D'TARGET_IO_PORTH=0xffff' \ +\ +-DUSE_I2C \ +-DUSE_I2C_DEVICE_1 \ +-D'I2C1_SCL=PB8' \ +-D'I2C1_SDA=PB9' \ +\ +-DUSE_I2C_DEVICE_2 \ +-D'I2C2_SCL=PB10' \ +-D'I2C2_SDA=PB11' \ +-D'MAG_I2C_INSTANCE=(I2CDEV_1)' \ +-D'BARO_I2C_INSTANCE=(I2CDEV_2)' \ +\ +-DUSE_ACC \ +-DUSE_GYRO \ +\ +-DUSE_MPU_DATA_READY_SIGNAL \ +-DENSURE_MPU_DATA_READY_IS_LOW \ +\ +-D'ADC3_DMA_OPT=10' \ +-D'ADC_INSTANCE=ADC3' \ +-D'CURRENT_METER_2_ADC_PIN=PC0' \ +-D'CURRENT_METER_2_ADC_INSTANCE=ADC3' \ +-D'CURRENT_METER_1_ADC_PIN=PC1' \ +-D'CURRENT_METER_1_ADC_INSTANCE=ADC3' \ +-D'EXTERNAL1_ADC_PIN=PC2' \ +-D'EXTERNAL1_ADC_INSTANCE=ADC3' \ +-D'VIDEO_IN_ADC_PIN=PC5' \ +-D'VIDEO_OUT_ADC_PIN=PC4' \ +-D'VBAT_ADC_PIN=PC3' \ +-D'VBAT_ADC_INSTANCE=ADC3' \ +-D'RSSI_ADC_PIN=CURRENT_METER_2_ADC_PIN' \ +-D'RSSI_ADC_INSTANCE=CURRENT_METER_2_ADC_INSTANCE' \ +-D'CURRENT_METER_ADC_PIN=CURRENT_METER_1_ADC_PIN' \ +-D'CURRENT_METER_ADC_INSTANCE=CURRENT_METER_1_ADC_INSTANCE' \ +-D'DEFAULT_VOLTAGE_METER_SOURCE=VOLTAGE_METER_ADC' \ +-D'DEFAULT_CURRENT_METER_SOURCE=CURRENT_METER_ADC' \ +\ +-DENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT \ +\ +-DUSE_SDCARD \ +-DUSE_ACC_SPI_ICM42605 \ +-DUSE_ACC_SPI_ICM42688P \ +-DUSE_GYRO_SPI_ICM42605 \ +-DUSE_GYRO_SPI_ICM42688P \ +-DUSE_FLASH_W25Q128FV \ +" + +# Settings that are currently defined in target/common_pre.h for non-cloud builds that probably shouldn't be. +# There are here to illustrate that they SHOULD be included in THIS target when they are removed by default. + +#-DUSE_MAG \ +#-DUSE_MAG_HMC5883 \ +#-DUSE_MAG_QMC5883 \ +#-DUSE_BARO \ +#-DUSE_BARO_BMP388 \