1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-19 14:25:20 +03:00

Merge remote-tracking branch 'origin/4.4-maintenance' into sl-4.4.0

This commit is contained in:
skyfpv 2023-05-01 09:32:00 -06:00
commit 5b42e11157
452 changed files with 17994 additions and 716 deletions

129
Makefile
View file

@ -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
## <CONFIG>_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))
## <TARGET>_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)

View file

@ -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 \

View file

@ -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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

40
src/config/AIRF7/config.h Normal file
View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

37
src/config/ELLE0/config.h Normal file
View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

40
src/config/F4BY/config.h Normal file
View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
/*
This file has been auto 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

Some files were not shown because too many files have changed in this diff Show more