From 06c5bb40b58d79cf59ebe4cf0064d981f6f8dac0 Mon Sep 17 00:00:00 2001 From: blckmn Date: Tue, 25 Oct 2022 14:28:13 +1100 Subject: [PATCH] Final target cleanup --- Makefile | 46 +-- make/targets.mk | 18 +- make/targets_list.mk | 188 ----------- src/main/target/EMAXF4SX1280/target.c | 43 --- src/main/target/EMAXF4SX1280/target.h | 128 -------- src/main/target/EMAXF4SX1280/target.mk | 15 - src/main/target/KISSFCV2F7/README.md | 11 - src/main/target/KISSFCV2F7/config.c | 41 --- .../KISSFCV2F7/stm32_flash_f722_kissfcv2f7.ld | 55 ---- src/main/target/KISSFCV2F7/target.c | 45 --- src/main/target/KISSFCV2F7/target.h | 118 ------- src/main/target/KISSFCV2F7/target.mk | 6 - src/main/target/MICROSCISKY/target.h | 90 ------ src/main/target/MOTOLABF4/MLTEMPF4.mk | 0 src/main/target/MOTOLABF4/MLTYPHF4.mk | 0 src/main/target/MOTOLABF4/MOTOLABF4.nomk | 0 src/main/target/MOTOLABF4/config.c | 36 --- src/main/target/MOTOLABF4/target.c | 38 --- src/main/target/MOTOLABF4/target.h | 148 --------- src/main/target/MOTOLABF4/target.mk | 12 - src/main/target/NUCLEOF446RE/config.c | 38 --- src/main/target/NUCLEOF446RE/target.c | 39 --- src/main/target/NUCLEOF446RE/target.h | 164 ---------- src/main/target/NUCLEOF446RE/target.mk | 16 - src/main/target/NUCLEOF7/target.c | 66 ---- src/main/target/NUCLEOF7/target.h | 166 ---------- src/main/target/NUCLEOF7/target.mk | 13 - src/main/target/NUCLEOH723ZG/config.c | 43 --- src/main/target/NUCLEOH723ZG/target.c | 54 ---- src/main/target/NUCLEOH723ZG/target.h | 283 ----------------- src/main/target/NUCLEOH723ZG/target.mk | 32 -- src/main/target/NUCLEOH725ZG/config.c | 43 --- src/main/target/NUCLEOH725ZG/target.c | 54 ---- src/main/target/NUCLEOH725ZG/target.h | 292 ----------------- src/main/target/NUCLEOH725ZG/target.mk | 32 -- .../target/NUCLEOH743/NUCLEOH743_RAMBASED.mk | 0 src/main/target/NUCLEOH743/config.c | 46 --- src/main/target/NUCLEOH743/target.c | 61 ---- src/main/target/NUCLEOH743/target.h | 297 ------------------ src/main/target/NUCLEOH743/target.mk | 35 --- src/main/target/NUCLEOH7A3ZI/config.c | 43 --- src/main/target/NUCLEOH7A3ZI/target.c | 54 ---- src/main/target/NUCLEOH7A3ZI/target.h | 285 ----------------- src/main/target/NUCLEOH7A3ZI/target.mk | 35 --- src/main/target/SPARKY2/target.c | 42 --- src/main/target/SPARKY2/target.h | 127 -------- src/main/target/SPARKY2/target.mk | 9 - src/main/target/SPEKTRUMF400/target.c | 46 --- src/main/target/SPEKTRUMF400/target.h | 125 -------- src/main/target/SPEKTRUMF400/target.mk | 11 - src/main/target/SPRACINGH7EXTREME/config.c | 51 --- src/main/target/SPRACINGH7EXTREME/target.c | 58 ---- src/main/target/SPRACINGH7EXTREME/target.h | 243 -------------- src/main/target/SPRACINGH7EXTREME/target.mk | 22 -- src/main/target/SPRACINGH7NANO/config.c | 44 --- src/main/target/SPRACINGH7NANO/target.c | 60 ---- src/main/target/SPRACINGH7NANO/target.h | 234 -------------- src/main/target/SPRACINGH7NANO/target.mk | 23 -- src/main/target/SPRACINGH7ZERO/config.c | 51 --- src/main/target/SPRACINGH7ZERO/target.c | 59 ---- src/main/target/SPRACINGH7ZERO/target.h | 236 -------------- src/main/target/SPRACINGH7ZERO/target.mk | 26 -- src/main/target/UAVPNG030MINI/target.c | 39 --- src/main/target/UAVPNG030MINI/target.h | 134 -------- src/main/target/UAVPNG030MINI/target.mk | 6 - src/test/Makefile | 22 +- 66 files changed, 10 insertions(+), 4887 deletions(-) delete mode 100644 make/targets_list.mk delete mode 100644 src/main/target/EMAXF4SX1280/target.c delete mode 100644 src/main/target/EMAXF4SX1280/target.h delete mode 100644 src/main/target/EMAXF4SX1280/target.mk delete mode 100644 src/main/target/KISSFCV2F7/README.md delete mode 100644 src/main/target/KISSFCV2F7/config.c delete mode 100644 src/main/target/KISSFCV2F7/stm32_flash_f722_kissfcv2f7.ld delete mode 100644 src/main/target/KISSFCV2F7/target.c delete mode 100644 src/main/target/KISSFCV2F7/target.h delete mode 100644 src/main/target/KISSFCV2F7/target.mk delete mode 100644 src/main/target/MICROSCISKY/target.h delete mode 100644 src/main/target/MOTOLABF4/MLTEMPF4.mk delete mode 100644 src/main/target/MOTOLABF4/MLTYPHF4.mk delete mode 100644 src/main/target/MOTOLABF4/MOTOLABF4.nomk delete mode 100644 src/main/target/MOTOLABF4/config.c delete mode 100644 src/main/target/MOTOLABF4/target.c delete mode 100644 src/main/target/MOTOLABF4/target.h delete mode 100644 src/main/target/MOTOLABF4/target.mk delete mode 100644 src/main/target/NUCLEOF446RE/config.c delete mode 100644 src/main/target/NUCLEOF446RE/target.c delete mode 100644 src/main/target/NUCLEOF446RE/target.h delete mode 100644 src/main/target/NUCLEOF446RE/target.mk delete mode 100644 src/main/target/NUCLEOF7/target.c delete mode 100644 src/main/target/NUCLEOF7/target.h delete mode 100644 src/main/target/NUCLEOF7/target.mk delete mode 100644 src/main/target/NUCLEOH723ZG/config.c delete mode 100644 src/main/target/NUCLEOH723ZG/target.c delete mode 100644 src/main/target/NUCLEOH723ZG/target.h delete mode 100644 src/main/target/NUCLEOH723ZG/target.mk delete mode 100644 src/main/target/NUCLEOH725ZG/config.c delete mode 100644 src/main/target/NUCLEOH725ZG/target.c delete mode 100644 src/main/target/NUCLEOH725ZG/target.h delete mode 100644 src/main/target/NUCLEOH725ZG/target.mk delete mode 100644 src/main/target/NUCLEOH743/NUCLEOH743_RAMBASED.mk delete mode 100644 src/main/target/NUCLEOH743/config.c delete mode 100644 src/main/target/NUCLEOH743/target.c delete mode 100644 src/main/target/NUCLEOH743/target.h delete mode 100644 src/main/target/NUCLEOH743/target.mk delete mode 100644 src/main/target/NUCLEOH7A3ZI/config.c delete mode 100644 src/main/target/NUCLEOH7A3ZI/target.c delete mode 100644 src/main/target/NUCLEOH7A3ZI/target.h delete mode 100644 src/main/target/NUCLEOH7A3ZI/target.mk delete mode 100644 src/main/target/SPARKY2/target.c delete mode 100644 src/main/target/SPARKY2/target.h delete mode 100644 src/main/target/SPARKY2/target.mk delete mode 100644 src/main/target/SPEKTRUMF400/target.c delete mode 100644 src/main/target/SPEKTRUMF400/target.h delete mode 100644 src/main/target/SPEKTRUMF400/target.mk delete mode 100644 src/main/target/SPRACINGH7EXTREME/config.c delete mode 100644 src/main/target/SPRACINGH7EXTREME/target.c delete mode 100644 src/main/target/SPRACINGH7EXTREME/target.h delete mode 100644 src/main/target/SPRACINGH7EXTREME/target.mk delete mode 100644 src/main/target/SPRACINGH7NANO/config.c delete mode 100644 src/main/target/SPRACINGH7NANO/target.c delete mode 100644 src/main/target/SPRACINGH7NANO/target.h delete mode 100644 src/main/target/SPRACINGH7NANO/target.mk delete mode 100644 src/main/target/SPRACINGH7ZERO/config.c delete mode 100644 src/main/target/SPRACINGH7ZERO/target.c delete mode 100644 src/main/target/SPRACINGH7ZERO/target.h delete mode 100644 src/main/target/SPRACINGH7ZERO/target.mk delete mode 100644 src/main/target/UAVPNG030MINI/target.c delete mode 100644 src/main/target/UAVPNG030MINI/target.h delete mode 100644 src/main/target/UAVPNG030MINI/target.mk diff --git a/Makefile b/Makefile index 2c2cca5857..7b2dced8f9 100644 --- a/Makefile +++ b/Makefile @@ -100,14 +100,6 @@ FEATURES = FEATURE_CUT_LEVEL_SUPPLIED := $(FEATURE_CUT_LEVEL) FEATURE_CUT_LEVEL = -# The list of targets to build for 'pre-push' -ifeq ($(OSFAMILY), macosx) -# SITL is not buildable on MacOS -PRE_PUSH_TARGET_LIST ?= $(UNIFIED_TARGETS) STM32F4DISCOVERY_DEBUG test-representative -else -PRE_PUSH_TARGET_LIST ?= $(UNIFIED_TARGETS) SITL STM32F4DISCOVERY_DEBUG test-representative -endif - include $(ROOT)/make/targets.mk REVISION := norevision @@ -181,7 +173,7 @@ else ifneq ($(FEATURE_CUT_LEVEL),) DEVICE_FLAGS := $(DEVICE_FLAGS) -DFEATURE_CUT_LEVEL=$(FEATURE_CUT_LEVEL) endif -TARGET_DIR = $(ROOT)/src/main/target/$(BASE_TARGET) +TARGET_DIR = $(ROOT)/src/main/target/$(TARGET) TARGET_DIR_SRC = $(notdir $(wildcard $(TARGET_DIR)/*.c)) .DEFAULT_GOAL := hex @@ -450,31 +442,6 @@ all: $(CI_TARGETS) ## all_all : Build all targets (including legacy / unsupported) all_all: $(VALID_TARGETS) -## unified : build all Unified Targets -unified: $(UNIFIED_TARGETS) - -## unified_zip : build all Unified Targets as zip files (for posting on GitHub) -unified_zip: $(addsuffix _clean,$(UNIFIED_TARGETS)) $(addsuffix _zip,$(UNIFIED_TARGETS)) - -## legacy : Build legacy targets -legacy: $(LEGACY_TARGETS) - -## unsupported : Build unsupported targets -unsupported: $(UNSUPPORTED_TARGETS) - -## pre-push : The minimum verification that should be run before pushing, to check if CI has a chance of succeeding -pre-push: - $(MAKE) $(addsuffix _clean,$(PRE_PUSH_TARGET_LIST)) $(PRE_PUSH_TARGET_LIST) EXTRA_FLAGS=-Werror - -## targets-group-1 : build some targets -targets-group-1: $(GROUP_1_TARGETS) - -## targets-group-2 : build some targets -targets-group-2: $(GROUP_2_TARGETS) - -## targets-group-rest: build the rest of the targets (not listed in the other groups) -targets-group-rest: $(GROUP_OTHER_TARGETS) - $(VALID_TARGETS): $(V0) @echo "Building $@" && \ $(MAKE) hex TARGET=$@ && \ @@ -613,18 +580,7 @@ help: Makefile make/tools.mk targets: @echo "Valid targets: $(VALID_TARGETS)" @echo "Built targets: $(CI_TARGETS)" - @echo "Unified targets: $(UNIFIED_TARGETS)" - @echo "Legacy targets: $(LEGACY_TARGETS)" - @echo "Unsupported targets: $(UNSUPPORTED_TARGETS)" @echo "Default target: $(TARGET)" - @echo "targets-group-1: $(GROUP_1_TARGETS)" - @echo "targets-group-2: $(GROUP_2_TARGETS)" - @echo "targets-group-rest: $(GROUP_OTHER_TARGETS)" - - @echo "targets-group-1: $(words $(GROUP_1_TARGETS)) targets" - @echo "targets-group-2: $(words $(GROUP_2_TARGETS)) targets" - @echo "targets-group-rest: $(words $(GROUP_OTHER_TARGETS)) targets" - @echo "total in all groups $(words $(CI_TARGETS)) targets" targets-ci-print: @echo $(CI_TARGETS) diff --git a/make/targets.mk b/make/targets.mk index 12adfda97d..72319c271d 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -1,16 +1,10 @@ -include $(ROOT)/make/targets_list.mk +BASE_TARGETS = $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))))) +VALID_TARGETS = $(sort $(BASE_TARGETS)) -ifeq ($(filter $(TARGET),$(NOBUILD_TARGETS)), $(TARGET)) -ALTERNATES := $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/$(TARGET)/*.mk))))) -$(error The target specified, $(TARGET), cannot be built. Use one of the ALT targets: $(ALTERNATES)) -endif - -BASE_TARGET := $(call get_base_target,$(TARGET)) -# silently ignore if the file is not present. Allows for target specific. --include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk +CI_TARGETS := $(VALID_TARGETS) # silently ignore if the file is not present. Allows for target defaults. --include $(ROOT)/src/main/target/$(BASE_TARGET)/target.mk +-include $(ROOT)/src/main/target/$(TARGET)/target.mk F4_TARGETS := $(F405_TARGETS) $(F411_TARGETS) $(F446_TARGETS) F7_TARGETS := $(F7X2RE_TARGETS) $(F7X5XE_TARGETS) $(F7X5XG_TARGETS) $(F7X5XI_TARGETS) $(F7X6XG_TARGETS) @@ -45,8 +39,4 @@ else $(error Unknown target MCU specified.) endif -ifneq ($(BASE_TARGET), $(TARGET)) -TARGET_FLAGS := $(TARGET_FLAGS) -D$(BASE_TARGET) -endif - TARGET_FLAGS := $(TARGET_FLAGS) -D$(TARGET_MCU) diff --git a/make/targets_list.mk b/make/targets_list.mk deleted file mode 100644 index 88a4a16ba1..0000000000 --- a/make/targets_list.mk +++ /dev/null @@ -1,188 +0,0 @@ -ALT_TARGET_PATHS = $(filter-out %/target,$(basename $(wildcard $(ROOT)/src/main/target/*/*.mk))) -ALT_TARGET_NAMES = $(notdir $(ALT_TARGET_PATHS)) -BASE_TARGET_NAMES = $(notdir $(patsubst %/,%,$(dir $(ALT_TARGET_PATHS)))) -BASE_ALT_PAIRS = $(join $(BASE_TARGET_NAMES:=/),$(ALT_TARGET_NAMES)) - -ALT_TARGETS = $(sort $(notdir $(BASE_ALT_PAIRS))) -BASE_TARGETS = $(sort $(notdir $(patsubst %/,%,$(dir $(wildcard $(ROOT)/src/main/target/*/target.mk))))) -NOBUILD_TARGETS = $(sort $(filter-out target,$(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.nomk))))) -VALID_TARGETS = $(sort $(filter-out $(NOBUILD_TARGETS),$(BASE_TARGETS) $(ALT_TARGETS))) - -# For alt targets, returns their base target name. -# For base targets, returns the (same) target name. -# param $1 = target name -find_target_pair = $(filter %/$(1),$(BASE_ALT_PAIRS)) -get_base_target = $(if $(call find_target_pair,$(1)),$(patsubst %/,%,$(dir $(call find_target_pair,$(1)))),$(1)) - -UNSUPPORTED_TARGETS := \ - AFROMINI \ - BEEBRAIN \ - CJMCU \ - MICROSCISKY \ - AIR32 \ - BEEBRAIN_V2D \ - BEEBRAIN_V2F \ - BEESTORM \ - COLIBRI_RACE \ - FF_ACROWHOOPSP \ - FF_KOMBINI \ - FF_PIKOBLX \ - FF_RADIANCE \ - KISSCC \ - KISSFC \ - LUXV2_RACE \ - LUX_RACE \ - MOTOLAB \ - MULTIFLITEPICO \ - OMNIBUS \ - RACEBASE \ - RMDO \ - SINGULARITY \ - SIRINFPV \ - SPARKY \ - TINYFISH \ - X_RACERSPI - -UNIFIED_TARGETS := STM32F405 \ - STM32F411 \ - STM32F7X2 \ - STM32F745 \ - STM32G47X \ - STM32H743 \ - STM32F411SX1280 - -# Legacy targets are targets that have been replaced by Unified Target configurations -LEGACY_TARGETS := MATEKF405 \ - AIKONF4 \ - ALIENFLIGHTF4 \ - BEEROTORF4 \ - CLRACINGF4 \ - CRAZYBEEF4FR \ - DYSF4PRO \ - ELINF405 \ - FF_RACEPIT \ - FLYWOOF405 \ - FLYWOOF411 \ - FURYF4OSD \ - HAKRCF411 \ - KAKUTEF4V2 \ - MAMBAF411 \ - MATEKF411 \ - MATEKF411RX \ - MERAKRCF405 \ - MLTEMPF4 \ - MLTYPHF4 \ - OMNIBUSF4 \ - OMNIBUSF4FW \ - OMNIBUSF4NANOV7 \ - OMNIBUSF4SD \ - OMNIBUSF4V6 \ - SPEEDYBEEF4 \ - SYNERGYF4 \ - TMOTORF4 \ - TRANSTECF411 \ - VGOODRCF4 \ - XILOF4 \ - AIRBOTF7 \ - AIRF7 \ - ALIENFLIGHTNGF7 \ - CLRACINGF7 \ - ELINF722 \ - EXF722DUAL \ - FLYWOOF7DUAL \ - FOXEERF722DUAL \ - FPVM_BETAFLIGHTF7 \ - JHEF7DUAL \ - KAKUTEF7 \ - KAKUTEF7MINI \ - LUXMINIF7 \ - MAMBAF722 \ - MATEKF722 \ - MATEKF722SE \ - MERAKRCF722 \ - NERO \ - OMNIBUSF7NANOV7 \ - OMNIBUSF7V2 \ - RUSHCORE7 \ - SPEEDYBEEF7 \ - SPRACINGF7DUAL \ - TMOTORF7 \ - TRANSTECF7 \ - AIRBOTF4 \ - AIRBOTF4SD \ - BLUEJAYF4 \ - CRAZYBEEF4DX \ - CRAZYBEEF4FS \ - DALRCF405 \ - FOXEERF405 \ - HAKRCF405 \ - KAKUTEF4 \ - NOX \ - OMNINXT4 \ - REVO \ - DALRCF722DUAL \ - OMNINXT7 \ - BETAFLIGHTF4 \ - EXUAVF4PRO \ - FRSKYF4 \ - KIWIF4 \ - KIWIF4V2 \ - PLUMF4 \ - SKYZONEF405 \ - XRACERF4 \ - AG3XF7 \ - YUPIF7 \ - PYRODRONEF4 \ - AG3XF4 \ - COLIBRI \ - ELLE0 \ - F4BY \ - FF_FORTINIF4 \ - FF_FORTINIF4_REV03 \ - FF_PIKOF4 \ - FF_PIKOF4OSD \ - FURYF4 \ - LUXF4OSD \ - REVOLT \ - REVOLTOSD \ - REVONANO \ - SOULF4 \ - SPARKY2 \ - SPRACINGF4EVO \ - SPRACINGF4NEO \ - STM32F411DISCOVERY \ - UAVPNG030MINI \ - WORMFC \ - YUPIF4 \ - ANYFCF7 \ - ANYFCM7 \ - HAKRCF722 \ - KAKUTEF7V2 \ - NUCLEOF722 \ - OMNIBUSF7 \ - ALIENWHOOPF4 \ - FISHDRONEF4 \ - PIRXF4 \ - PODIUMF4 \ - STACKX \ - VRRACE \ - KROOZX - -# Temporarily excluded to get CI coverage for USE_SPI_TRANSACTION -# STM32F4DISCOVERY \ - -CI_TARGETS := $(UNIFIED_TARGETS) SITL - -TARGETS_TOTAL := $(words $(CI_TARGETS)) -TARGET_GROUPS := 3 -TARGETS_PER_GROUP := $(shell expr $(TARGETS_TOTAL) / $(TARGET_GROUPS) ) - -ST := 1 -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_1_TARGETS := $(wordlist $(ST), $(ET), $(CI_TARGETS)) - -ST := $(shell expr $(ET) + 1) -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_2_TARGETS := $(wordlist $(ST), $(ET), $(CI_TARGETS)) - -GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS), $(CI_TARGETS)) diff --git a/src/main/target/EMAXF4SX1280/target.c b/src/main/target/EMAXF4SX1280/target.c deleted file mode 100644 index eea19600ae..0000000000 --- a/src/main/target/EMAXF4SX1280/target.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" - -#include "drivers/dma.h" -#include "drivers/io.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM9, CH2, PA3, TIM_USE_PPM, 0, 0), // PPM/RX2 - - DEF_TIM(TIM2, CH3, PB10, TIM_USE_MOTOR, 0, 0), // S1_OUT - DMA1_ST1 - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), // S2_OUT - DMA1_ST0 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), // S3_OUT - DMA1_ST3 - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // S4_OUT - DMA1_ST7 - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_LED, 0, 0), // 2812LED - DMA1_ST2 - - DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM, 0, 0 ), // TX2 - DEF_TIM(TIM1, CH2, PA9, TIM_USE_PWM, 0, 0 ), // TX1 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_PWM, 0, 0 ), // RX1 -}; diff --git a/src/main/target/EMAXF4SX1280/target.h b/src/main/target/EMAXF4SX1280/target.h deleted file mode 100644 index be895c9d37..0000000000 --- a/src/main/target/EMAXF4SX1280/target.h +++ /dev/null @@ -1,128 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "EMAX" -#define USBD_PRODUCT_STRING "EMAXF4SX1280" - - -#define LED0_PIN PC13 - -#define USE_BEEPER -#define BEEPER_PIN PC15 -#define BEEPER_INVERTED - -#define ENABLE_DSHOT_DMAR DSHOT_DMAR_AUTO -#define DSHOT_BITBANG_DEFAULT DSHOT_BITBANG_OFF - -// *************** SPI1 Gyro & ACC ********************** -#define USE_SPI -#define USE_SPI_DEVICE_1 - -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define GYRO_1_CS_PIN PA4 -#define GYRO_1_SPI_INSTANCE SPI1 - -#define GYRO_1_EXTI_PIN PA1 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 -#define USE_GYRO_SPI_ICM20689 -#define GYRO_1_ALIGN CW180_DEG - -#define USE_ACC -#define USE_ACC_SPI_MPU6000 -#define USE_ACC_SPI_ICM20689 -#define USE_ACCGYRO_BMI270 - -// *************** SPI2 OSD ***************************** -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI2 -#define MAX7456_SPI_CS_PIN PB12 - -// *************** SPI3 RX *************************** -#define USE_SPI_DEVICE_3 -#define RX_SPI_INSTANCE SPI3 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PB5 -#define RX_NSS_PIN PA15 - -#define USE_RX_SPI -#define USE_RX_EXPRESSLRS -#define USE_RX_SX1280 - -#define RX_SPI_LED_INVERTED -#define RX_SPI_BIND_PIN PB2 -#define RX_SPI_EXTI_PIN PC14 -#define RX_SPI_LED_PIN PB9 -#define RX_EXPRESSLRS_SPI_RESET_PIN PA8 -#define RX_EXPRESSLRS_SPI_BUSY_PIN PA13 -#define RX_EXPRESSLRS_TIMER_INSTANCE TIM3 - -#define DEFAULT_RX_FEATURE FEATURE_RX_SPI -#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_EXPRESSLRS - -// *************** UART ***************************** -#define USE_VCP - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_SOFTSERIAL1 - -#define SERIAL_PORT_COUNT 4 - -// *************** ADC ***************************** -#define USE_ADC -#define ADC_INSTANCE ADC1 // Default added -#define ADC1_DMA_OPT 0 // DMA 2 Stream 0 Channel 0 - -#define VBAT_ADC_PIN PB0 -#define CURRENT_METER_ADC_PIN PB1 - -#define USE_ESCSERIAL - -#define DEFAULT_FEATURES (FEATURE_OSD | FEATURE_TELEMETRY ) -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC -#define CURRENT_METER_SCALE_DEFAULT 179 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) - -#define USABLE_TIMER_CHANNEL_COUNT 9 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(5) | TIM_N(9) ) diff --git a/src/main/target/EMAXF4SX1280/target.mk b/src/main/target/EMAXF4SX1280/target.mk deleted file mode 100644 index 3842619f38..0000000000 --- a/src/main/target/EMAXF4SX1280/target.mk +++ /dev/null @@ -1,15 +0,0 @@ -F411_TARGETS += $(TARGET) - -FEATURES += VCP SDCARD_SPI - -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_icm20689.c \ - $(ROOT)/lib/main/BoschSensortec/BMI270-Sensor-API/bmi270_maximum_fifo.c \ - drivers/accgyro/accgyro_spi_bmi270.c \ - drivers/max7456.c \ - drivers/rx/expresslrs_driver.c \ - drivers/rx/rx_sx1280.c \ - rx/expresslrs_telemetry.c \ - rx/expresslrs_common.c \ - rx/expresslrs.c diff --git a/src/main/target/KISSFCV2F7/README.md b/src/main/target/KISSFCV2F7/README.md deleted file mode 100644 index 63f1dcf3a0..0000000000 --- a/src/main/target/KISSFCV2F7/README.md +++ /dev/null @@ -1,11 +0,0 @@ -# KISSFCV2 - - -* available: https://flyduino.net - -## HW info - -* STM32F722RET6 -* MPU6000 SPI -* All 5 uarts available -* 6 pwm outputs diff --git a/src/main/target/KISSFCV2F7/config.c b/src/main/target/KISSFCV2F7/config.c deleted file mode 100644 index 839c8f1333..0000000000 --- a/src/main/target/KISSFCV2F7/config.c +++ /dev/null @@ -1,41 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#include "drivers/serial.h" -#include "pg/rx.h" -#include "rx/rx.h" - -#include "telemetry/telemetry.h" - -#include "config/config.h" - - -#ifdef USE_TARGET_CONFIG -void targetConfiguration(void) -{ - rxConfigMutable()->halfDuplex = true; - serialConfigMutable()->portConfigs[findSerialPortIndexByIdentifier(SERIAL_PORT_UART4)].functionMask = FUNCTION_MSP; -} -#endif diff --git a/src/main/target/KISSFCV2F7/stm32_flash_f722_kissfcv2f7.ld b/src/main/target/KISSFCV2F7/stm32_flash_f722_kissfcv2f7.ld deleted file mode 100644 index 8dfae7cbe2..0000000000 --- a/src/main/target/KISSFCV2F7/stm32_flash_f722_kissfcv2f7.ld +++ /dev/null @@ -1,55 +0,0 @@ -/* -***************************************************************************** -** -** File : stm32_flash_f722.ld -** -** Abstract : Linker script for STM32F722RETx Device with -** 512KByte FLASH, 256KByte RAM -** -***************************************************************************** -*/ - -/* Entry Point */ -ENTRY(Reset_Handler) - -/* -0x08000000 to 0x0807FFFF 512K full flash -0x08000000 to 0x08003FFF 16K KISS bootloader -0x08004000 to 0x08007FFF 16K config -0x08008000 to 0x0807FFFF 480K ISR vector, firmware -*/ - -/* Specify the memory areas */ -MEMORY -{ - ITCM_RAM (rx) : ORIGIN = 0x00000000, LENGTH = 16K - - /* config occupies the entire flash sector 1 for the ease of erasure, 16K on F72x */ - ITCM_FLASH_CONFIG (r) : ORIGIN = 0x00204000, LENGTH = 16K - ITCM_FLASH (rx) : ORIGIN = 0x00208000, LENGTH = 480K - - AXIM_FLASH_CUSTOM_DEFAULTS (r) : ORIGIN = 0x08002800, LENGTH = 6K - AXIM_FLASH_CONFIG (r) : ORIGIN = 0x08004000, LENGTH = 16K - AXIM_FLASH (rx) : ORIGIN = 0x08008000, LENGTH = 480K - - DTCM_RAM (rwx) : ORIGIN = 0x20000000, LENGTH = 64K - SRAM1 (rwx) : ORIGIN = 0x20010000, LENGTH = 176K - SRAM2 (rwx) : ORIGIN = 0x2003C000, LENGTH = 16K - MEMORY_B1 (rx) : ORIGIN = 0x60000000, LENGTH = 0K -} - -REGION_ALIAS("FLASH", AXIM_FLASH) -REGION_ALIAS("WRITABLE_FLASH", AXIM_FLASH) -REGION_ALIAS("FLASH_CONFIG", AXIM_FLASH_CONFIG) -REGION_ALIAS("FLASH1", AXIM_FLASH) -REGION_ALIAS("FLASH_CUSTOM_DEFAULTS", AXIM_FLASH_CUSTOM_DEFAULTS) -REGION_ALIAS("WRITABLE_FLASH1", AXIM_FLASH) - -REGION_ALIAS("STACKRAM", DTCM_RAM) -REGION_ALIAS("FASTRAM", DTCM_RAM) -REGION_ALIAS("RAM", SRAM1) - -/* Put various bits and bobs of data into the free space after the vector table in sector 0 to save flash space. */ -REGION_ALIAS("MOVABLE_FLASH", AXIM_FLASH) - -INCLUDE "stm32_flash_f7_split.ld" diff --git a/src/main/target/KISSFCV2F7/target.c b/src/main/target/KISSFCV2F7/target.c deleted file mode 100644 index 82ca175d4e..0000000000 --- a/src/main/target/KISSFCV2F7/target.c +++ /dev/null @@ -1,45 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - - DEF_TIM(TIM9, CH1, PA2, TIM_USE_PWM | TIM_USE_PPM, 0, 0), - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 0), - - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 0), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), - - DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 0) - -}; - diff --git a/src/main/target/KISSFCV2F7/target.h b/src/main/target/KISSFCV2F7/target.h deleted file mode 100644 index 3c375b546c..0000000000 --- a/src/main/target/KISSFCV2F7/target.h +++ /dev/null @@ -1,118 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define USE_TARGET_CONFIG - -#define TARGET_BOARD_IDENTIFIER "KISSV2" - -#define USBD_PRODUCT_STRING "KISSFCV2F7" - -#undef USE_CUSTOM_DEFAULTS_ADDRESS - -#define LED0_PIN PA8 // blue -#define LED1_PIN PC8 // blingbling -#define LED1_INVERTED - -#define USE_BEEPER -#define BEEPER_PIN PC9 -#define BEEPER_INVERTED - -#define GYRO_1_CS_PIN PB12 -#define GYRO_1_SPI_INSTANCE SPI2 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 -#define GYRO_1_ALIGN CW90_DEG - -#define USE_ACC -#define USE_ACC_SPI_MPU6000 - - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_NSS_PIN PA4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define USE_SPI_DEVICE_2 -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN PA3 -#define UART2_TX_PIN PA2 - -#define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -//#define USE_UART6 -//#define UART6_RX_PIN PC7 -//#define UART6_TX_PIN PC6 - -#define USE_SOFTSERIAL1 -#define SOFTSERIAL1_TX_PIN PB4 -#define SOFTSERIAL1_RX_PIN NONE //PB5 - -#define SERIAL_PORT_COUNT 6 - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART2 - -#define AVOID_UART2_FOR_PWM_PPM - -#define SPEKTRUM_BIND_PIN UART2_RX_PIN - -#define USE_ADC -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define VBAT_SCALE_DEFAULT 160 -#define VBAT_ADC_PIN PB1 - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) - -#define USABLE_TIMER_CHANNEL_COUNT 8 - -#define USED_TIMERS ( TIM_N(2) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/KISSFCV2F7/target.mk b/src/main/target/KISSFCV2F7/target.mk deleted file mode 100644 index a8c2d13174..0000000000 --- a/src/main/target/KISSFCV2F7/target.mk +++ /dev/null @@ -1,6 +0,0 @@ -F7X2RE_TARGETS += $(TARGET) -LD_SCRIPT = $(ROOT)/src/main/target/$(TARGET)/stm32_flash_f722_kissfcv2f7.ld -CFLAGS += -DCLOCK_SOURCE_USE_HSI - -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu6000.c diff --git a/src/main/target/MICROSCISKY/target.h b/src/main/target/MICROSCISKY/target.h deleted file mode 100644 index 52593ec2b4..0000000000 --- a/src/main/target/MICROSCISKY/target.h +++ /dev/null @@ -1,90 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "MSKY" // Micro sciSKY - -#define LED0_PIN PB3 -#define LED1_PIN PB4 - -#define USE_BEEPER -#define BEEPER_PIN PA12 - -#define BARO_XCLR_PIN PC13 -#define BARO_EOC_PIN PC14 - -#define INVERTER_PIN_UART2 PB2 // PB2 (BOOT1) abused as inverter select GPIO - -#define MAG_INT_EXTI PC14 -#define USE_MAG_DATA_READY_SIGNAL - -// SPI2 -// PB15 28 SPI2_MOSI -// PB14 27 SPI2_MISO -// PB13 26 SPI2_SCK -// PB12 25 SPI2_NSS - -#define USE_SPI -#define USE_SPI_DEVICE_2 - -#define USE_GYRO -#define USE_GYRO_MPU6050 -#define GYRO_1_ALIGN CW0_DEG - -#define USE_ACC -#define USE_ACC_MPU6050 - -#define USE_BARO -#define USE_BARO_MS5611 -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define MAG_HMC5883_ALIGN CW180_DEG - -#define USE_UART1 -#define USE_UART2 -#define SERIAL_PORT_COUNT 2 - -#define USE_I2C -#define USE_I2C_DEVICE_2 -#define I2C_DEVICE (I2CDEV_2) - -#define BRUSHED_MOTORS -#define DEFAULT_FEATURES FEATURE_MOTOR_STOP -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SPEKTRUM1024 -#define SERIALRX_UART SERIAL_PORT_USART2 -#define RX_CHANNELS_TAER - -#undef USE_SERVOS -#define USE_QUAD_MIXER_ONLY - - -// IO - assuming all IOs on 48pin package -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC ( BIT(13) | BIT(14) | BIT(15) ) - -#define USABLE_TIMER_CHANNEL_COUNT 14 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/MOTOLABF4/MLTEMPF4.mk b/src/main/target/MOTOLABF4/MLTEMPF4.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/MOTOLABF4/MLTYPHF4.mk b/src/main/target/MOTOLABF4/MLTYPHF4.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/MOTOLABF4/MOTOLABF4.nomk b/src/main/target/MOTOLABF4/MOTOLABF4.nomk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/MOTOLABF4/config.c b/src/main/target/MOTOLABF4/config.c deleted file mode 100644 index 340743ea94..0000000000 --- a/src/main/target/MOTOLABF4/config.c +++ /dev/null @@ -1,36 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "pg/sdcard.h" - -#include "telemetry/telemetry.h" - -void targetConfiguration(void) -{ - telemetryConfigMutable()->halfDuplex = 0; -} -#endif diff --git a/src/main/target/MOTOLABF4/target.c b/src/main/target/MOTOLABF4/target.c deleted file mode 100644 index 4364dc658c..0000000000 --- a/src/main/target/MOTOLABF4/target.c +++ /dev/null @@ -1,38 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" -#include "drivers/dma.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0 ), // PWM1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // PWM2 - DEF_TIM(TIM2, CH2, PB3, TIM_USE_MOTOR, 0, 0 ), // PWM3 - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // PWM4 - DEF_TIM(TIM5, CH3, PA2, TIM_USE_NONE, 0, 0 ), // PWM5, UART 2 TX - DEF_TIM(TIM5, CH4, PA3, TIM_USE_NONE, 0, 0 ), // PWM6, UART 2 RX - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 0 ), // Serial LED - DEF_TIM(TIM4, CH3, PB8, TIM_USE_NONE, 0, 0 ), // ESC serial (unwired) -}; diff --git a/src/main/target/MOTOLABF4/target.h b/src/main/target/MOTOLABF4/target.h deleted file mode 100644 index 522d73362c..0000000000 --- a/src/main/target/MOTOLABF4/target.h +++ /dev/null @@ -1,148 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define USE_TARGET_CONFIG -#undef USE_MSP_DISPLAYPORT - -#ifdef MLTEMPF4 -#define TARGET_BOARD_IDENTIFIER "MLTE" -#else -#define TARGET_BOARD_IDENTIFIER "MLTY" -#endif - -#define USBD_PRODUCT_STRING "MotoLabF4" - -#define LED0_PIN PC3 -//#define LED1 PC4 - -#define USE_BEEPER -#define BEEPER_PIN PB4 -#define BEEPER_INVERTED - -#define GYRO_1_CS_PIN PA4 -#define GYRO_1_SPI_INSTANCE SPI1 - -#define USE_ACC -#define USE_ACC_SPI_MPU6000 -#define GYRO_1_ALIGN CW180_DEG - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 - -// MPU6000 interrupts -#define GYRO_1_EXTI_PIN PC5 -//#define ENSURE_MPU_DATA_READY_IS_LOW -//#define EXTI_CALLBACK_HANDLER_COUNT 1 // MPU data ready - -#define USE_SPI_DEVICE_3 // MAX7456 on V1.2 -#define SPI3_NSS_PIN PA15 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PC12 - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI3 -#define MAX7456_SPI_CS_PIN SPI3_NSS_PIN - -#define USE_VCP -//#define USB_DETECT_PIN PC15 -//#define USE_USB_DETECT - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN PA3 -#define UART2_TX_PIN PA2 - -// Pins are available, not connected -//#define USE_UART3 -//#define UART3_RX_PIN PB11 -//#define UART3_TX_PIN PB10 - -#define USE_UART4 -#define UART4_RX_PIN PA1 -#define UART4_TX_PIN PA0 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 // not connected - -#ifdef MLTEMPF4 -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 -#define SERIAL_PORT_COUNT 6 //VCP, USART1, USART2, UART4, UART5, USART6 -#else -#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, UART4, UART5 -#define USE_VTX_RTC6705 -#define USE_VTX_RTC6705_SOFTSPI -#define RTC6705_SPI_MOSI_PIN PC6 -#define RTC6705_SPICLK_PIN PC2 -#define RTC6705_CS_PIN PC7 -#endif - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PB8 - -#define USE_SPI -#define USE_SPI_DEVICE_1 // MPU6000 -#define USE_SPI_DEVICE_2 // SDcard - -#define USE_SDCARD -#define USE_SDCARD_SPI -#define SDCARD_DETECT_INVERTED -#define SDCARD_DETECT_PIN PC13 -#define SDCARD_SPI_INSTANCE SPI2 -#define SDCARD_SPI_CS_PIN PB12 -#define SDCARD_SPI_CS_CFG IOCFG_OUT_OD -#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel 0 - -// Pins are available unless USART3 is connected, not connected -//#define USE_I2C -//#define I2C_DEVICE (I2CDEV_2) - -#define USE_ADC -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -// Reserved pins, not connected -//#define RSSI_ADC_PIN PC2 - -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_UART5 -#define SBUS_TELEMETRY_UART SERIAL_PORT_UART4 -#define DEFAULT_FEATURES (FEATURE_TELEMETRY | FEATURE_OSD) -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC -#define CURRENT_METER_SCALE_DEFAULT 140 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD (BIT(2)) - -#define USABLE_TIMER_CHANNEL_COUNT 8 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) ) diff --git a/src/main/target/MOTOLABF4/target.mk b/src/main/target/MOTOLABF4/target.mk deleted file mode 100644 index d837aa32a4..0000000000 --- a/src/main/target/MOTOLABF4/target.mk +++ /dev/null @@ -1,12 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += SDCARD_SPI VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/max7456.c - -ifeq ($(TARGET), MLTYPHF4) -TARGET_SRC += \ - drivers/vtx_rtc6705.c \ - drivers/vtx_rtc6705_soft_spi.c -endif diff --git a/src/main/target/NUCLEOF446RE/config.c b/src/main/target/NUCLEOF446RE/config.c deleted file mode 100644 index 08513b492c..0000000000 --- a/src/main/target/NUCLEOF446RE/config.c +++ /dev/null @@ -1,38 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "io/serial.h" - -#include "config_helper.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART1, FUNCTION_MSP }, - { SERIAL_PORT_USART2, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); -} -#endif diff --git a/src/main/target/NUCLEOF446RE/target.c b/src/main/target/NUCLEOF446RE/target.c deleted file mode 100644 index 45096a504a..0000000000 --- a/src/main/target/NUCLEOF446RE/target.c +++ /dev/null @@ -1,39 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/timer.h" -#include "drivers/timer_def.h" -#include "drivers/dma.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_MOTOR, 0, 1), - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 1), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 1), - DEF_TIM(TIM3, CH4, PB1, 0, 0, 0), - DEF_TIM(TIM3, CH2, PA4, 0, 0, 0), - DEF_TIM(TIM2, CH2, PA1, 0, 0, 0), - DEF_TIM(TIM2, CH3, PA2, 0, 0, 0) -}; diff --git a/src/main/target/NUCLEOF446RE/target.h b/src/main/target/NUCLEOF446RE/target.h deleted file mode 100644 index d7575d2cff..0000000000 --- a/src/main/target/NUCLEOF446RE/target.h +++ /dev/null @@ -1,164 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define USE_TARGET_CONFIG - -#define TARGET_BOARD_IDENTIFIER "N446" // STM32 Nucleo F446RE -#define USBD_PRODUCT_STRING "NucleoF446RE" - -#define LED0_PIN PA5 // Onboard LED - -//#define USE_BEEPER -//#define BEEPER_PIN PD12 - - -#define USE_SPI -//#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_2 - -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -#define USE_GYRO -#define USE_FAKE_GYRO -#define USE_GYRO_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 - -#define USE_ACC -#define USE_FAKE_ACC -#define USE_ACC_SPI_MPU6500 -#define USE_ACC_SPI_MPU9250 - -#define GYRO_1_SPI_INSTANCE SPI2 -#define GYRO_1_CS_PIN PB12 - - -//#define GYRO_1_EXTI_PIN PC13 -//#define ENSURE_MPU_DATA_READY_IS_LOW - -#define USE_BARO -#define USE_FAKE_BARO -//#define USE_BARO_BMP085 -//#define USE_BARO_BMP280 -//#define USE_BARO_MS5611 - -//#define USE_MAX7456 -//#define MAX7456_SPI_INSTANCE SPI2 -//#define MAX7456_SPI_CS_PIN SPI2_NSS_PIN - -#define USE_CMS - -//#define USE_SDCARD -//#define SDCARD_SPI_INSTANCE SPI2 -//#define SDCARD_SPI_CS_PIN PB12 -//// Note, this is the same DMA channel as UART1_RX. Luckily we don't use DMA for USART Rx. -//#define SDCARD_DMA_CHANNEL_TX DMA1_Channel5 -// Performance logging for SD card operations: -// #define AFATFS_USE_INTROSPECTIVE_LOGGING - -#define USE_MAG -#define USE_FAKE_MAG -//#define USE_MAG_AK8963 -//#define USE_MAG_AK8975 -//#define USE_MAG_HMC5883 - -#define USE_RX_SPI -#define RX_SPI_INSTANCE SPI1 -// Nordic Semiconductor uses 'CSN', STM uses 'NSS' -#define RX_CE_PIN PC7 // D9 -#define RX_NSS_PIN PB6 // D10 -// NUCLEO has NSS on PB6, rather than the standard PA4 - -#define SPI1_NSS_PIN RX_NSS_PIN -#define SPI1_SCK_PIN PA5 // D13 -#define SPI1_MISO_PIN PA6 // D12 -#define SPI1_MOSI_PIN PA7 // D11 - -#define USE_RX_NRF24 -#define USE_RX_CX10 -#define USE_RX_H8_3D -#define USE_RX_INAV -#define USE_RX_SYMA -#define USE_RX_V202 -#define RX_SPI_DEFAULT_PROTOCOL RX_SPI_NRF24_H8_3D - -#define USE_VCP - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_UART3 -#define UART3_TX_PIN PB10 -#define UART3_RX_PIN PB11 - -//#define USE_UART4 -//#define USE_UART5 - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 6 - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PB8 // (HARDARE=0,PPM) - -#define USE_I2C - -#define USE_I2C_DEVICE_2 -#define I2C2_SCL NONE // PB10, shared with UART3TX -#define I2C2_SDA NONE // PB11, shared with UART3RX - -#define USE_I2C_DEVICE_3 -#define I2C3_SCL NONE // PA8 -#define I2C3_SDA NONE // PC9 -#define I2C_DEVICE (I2CDEV_2) - -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default) -//#define ADC_INSTANCE ADC2 -//#define ADC2_DMA_OPT 1 // DMA 2 Stream 3 Channel 1 (compat default) -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC1 -#define RSSI_ADC_PIN PC2 -#define EXTERNAL1_ADC_PIN PC3 - -#define USE_SONAR -#define SONAR_TRIGGER_PIN PB0 -#define SONAR_ECHO_PIN PB1 - -#define MAX_SUPPORTED_MOTORS 12 - -#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) -#define TARGET_IO_PORTB (0xffff & ~(BIT(2))) -#define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) -#define TARGET_IO_PORTD BIT(2) - -#define USABLE_TIMER_CHANNEL_COUNT 8 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8)) diff --git a/src/main/target/NUCLEOF446RE/target.mk b/src/main/target/NUCLEOF446RE/target.mk deleted file mode 100644 index a3a3181d86..0000000000 --- a/src/main/target/NUCLEOF446RE/target.mk +++ /dev/null @@ -1,16 +0,0 @@ -F446_TARGETS += $(TARGET) -FEATURES = VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_fake.c \ - drivers/barometer/barometer_fake.c \ - drivers/compass/compass_fake.c \ - drivers/rx/rx_nrf24l01.c \ - rx/nrf24_cx10.c \ - rx/nrf24_inav.c \ - rx/nrf24_h8_3d.c \ - rx/nrf24_syma.c \ - rx/nrf24_v202.c diff --git a/src/main/target/NUCLEOF7/target.c b/src/main/target/NUCLEOF7/target.c deleted file mode 100644 index 4026e59c52..0000000000 --- a/src/main/target/NUCLEOF7/target.c +++ /dev/null @@ -1,66 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" -#include "drivers/dma.h" - -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -#if defined(USE_DSHOT) -// DSHOT TEST -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 1), // S4_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S5_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 1), // S6_IN - - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 0), // S10_OUT 1 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 1), // S1_OUT 4 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S4_OUT - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // S5_OUT 3 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0), // S3_OUT - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S9_OUT - -}; -#else -// STANDARD LAYOUT -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM | TIM_USE_PPM, 0, 0), // S2_IN - DEF_TIM(TIM8, CH1, PC6, TIM_USE_PWM, 0, 0), // S3_IN - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM, 0, 0), // S4_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0), // S5_IN - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0), // S6_IN - - DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR | TIM_USE_LED, 0, 0), // S10_OUT 1 - DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0), // S5_OUT 3 - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 0), // S1_OUT 4 - DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0), // S3_OUT - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // S4_OUT - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // S9_OUT - -}; -#endif diff --git a/src/main/target/NUCLEOF7/target.h b/src/main/target/NUCLEOF7/target.h deleted file mode 100644 index 30330783e1..0000000000 --- a/src/main/target/NUCLEOF7/target.h +++ /dev/null @@ -1,166 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "NUC7" - -#define USBD_PRODUCT_STRING "NucleoF7" - -#define LED0_PIN PB7 -#define LED1_PIN PB14 -#define LED0_INVERTED -#define LED1_INVERTED - -#define USE_BEEPER -#define BEEPER_PIN PA0 -#define BEEPER_INVERTED - -#undef USE_MULTI_GYRO // XXX Drop this if target has I2C configured - -#define USE_ACC -#define USE_FAKE_ACC -#define USE_ACC_MPU6050 - -#define USE_GYRO -#define USE_FAKE_GYRO -#define USE_GYRO_MPU6050 -#define GYRO_1_ALIGN CW270_DEG - -// MPU6050 interrupts -#define GYRO_1_EXTI_PIN PB15 - -#define USE_MAG -#define USE_FAKE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 -#define USE_MAG_LIS3MDL -#define MAG_HMC5883_ALIGN CW270_DEG_FLIP - -#define USE_BARO -#define USE_FAKE_BARO -#define USE_BARO_MS5611 -#define USE_BARO_SPI_BMP388 -#define BARO_SPI_INSTANCE SPI1 -#define BARO_CS_PIN SPI1_NSS_PIN - -#define USABLE_TIMER_CHANNEL_COUNT 11 - -#define USE_VCP -#define USE_USB_DETECT -#define USB_DETECT_PIN PA9 - -//#define USE_UART1 -//#define UART1_RX_PIN PA10 -//#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN PD6 -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define USE_UART7 -#define UART7_RX_PIN PE7 -#define UART7_TX_PIN PE8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 10 //VCP, USART2, USART3, UART4, UART5, USART6, USART7, USART8, SOFTSERIAL x 2 - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PB15 // (Hardware=0, PPM) - -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define USE_SPI_DEVICE_4 - -#define SPI1_NSS_PIN PA4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define SPI4_NSS_PIN PE11 -#define SPI4_SCK_PIN PE12 -#define SPI4_MISO_PIN PE13 -#define SPI4_MOSI_PIN PE14 - -#define USE_SDCARD -#define USE_SDCARD_SPI -#define SDCARD_DETECT_INVERTED -#define SDCARD_DETECT_PIN PF14 -#define SDCARD_SPI_INSTANCE SPI4 -#define SDCARD_SPI_CS_PIN SPI4_NSS_PIN -#define SPI4_TX_DMA_OPT 0 // DMA 2 Stream 1 Channel 4 - -#define USE_FLASHFS -#define USE_FLASH_CHIP -#define USE_FLASH_M25P16 -#define USE_FLASH_W25N01G // 1Gb NAND flash support -#define USE_FLASH_W25M // Stacked die support -#define USE_FLASH_W25M512 // 512Kb (256Kb x 2 stacked) NOR flash support -#define USE_FLASH_W25M02G // 2Gb (1Gb x 2 stacked) NAND flash support -#define FLASH_SPI_INSTANCE SPI4 -#define FLASH_CS_PIN PE10 - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C_DEVICE (I2CDEV_1) -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -#define USE_ADC -#define VBAT_ADC_PIN PA3 -#define CURRENT_METER_ADC_PIN PC0 -#define RSSI_ADC_PIN PC3 - -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) | TIM_N(12) ) diff --git a/src/main/target/NUCLEOF7/target.mk b/src/main/target/NUCLEOF7/target.mk deleted file mode 100644 index b4697a23d8..0000000000 --- a/src/main/target/NUCLEOF7/target.mk +++ /dev/null @@ -1,13 +0,0 @@ -F7X6XG_TARGETS += $(TARGET) -FEATURES += SDCARD_SPI ONBOARDFLASH VCP - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_fake.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/compass/compass_fake.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/compass/compass_lis3mdl.c diff --git a/src/main/target/NUCLEOH723ZG/config.c b/src/main/target/NUCLEOH723ZG/config.c deleted file mode 100644 index 4fcef5467d..0000000000 --- a/src/main/target/NUCLEOH723ZG/config.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "io/serial.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART3, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; -} -#endif diff --git a/src/main/target/NUCLEOH723ZG/target.c b/src/main/target/NUCLEOH723ZG/target.c deleted file mode 100644 index bd81f68f4d..0000000000 --- a/src/main/target/NUCLEOH723ZG/target.c +++ /dev/null @@ -1,54 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 7, 0 ), // SPI1_SCK - DEF_TIM(TIM12, CH2, PB15, TIM_USE_LED, 0, 0, 0 ), - - DEF_TIM(TIM1, CH2, PE11, TIM_USE_PWM|TIM_USE_PPM, 0, 0, 0 ), - DEF_TIM(TIM1, CH1, PE9, TIM_USE_PWM, 0, 0, 0 ), - DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0, 0 ), - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0, 4 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1, 4), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 2, 4), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 3, 4), - - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 5, 0 ), - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0, 0 ), - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 2, 0 ), - - // DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 8, 0 ), // I2C1 - // DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0, 0 ), // I2C1 - // DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0, 0 ), -}; diff --git a/src/main/target/NUCLEOH723ZG/target.h b/src/main/target/NUCLEOH723ZG/target.h deleted file mode 100644 index cee9efc4d7..0000000000 --- a/src/main/target/NUCLEOH723ZG/target.h +++ /dev/null @@ -1,283 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "H723" -#define USBD_PRODUCT_STRING "Nucleo-H723" - -#define USE_TARGET_CONFIG - -#define LED0_PIN PB0 -#define LED1_PIN PB7 // PE1 on NUCLEO-H743ZI2 (may collide with UART8_TX) -//#define LED2_PIN PB14 // SDMMC2_D0 - -// Nucleo-H7A3 has one button (The blue USER button). -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PC13 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PC13 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_BEEPER -#define BEEPER_PIN PE3 -#define BEEPER_INVERTED - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN NONE // PD6, collide with SDMMC2_CK -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 // Virtual COM port on NUCLEO-H7A3ZI-Q -#define UART3_TX_PIN PD8 // Virtual COM port on NUCLEO-H7A3ZI-Q - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define USE_UART7 -#define UART7_RX_PIN PE7 -#define UART7_TX_PIN PE8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_LPUART1 -#define LPUART1_RX_PIN PB7 // PA10 (Shared with UART1) -#define LPUART1_TX_PIN PB6 // PA9 (Shared with UART1) - -#define USE_VCP - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 12 - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PB3 -#define SPI1_MISO_PIN PB4 -#define SPI1_MOSI_PIN PB5 - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN NONE -#define SPI2_MISO_PIN NONE -#define SPI2_MOSI_PIN NONE - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PC10 // PC10 -#define SPI3_MISO_PIN PC11 // PC11 -#define SPI3_MOSI_PIN PC12 // PC12 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN NONE -#define SPI4_MISO_PIN NONE -#define SPI4_MOSI_PIN NONE - -#define USE_SPI_DEVICE_5 -#define SPI5_SCK_PIN NONE -#define SPI5_MISO_PIN NONE -#define SPI5_MOSI_PIN NONE - -#define USE_SPI_DEVICE_6 -#define SPI6_SCK_PIN NONE -#define SPI6_MISO_PIN NONE -#define SPI6_MOSI_PIN NONE - -// #define USE_QUADSPI -//#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN NONE // PB2 - -#define QUADSPI1_BK1_IO0_PIN NONE // PD11 -#define QUADSPI1_BK1_IO1_PIN NONE // PD12 -#define QUADSPI1_BK1_IO2_PIN NONE // PE2 -#define QUADSPI1_BK1_IO3_PIN NONE // PD13 -#define QUADSPI1_BK1_CS_PIN NONE // PB10 - -#define QUADSPI1_BK2_IO0_PIN NONE // PE7 -#define QUADSPI1_BK2_IO1_PIN NONE // PE8 -#define QUADSPI1_BK2_IO2_PIN NONE // PE9 -#define QUADSPI1_BK2_IO3_PIN NONE // PE10 -#define QUADSPI1_BK2_CS_PIN NONE // NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#if !defined(NUCLEOH7A3_RAMBASED) - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN NONE - -// SDMMC1 -// CK PC12 -// CMD PD2 -// D0 PC8 -// D1 PC9 -// D2 PC10 -// D3 PC11 - -// SDIO configuration for SDMMC1, 1-bit width -#define SDIO_DEVICE SDIODEV_2 // SDIODEV_1 (for SDMMC1) or SDIODEV_2 (for SDMMC2) (or SDIOINVALID) -#define SDIO_USE_4BIT false -#define SDIO_CK_PIN PD6 // SDMMC1: PC12 SDMMC2: PC1 or PD6 -#define SDIO_CMD_PIN PD7 // SDMMC1: PD2 SDMMC2: PA0 or PD7 -#define SDIO_D0_PIN PB14 // SDMMC1: PC8 SDMMC2: PB14 -#define SDIO_D1_PIN NONE // SDMMC1: PC9 SDMMC2: PB15 -#define SDIO_D2_PIN NONE // SDMMC1: PC10 SDMMC2: PB3 -#define SDIO_D3_PIN NONE // SDMMC2: PC11 SDMMC2: PB4 - -#define USE_BLACKBOX -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#endif - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_SPI_HMC5883 -#define HMC5883_SPI_INSTANCE NULL -#define HMC5883_CS_PIN NONE - -#define USE_BARO -#define USE_BARO_LPS -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 -#define USE_BARO_BMP388 -#define USE_BARO_MS5611 -#define USE_BARO_SPI_BMP280 -#define BMP280_SPI_INSTANCE NULL -#define BMP280_CS_PIN NONE - -#define USE_GYRO -#define USE_MULTI_GYRO -#define USE_ACC - -#define USE_FAKE_GYRO -#define USE_FAKE_ACC -#define USE_GYRO_SPI_MPU6000 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6500 -#define USE_ACC_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 -#define USE_ACC_SPI_MPU9250 -#define USE_GYRO_SPI_ICM42605 -#define USE_ACC_SPI_ICM42605 -#define USE_GYRO_SPI_ICM42688P -#define USE_ACC_SPI_ICM42688P - -#define GYRO_1_CS_PIN PD15 -#define GYRO_1_SPI_INSTANCE SPI1 - -// I2C acc/gyro test, may require to activate -// set gyro_x_bustype = I2C -// set gyro_x_i2cBus = -//#define USE_GYRO_MPU6050 -//#define USE_ACC_MPU6050 - -#define USE_FLASH_CHIP -#define USE_FLASH_M25P16 -#define USE_FLASH_W25M -#define FLASH_SPI_INSTANCE NULL -#define FLASH_CS_PIN NONE -#define USE_FLASHFS - -#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot -#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values -#define USE_TIMER -#define USE_PWM_OUTPUT -#define USE_MOTOR - -#define USE_RANGEFINDER -#define USE_RANGEFINDER_HCSR04 -#define USE_RANGEFINDER_TF - -#define USE_TRANSPONDER - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE NULL // SPI3 -#define MAX7456_SPI_CS_PIN NONE // PC9 - -#define USE_I2C_OLED_DISPLAY - -#define USE_ADC - -// DMA stream assignmnets -#define VBAT_ADC_PIN PB1 // ADC1 -#define CURRENT_METER_ADC_PIN PC0 // ADC1 -#define RSSI_ADC_PIN PF14 // ADC2 -#define EXTERNAL1_ADC_PIN PC3 // ADC3 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define USE_DSHOT -#define USE_DSHOT_DMAR - -#define USE_DMA - -// Thanks to DMAMUX, H7 does not have limitations on DMA stream assignments to devices (except for collisions among them). -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC2_DMA_OPT 9 -#define ADC3_DMA_OPT 10 - -#define DEFAULT_FEATURE (FEATURE_OSD) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 14 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) diff --git a/src/main/target/NUCLEOH723ZG/target.mk b/src/main/target/NUCLEOH723ZG/target.mk deleted file mode 100644 index a61ea8fb10..0000000000 --- a/src/main/target/NUCLEOH723ZG/target.mk +++ /dev/null @@ -1,32 +0,0 @@ -# -# NUCLEO-H723ZG board -# -H723xG_TARGETS += $(TARGET) - -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO - -# Top level Makefile adds, if not defined, HSE_VALUE, as default for F4 targets. -# We don't want to assume any particular value until de facto design is established, -# so we set the value here. -# -# However, HSE_VALUE is currently a global build option and can not be changed from -# board to board. Generic target will have to store this value as a PG variable and -# change clock on the fly after the PG became readable. - -HSE_VALUE = 8000000 # For NUCLEO-H723ZG with STLINK, HSE is 8MHz from STLINK - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/max7456.c \ diff --git a/src/main/target/NUCLEOH725ZG/config.c b/src/main/target/NUCLEOH725ZG/config.c deleted file mode 100644 index 4fcef5467d..0000000000 --- a/src/main/target/NUCLEOH725ZG/config.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "io/serial.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART3, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; -} -#endif diff --git a/src/main/target/NUCLEOH725ZG/target.c b/src/main/target/NUCLEOH725ZG/target.c deleted file mode 100644 index bd81f68f4d..0000000000 --- a/src/main/target/NUCLEOH725ZG/target.c +++ /dev/null @@ -1,54 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 7, 0 ), // SPI1_SCK - DEF_TIM(TIM12, CH2, PB15, TIM_USE_LED, 0, 0, 0 ), - - DEF_TIM(TIM1, CH2, PE11, TIM_USE_PWM|TIM_USE_PPM, 0, 0, 0 ), - DEF_TIM(TIM1, CH1, PE9, TIM_USE_PWM, 0, 0, 0 ), - DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0, 0 ), - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0, 4 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1, 4), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 2, 4), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 3, 4), - - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 5, 0 ), - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0, 0 ), - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 2, 0 ), - - // DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 8, 0 ), // I2C1 - // DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0, 0 ), // I2C1 - // DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0, 0 ), -}; diff --git a/src/main/target/NUCLEOH725ZG/target.h b/src/main/target/NUCLEOH725ZG/target.h deleted file mode 100644 index 423f8bfa6c..0000000000 --- a/src/main/target/NUCLEOH725ZG/target.h +++ /dev/null @@ -1,292 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -/* - * Note about "Nucleo-H725ZG" - * - * Nucleo-H725ZG is Nucleo-H7A3ZI-Q board transplanted with STM32H725ZG. - * STM32H7A3ZI and STM32H725ZG are drop-in compatible, except for pin 119; - * VDDMMC (supply) on H723 and VDD (supply) on H725. Since Nucleo-H723ZG connects - * VDD to pin 119, the board is fully compatible with H725ZG. - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "H725" -#define USBD_PRODUCT_STRING "Nucleo-H725" - -#define USE_TARGET_CONFIG - -#define LED0_PIN PB0 -#define LED1_PIN PB7 // PE1 on NUCLEO-H743ZI2 (may collide with UART8_TX) XXX How about H7A3 case? -//#define LED2_PIN PB14 // SDMMC2_D0 - -// Nucleo-H7A3 has one button (The blue USER button). -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PC13 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PC13 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_BEEPER -#define BEEPER_PIN PE3 -#define BEEPER_INVERTED - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN NONE // PD6, collide with SDMMC2_CK -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 // Virtual COM port on NUCLEO-H7A3ZI-Q -#define UART3_TX_PIN PD8 // Virtual COM port on NUCLEO-H7A3ZI-Q - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define USE_UART7 -#define UART7_RX_PIN PE7 -#define UART7_TX_PIN PE8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_LPUART1 -#define LPUART1_RX_PIN PB7 // PA10 (Shared with UART1) -#define LPUART1_TX_PIN PB6 // PA9 (Shared with UART1) - -#define USE_VCP - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 12 - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PB3 -#define SPI1_MISO_PIN PB4 -#define SPI1_MOSI_PIN PB5 - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN NONE -#define SPI2_MISO_PIN NONE -#define SPI2_MOSI_PIN NONE - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PC10 // PC10 -#define SPI3_MISO_PIN PC11 // PC11 -#define SPI3_MOSI_PIN PC12 // PC12 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN NONE -#define SPI4_MISO_PIN NONE -#define SPI4_MOSI_PIN NONE - -#define USE_SPI_DEVICE_5 -#define SPI5_SCK_PIN NONE -#define SPI5_MISO_PIN NONE -#define SPI5_MOSI_PIN NONE - -#define USE_SPI_DEVICE_6 -#define SPI6_SCK_PIN NONE -#define SPI6_MISO_PIN NONE -#define SPI6_MOSI_PIN NONE - -// #define USE_QUADSPI -//#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN NONE // PB2 - -#define QUADSPI1_BK1_IO0_PIN NONE // PD11 -#define QUADSPI1_BK1_IO1_PIN NONE // PD12 -#define QUADSPI1_BK1_IO2_PIN NONE // PE2 -#define QUADSPI1_BK1_IO3_PIN NONE // PD13 -#define QUADSPI1_BK1_CS_PIN NONE // PB10 - -#define QUADSPI1_BK2_IO0_PIN NONE // PE7 -#define QUADSPI1_BK2_IO1_PIN NONE // PE8 -#define QUADSPI1_BK2_IO2_PIN NONE // PE9 -#define QUADSPI1_BK2_IO3_PIN NONE // PE10 -#define QUADSPI1_BK2_CS_PIN NONE // NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#if !defined(NUCLEOH7A3_RAMBASED) - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN NONE - -// SDMMC1 -// CK PC12 -// CMD PD2 -// D0 PC8 -// D1 PC9 -// D2 PC10 -// D3 PC11 - -// SDIO configuration for SDMMC1, 1-bit width -#define SDIO_DEVICE SDIODEV_2 // SDIODEV_1 (for SDMMC1) or SDIODEV_2 (for SDMMC2) (or SDIOINVALID) -#define SDIO_USE_4BIT false -#define SDIO_CK_PIN PD6 // SDMMC1: PC12 SDMMC2: PC1 or PD6 -#define SDIO_CMD_PIN PD7 // SDMMC1: PD2 SDMMC2: PA0 or PD7 -#define SDIO_D0_PIN PB14 // SDMMC1: PC8 SDMMC2: PB14 -#define SDIO_D1_PIN NONE // SDMMC1: PC9 SDMMC2: PB15 -#define SDIO_D2_PIN NONE // SDMMC1: PC10 SDMMC2: PB3 -#define SDIO_D3_PIN NONE // SDMMC2: PC11 SDMMC2: PB4 - -#define USE_BLACKBOX -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#endif - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_SPI_HMC5883 -#define HMC5883_SPI_INSTANCE NULL -#define HMC5883_CS_PIN NONE - -#define USE_BARO -#define USE_BARO_LPS -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 -#define USE_BARO_BMP388 -#define USE_BARO_MS5611 -#define USE_BARO_SPI_BMP280 -#define BMP280_SPI_INSTANCE NULL -#define BMP280_CS_PIN NONE - -#define USE_GYRO -#define USE_MULTI_GYRO -#define USE_ACC - -#define USE_FAKE_GYRO -#define USE_FAKE_ACC -#define USE_GYRO_SPI_MPU6000 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6500 -#define USE_ACC_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 -#define USE_ACC_SPI_MPU9250 -#define USE_GYRO_SPI_ICM42605 -#define USE_ACC_SPI_ICM42605 -#define USE_GYRO_SPI_ICM42688P -#define USE_ACC_SPI_ICM42688P - -#define GYRO_1_CS_PIN PD15 -#define GYRO_1_SPI_INSTANCE SPI1 - -// I2C acc/gyro test, may require to activate -// set gyro_x_bustype = I2C -// set gyro_x_i2cBus = -//#define USE_GYRO_MPU6050 -//#define USE_ACC_MPU6050 - -#define USE_FLASH_CHIP -#define USE_FLASH_M25P16 -#define USE_FLASH_W25M -#define FLASH_SPI_INSTANCE NULL -#define FLASH_CS_PIN NONE -#define USE_FLASHFS - -#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot -#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values -#define USE_TIMER -#define USE_PWM_OUTPUT -#define USE_MOTOR - -#define USE_RANGEFINDER -#define USE_RANGEFINDER_HCSR04 -#define USE_RANGEFINDER_TF - -#define USE_TRANSPONDER - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE NULL // SPI3 -#define MAX7456_SPI_CS_PIN NONE // PC9 - -#define USE_I2C_OLED_DISPLAY - -#define USE_ADC - -// DMA stream assignmnets -#define VBAT_ADC_PIN PB1 // ADC1 -#define CURRENT_METER_ADC_PIN PC0 // ADC1 -#define RSSI_ADC_PIN PF14 // ADC2 -#define EXTERNAL1_ADC_PIN PC3 // ADC3 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define USE_DSHOT -#define USE_DSHOT_DMAR - -#define USE_DMA - -// Thanks to DMAMUX, H7 does not have limitations on DMA stream assignments to devices (except for collisions among them). -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC2_DMA_OPT 9 -#define ADC3_DMA_OPT 10 - -#define DEFAULT_FEATURE (FEATURE_OSD) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 14 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) diff --git a/src/main/target/NUCLEOH725ZG/target.mk b/src/main/target/NUCLEOH725ZG/target.mk deleted file mode 100644 index ce6bd819de..0000000000 --- a/src/main/target/NUCLEOH725ZG/target.mk +++ /dev/null @@ -1,32 +0,0 @@ -# -# NUCLEO-H7A3ZI-Q board transplanted with STM32H725ZG -# -H725xG_TARGETS += $(TARGET) - -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO - -# Top level Makefile adds, if not defined, HSE_VALUE, as default for F4 targets. -# We don't want to assume any particular value until de facto design is established, -# so we set the value here. -# -# However, HSE_VALUE is currently a global build option and can not be changed from -# board to board. Generic target will have to store this value as a PG variable and -# change clock on the fly after the PG became readable. - -HSE_VALUE = 8000000 # For NUCLEO-H7A3ZI-Q with STLINK, HSE is 8MHz from STLINK - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/max7456.c \ diff --git a/src/main/target/NUCLEOH743/NUCLEOH743_RAMBASED.mk b/src/main/target/NUCLEOH743/NUCLEOH743_RAMBASED.mk deleted file mode 100644 index e69de29bb2..0000000000 diff --git a/src/main/target/NUCLEOH743/config.c b/src/main/target/NUCLEOH743/config.c deleted file mode 100644 index 8a435f64a8..0000000000 --- a/src/main/target/NUCLEOH743/config.c +++ /dev/null @@ -1,46 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "io/serial.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART1, FUNCTION_MSP }, - { SERIAL_PORT_USART2, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); -#if !defined(NUCLEOH743_RAMBASED) - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; -#endif -} -#endif diff --git a/src/main/target/NUCLEOH743/target.c b/src/main/target/NUCLEOH743/target.c deleted file mode 100644 index 27112ef619..0000000000 --- a/src/main/target/NUCLEOH743/target.c +++ /dev/null @@ -1,61 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io_def.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -#include "build/debug_pin.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 7, 0 ), // SPI1_SCK - DEF_TIM(TIM12, CH2, PB15, TIM_USE_LED, 0, 0, 0 ), - - DEF_TIM(TIM1, CH2, PE11, TIM_USE_PWM|TIM_USE_PPM, 0, 0, 0 ), - DEF_TIM(TIM1, CH1, PE9, TIM_USE_PWM, 0, 0, 0 ), - DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0, 0 ), - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0, 4 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1, 4), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 2, 4), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 3, 4), - - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 5, 0 ), - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0, 0 ), - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 2, 0 ), - - // DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 8, 0 ), // I2C1 - // DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0, 0 ), // I2C1 - // DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0, 0 ), -}; - -dbgPin_t dbgPins[DEBUG_PIN_COUNT] = { - { .tag = IO_TAG(PG1) }, -}; diff --git a/src/main/target/NUCLEOH743/target.h b/src/main/target/NUCLEOH743/target.h deleted file mode 100644 index 3a0796fd43..0000000000 --- a/src/main/target/NUCLEOH743/target.h +++ /dev/null @@ -1,297 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "H743" -#define USBD_PRODUCT_STRING "Nucleo-H743" - -#define USE_TARGET_CONFIG - -#define USE_DEBUG_PIN -#define DEBUG_PIN_COUNT 1 - -#define LED0_PIN PB0 -#define LED1_PIN PB7 // PE1 on NUCLEO-H743ZI2 (may collide with UART8_TX) -//#define LED2_PIN PB14 // SDMMC2_D0 - -// Use explicit cache management as per https://github.com/betaflight/betaflight/pull/10378 -#define USE_LEDSTRIP_CACHE_MGMT - -// Nucleo-H743 has one button (The blue USER button). -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PC13 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PC13 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_BEEPER -#define BEEPER_PIN PE3 -#define BEEPER_INVERTED - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN NONE // PD6, collide with SDMMC2_CK -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 // ST-LINK Virtual COM Port -#define UART3_TX_PIN PD8 // ST-LINK Virtual COM Port - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define USE_UART7 -#define UART7_RX_PIN PE7 -#define UART7_TX_PIN PE8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_LPUART1 -#define LPUART1_RX_PIN PB7 // PA10 (Shared with UART1) -#define LPUART1_TX_PIN PB6 // PA9 (Shared with UART1) - -#define USE_VCP - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 12 - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PB3 -#define SPI1_MISO_PIN PB4 -#define SPI1_MOSI_PIN PB5 - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN NONE -#define SPI2_MISO_PIN NONE -#define SPI2_MOSI_PIN NONE - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PC10 // PC10 -#define SPI3_MISO_PIN PC11 // PC11 -#define SPI3_MOSI_PIN PC12 // PC12 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN NONE -#define SPI4_MISO_PIN NONE -#define SPI4_MOSI_PIN NONE - -#define USE_SPI_DEVICE_5 -#define SPI5_SCK_PIN NONE -#define SPI5_MISO_PIN NONE -#define SPI5_MOSI_PIN NONE - -#define USE_SPI_DEVICE_6 -#define SPI6_SCK_PIN NONE -#define SPI6_MISO_PIN NONE -#define SPI6_MOSI_PIN NONE - -#define USE_QUADSPI -#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN NONE // PB2 - -#define QUADSPI1_BK1_IO0_PIN NONE // PD11 -#define QUADSPI1_BK1_IO1_PIN NONE // PD12 -#define QUADSPI1_BK1_IO2_PIN NONE // PE2 -#define QUADSPI1_BK1_IO3_PIN NONE // PD13 -#define QUADSPI1_BK1_CS_PIN NONE // PB10 - -#define QUADSPI1_BK2_IO0_PIN NONE // PE7 -#define QUADSPI1_BK2_IO1_PIN NONE // PE8 -#define QUADSPI1_BK2_IO2_PIN NONE // PE9 -#define QUADSPI1_BK2_IO3_PIN NONE // PE10 -#define QUADSPI1_BK2_CS_PIN NONE // NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#if !defined(NUCLEOH743_RAMBASED) - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN NONE - -// SDMMC1 -// CK PC12 -// CMD PD2 -// D0 PC8 -// D1 PC9 -// D2 PC10 -// D3 PC11 - -// SDIO configuration for SDMMC1, 1-bit width -#define SDIO_DEVICE SDIODEV_2 // SDIODEV_1 (for SDMMC1) or SDIODEV_2 (for SDMMC2) (or SDIOINVALID) -#define SDIO_USE_4BIT false -#define SDIO_CK_PIN PD6 // SDMMC1: PC12 SDMMC2: PC1 or PD6 -#define SDIO_CMD_PIN PD7 // SDMMC1: PD2 SDMMC2: PA0 or PD7 -#define SDIO_D0_PIN PB14 // SDMMC1: PC8 SDMMC2: PB14 -#define SDIO_D1_PIN NONE // SDMMC1: PC9 SDMMC2: PB15 -#define SDIO_D2_PIN NONE // SDMMC1: PC10 SDMMC2: PB3 -#define SDIO_D3_PIN NONE // SDMMC2: PC11 SDMMC2: PB4 - -#define USE_BLACKBOX -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#endif - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -// For testing I2C4on APB4 -//#define USE_I2C_DEVICE_4 -//#define I2C4_SCL PF14 -//#define I2C4_SDA PF15 -//#define I2C_DEVICE (I2CDEV_4) - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_SPI_HMC5883 -#define HMC5883_SPI_INSTANCE NULL -#define HMC5883_CS_PIN NONE - -#define USE_BARO -#define USE_BARO_LPS -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 -#define USE_BARO_BMP388 -#define USE_BARO_MS5611 -#define USE_BARO_SPI_BMP280 -#define BMP280_SPI_INSTANCE NULL -#define BMP280_CS_PIN NONE - -#define USE_GYRO -#define USE_MULTI_GYRO -#define USE_ACC - -#define USE_FAKE_GYRO -#define USE_FAKE_ACC -#define USE_GYRO_SPI_MPU6000 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6500 -#define USE_ACC_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 -#define USE_ACC_SPI_MPU9250 -#define USE_GYRO_SPI_ICM42605 -#define USE_ACC_SPI_ICM42605 -#define USE_GYRO_SPI_ICM42688P -#define USE_ACC_SPI_ICM42688P - -#define GYRO_1_CS_PIN PD15 -#define GYRO_1_SPI_INSTANCE SPI1 - -// I2C acc/gyro test, may require to activate -// set gyro_x_bustype = I2C -// set gyro_x_i2cBus = -//#define USE_GYRO_MPU6050 -//#define USE_ACC_MPU6050 - -#define USE_FLASH_CHIP -#define USE_FLASH_M25P16 -#define USE_FLASH_W25M -#define USE_FLASH_W25Q128FV -#define USE_FLASH_W25N01G -#define FLASH_SPI_INSTANCE NULL -#define FLASH_CS_PIN NONE -#define USE_FLASHFS - -#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot -#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values -#define USE_TIMER -#define USE_PWM_OUTPUT -#define USE_MOTOR - -#define USE_RANGEFINDER -#define USE_RANGEFINDER_HCSR04 -#define USE_RANGEFINDER_TF - -#define USE_TRANSPONDER - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE NULL // SPI3 -#define MAX7456_SPI_CS_PIN NONE // PC9 - -#define USE_I2C_OLED_DISPLAY - -#define USE_ADC - -// DMA stream assignmnets -#define VBAT_ADC_PIN PB1 // ADC1 -#define CURRENT_METER_ADC_PIN PC0 // ADC1 -#define RSSI_ADC_PIN PF14 // ADC2 -#define EXTERNAL1_ADC_PIN PC3 // ADC3 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define USE_DSHOT -#define USE_DSHOT_DMAR - -#define USE_DMA - -// Thanks to DMAMUX, H7 does not have limitations on DMA stream assignments to devices (except for collisions among them). -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC2_DMA_OPT 9 -#define ADC3_DMA_OPT 10 - -#define DEFAULT_FEATURE (FEATURE_OSD) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 14 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) diff --git a/src/main/target/NUCLEOH743/target.mk b/src/main/target/NUCLEOH743/target.mk deleted file mode 100644 index dfe14af61f..0000000000 --- a/src/main/target/NUCLEOH743/target.mk +++ /dev/null @@ -1,35 +0,0 @@ -H743xI_TARGETS += $(TARGET) - - -ifeq ($(TARGET), NUCLEOH743_RAMBASED) -FEATURES += VCP ONBOARDFLASH -RAM_BASED = yes -else -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO -endif - -# Top level Makefile adds, if not defined, HSE_VALUE, as default for F4 targets. -# We don't want to assume any particular value until de facto design is established, -# so we set the value here. -# -# However, HSE_VALUE is currently a global build option and can not be changed from -# board to board. Generic target will have to store this value as a PG variable and -# change clock on the fly after the PG became readable. - -HSE_VALUE = 8000000 # For NUCLEO-H743ZI with STLINK, HSE is 8MHz from STLINK - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/max7456.c \ diff --git a/src/main/target/NUCLEOH7A3ZI/config.c b/src/main/target/NUCLEOH7A3ZI/config.c deleted file mode 100644 index ade7f3cb78..0000000000 --- a/src/main/target/NUCLEOH7A3ZI/config.c +++ /dev/null @@ -1,43 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "io/serial.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART3, FUNCTION_MSP }, // ST-LINK Virtual COM port on NUCLEO-H7A3ZI-Q -}; - -void targetConfiguration(void) -{ - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; -} -#endif diff --git a/src/main/target/NUCLEOH7A3ZI/target.c b/src/main/target/NUCLEOH7A3ZI/target.c deleted file mode 100644 index bd81f68f4d..0000000000 --- a/src/main/target/NUCLEOH7A3ZI/target.c +++ /dev/null @@ -1,54 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - // DEF_TIM(TIM2, CH2, PB3, TIM_USE_LED, 0, 7, 0 ), // SPI1_SCK - DEF_TIM(TIM12, CH2, PB15, TIM_USE_LED, 0, 0, 0 ), - - DEF_TIM(TIM1, CH2, PE11, TIM_USE_PWM|TIM_USE_PPM, 0, 0, 0 ), - DEF_TIM(TIM1, CH1, PE9, TIM_USE_PWM, 0, 0, 0 ), - DEF_TIM(TIM2, CH1, PA15, TIM_USE_PWM, 0, 0, 0 ), - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 0, 4 ), - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 1, 4), - DEF_TIM(TIM8, CH3, PC8, TIM_USE_MOTOR, 0, 2, 4), - DEF_TIM(TIM8, CH4, PC9, TIM_USE_MOTOR, 0, 3, 4), - - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 5, 0 ), - - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 0, 0 ), - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 4, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 2, 0 ), - - // DEF_TIM(TIM4, CH3, PB8, TIM_USE_MOTOR, 0, 8, 0 ), // I2C1 - // DEF_TIM(TIM4, CH4, PB9, TIM_USE_MOTOR, 0, 0, 0 ), // I2C1 - // DEF_TIM(TIM9, CH2, PE6, TIM_USE_MOTOR, 0, 0, 0 ), -}; diff --git a/src/main/target/NUCLEOH7A3ZI/target.h b/src/main/target/NUCLEOH7A3ZI/target.h deleted file mode 100644 index 918b706bb9..0000000000 --- a/src/main/target/NUCLEOH7A3ZI/target.h +++ /dev/null @@ -1,285 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "H7A3" -#define USBD_PRODUCT_STRING "Nucleo-H7A3" - -#define USE_TARGET_CONFIG - -#define LED0_PIN PB0 -#define LED1_PIN PB7 // PE1 on NUCLEO-H743ZI2 (may collide with UART8_TX) XXX How about H7A3 case? -//#define LED2_PIN PB14 // SDMMC2_D0 - -// Nucleo-H7A3 has one button (The blue USER button). -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PC13 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PC13 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_BEEPER -#define BEEPER_PIN PE3 -#define BEEPER_INVERTED - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART2 -#define UART2_RX_PIN NONE // PD6, collide with SDMMC2_CK -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 // ST-LINK Virtual COM port on NUCLEO-H7A3ZI-Q -#define UART3_TX_PIN PD8 // ST-LINK Virtual COM port on NUCLEO-H7A3ZI-Q - -#define USE_UART4 -#define UART4_RX_PIN PC11 -#define UART4_TX_PIN PC10 - -#define USE_UART5 -#define UART5_RX_PIN PD2 -#define UART5_TX_PIN PC12 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 - -#define USE_UART7 -#define UART7_RX_PIN PE7 -#define UART7_TX_PIN PE8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_LPUART1 -#define LPUART1_RX_PIN PB7 // PA10 (Shared with UART1) -#define LPUART1_TX_PIN PB6 // PA9 (Shared with UART1) - -#define USE_VCP - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 12 - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_SCK_PIN PB3 -#define SPI1_MISO_PIN PB4 -#define SPI1_MOSI_PIN PB5 - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN NONE -#define SPI2_MISO_PIN NONE -#define SPI2_MOSI_PIN NONE - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PC10 // PC10 -#define SPI3_MISO_PIN PC11 // PC11 -#define SPI3_MOSI_PIN PC12 // PC12 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN NONE -#define SPI4_MISO_PIN NONE -#define SPI4_MOSI_PIN NONE - -#define USE_SPI_DEVICE_5 -#define SPI5_SCK_PIN NONE -#define SPI5_MISO_PIN NONE -#define SPI5_MOSI_PIN NONE - -#define USE_SPI_DEVICE_6 -#define SPI6_SCK_PIN NONE -#define SPI6_MISO_PIN NONE -#define SPI6_MOSI_PIN NONE - -// #define USE_QUADSPI -//#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN NONE // PB2 - -#define QUADSPI1_BK1_IO0_PIN NONE // PD11 -#define QUADSPI1_BK1_IO1_PIN NONE // PD12 -#define QUADSPI1_BK1_IO2_PIN NONE // PE2 -#define QUADSPI1_BK1_IO3_PIN NONE // PD13 -#define QUADSPI1_BK1_CS_PIN NONE // PB10 - -#define QUADSPI1_BK2_IO0_PIN NONE // PE7 -#define QUADSPI1_BK2_IO1_PIN NONE // PE8 -#define QUADSPI1_BK2_IO2_PIN NONE // PE9 -#define QUADSPI1_BK2_IO3_PIN NONE // PE10 -#define QUADSPI1_BK2_CS_PIN NONE // NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#if !defined(NUCLEOH7A3_RAMBASED) - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN NONE - -// SDMMC1 -// CK PC12 -// CMD PD2 -// D0 PC8 -// D1 PC9 -// D2 PC10 -// D3 PC11 - -// SDIO configuration for SDMMC1, 1-bit width -#define SDIO_DEVICE SDIODEV_2 // SDIODEV_1 (for SDMMC1) or SDIODEV_2 (for SDMMC2) (or SDIOINVALID) -#define SDIO_USE_4BIT false -#define SDIO_CK_PIN PD6 // SDMMC1: PC12 SDMMC2: PC1 or PD6 -#define SDIO_CMD_PIN PD7 // SDMMC1: PD2 SDMMC2: PA0 or PD7 -#define SDIO_D0_PIN PB14 // SDMMC1: PC8 SDMMC2: PB14 -#define SDIO_D1_PIN NONE // SDMMC1: PC9 SDMMC2: PB15 -#define SDIO_D2_PIN NONE // SDMMC1: PC10 SDMMC2: PB3 -#define SDIO_D3_PIN NONE // SDMMC2: PC11 SDMMC2: PB4 - -#define USE_BLACKBOX -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#endif - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_SPI_HMC5883 -#define HMC5883_SPI_INSTANCE NULL -#define HMC5883_CS_PIN NONE - -#define USE_BARO -#define USE_BARO_LPS -#define USE_BARO_BMP085 -#define USE_BARO_BMP280 -#define USE_BARO_BMP388 -#define USE_BARO_MS5611 -#define USE_BARO_SPI_BMP280 -#define BMP280_SPI_INSTANCE NULL -#define BMP280_CS_PIN NONE - -#define USE_GYRO -#define USE_MULTI_GYRO -#define USE_ACC - -#define USE_FAKE_GYRO -#define USE_FAKE_ACC -#define USE_GYRO_SPI_MPU6000 -#define USE_ACC_SPI_MPU6000 -#define USE_GYRO_SPI_MPU6500 -#define USE_ACC_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 -#define USE_ACC_SPI_MPU9250 -#define USE_GYRO_SPI_ICM42605 -#define USE_ACC_SPI_ICM42605 -#define USE_GYRO_SPI_ICM42688P -#define USE_ACC_SPI_ICM42688P - -#define GYRO_1_CS_PIN PD15 -#define GYRO_1_SPI_INSTANCE SPI1 - -// I2C acc/gyro test, may require to activate -// set gyro_x_bustype = I2C -// set gyro_x_i2cBus = -//#define USE_GYRO_MPU6050 -//#define USE_ACC_MPU6050 - -#define USE_FLASH_CHIP -#define USE_FLASH_M25P16 -#define USE_FLASH_W25M -#define FLASH_SPI_INSTANCE NULL -#define FLASH_CS_PIN NONE -#define USE_FLASHFS - -#define USE_BRUSHED_ESC_AUTODETECT // Detect if brushed motors are connected and set defaults appropriately to avoid motors spinning on boot -#define USE_GYRO_REGISTER_DUMP // Adds gyroregisters command to cli to dump configured register values -#define USE_TIMER -#define USE_PWM_OUTPUT -#define USE_MOTOR - -#define USE_RANGEFINDER -#define USE_RANGEFINDER_HCSR04 -#define USE_RANGEFINDER_TF - -#define USE_TRANSPONDER - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE NULL // SPI3 -#define MAX7456_SPI_CS_PIN NONE // PC9 - -#define USE_I2C_OLED_DISPLAY - -#define USE_ADC - -// DMA stream assignmnets -#define VBAT_ADC_PIN PB1 // ADC1 -#define CURRENT_METER_ADC_PIN PC0 // ADC1 -#define RSSI_ADC_PIN PF14 // ADC2 -#define EXTERNAL1_ADC_PIN PC3 // ADC3 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define USE_DSHOT -#define USE_DSHOT_DMAR - -#define USE_DMA - -// Thanks to DMAMUX, H7 does not have limitations on DMA stream assignments to devices (except for collisions among them). -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -//#define UART9_TX_DMA_OPT 8 -//#define UART10_TX_DMA_OPT 9 -#define ADC1_DMA_OPT 8 -#define ADC2_DMA_OPT 9 -#define ADC3_DMA_OPT 10 - -#define DEFAULT_FEATURE (FEATURE_OSD) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 14 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) diff --git a/src/main/target/NUCLEOH7A3ZI/target.mk b/src/main/target/NUCLEOH7A3ZI/target.mk deleted file mode 100644 index 38a35f89ed..0000000000 --- a/src/main/target/NUCLEOH7A3ZI/target.mk +++ /dev/null @@ -1,35 +0,0 @@ -H7A3xIQ_TARGETS += $(TARGET) - - -ifeq ($(TARGET), NUCLEOH7A3ZI_RAMBASED) -FEATURES += VCP ONBOARDFLASH -RAM_BASED = yes -else -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO -endif - -# Top level Makefile adds, if not defined, HSE_VALUE, as default for F4 targets. -# We don't want to assume any particular value until de facto design is established, -# so we set the value here. -# -# However, HSE_VALUE is currently a global build option and can not be changed from -# board to board. Generic target will have to store this value as a PG variable and -# change clock on the fly after the PG became readable. - -HSE_VALUE = 8000000 # For NUCLEO-H7A3ZI-Q with STLINK, HSE is 8MHz from STLINK - -TARGET_SRC = \ - drivers/accgyro/accgyro_fake.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/accgyro/accgyro_spi_icm426xx.c \ - drivers/accgyro/accgyro_mpu6050.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/max7456.c \ diff --git a/src/main/target/SPARKY2/target.c b/src/main/target/SPARKY2/target.c deleted file mode 100644 index 5f8e53e0c3..0000000000 --- a/src/main/target/SPARKY2/target.c +++ /dev/null @@ -1,42 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/timer.h" -#include "drivers/timer_def.h" -#include "drivers/dma.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM8, CH2, PC7, TIM_USE_PWM | TIM_USE_PPM, 0, 0 ), // PPM IN - DEF_TIM(TIM12, CH1, PB14, TIM_USE_PWM, 0, 0 ), // S2_IN - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PWM, 0, 0 ), // S3_IN - GPIO_PartialRemap_TIM3 - DEF_TIM(TIM8, CH3, PC8, TIM_USE_PWM, 0, 0 ), // S4_IN - DEF_TIM(TIM8, CH4, PC9, TIM_USE_PWM, 0, 0 ), // S5_IN - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0 ), // S1_OUT - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0 ), // S2_OUT - DEF_TIM(TIM2, CH4, PA3, TIM_USE_MOTOR, 0, 0 ), // S3_OUT - DEF_TIM(TIM2, CH3, PA2, TIM_USE_MOTOR, 0, 0 ), // S4_OUT - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 0 ), // S5_OUT - GPIO_PartialRemap_TIM3 - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0 ), // S6_OUT -}; diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h deleted file mode 100644 index b7b0523b33..0000000000 --- a/src/main/target/SPARKY2/target.h +++ /dev/null @@ -1,127 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once -#define TARGET_BOARD_IDENTIFIER "SPK2" - -#define USBD_PRODUCT_STRING "Sparky 2.0" - -#define LED0_PIN PB5 -#define LED1_PIN PB4 -#define LED2_PIN PB6 - -#define USE_BEEPER -#define BEEPER_PIN PC9 -#define BEEPER_INVERTED - -#define INVERTER_PIN_UART6 PC6 - -// MPU9250 interrupt -#define GYRO_1_EXTI_PIN PC5 -#define ENSURE_MPU_DATA_READY_IS_LOW - -#define GYRO_1_CS_PIN PC4 -#define GYRO_1_SPI_INSTANCE SPI1 - -#define USE_ACC -#define USE_ACC_SPI_MPU9250 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU9250 -#define GYRO_1_ALIGN CW270_DEG - -#define USE_MAG -//#define USE_MAG_HMC5883 -#define USE_MAG_AK8963 - -//#define MAG_HMC5883_ALIGN CW180_DEG -#define MAG_AK8963_ALIGN CW270_DEG - -#define USE_BARO -#define USE_BARO_MS5611 -//#define USE_BARO_BMP280 - -#define FLASH_CS_PIN PB3 -#define FLASH_SPI_INSTANCE SPI3 - -//#define RFM22B_CS_PIN PA15 -//#define RFM22B_SPI_INSTANCE SPI3 - -#define USE_FLASHFS -#define USE_FLASH_M25P16 -#define USE_FLASH_TOOLS - -#define USE_VCP -#define USE_USB_DETECT -#define USB_DETECT_PIN PA8 - -#define USE_UART1 -#define UART1_RX_PIN PA10 -#define UART1_TX_PIN PA9 - -#define USE_UART3 -#define UART3_RX_PIN PB11 -#define UART3_TX_PIN PB10 - -#define USE_UART6 -#define UART6_RX_PIN PC7 -#define UART6_TX_PIN PC6 //inverter - -#define SERIAL_PORT_COUNT 4 - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PC7 // (HARDARE=0,PPM) - -#define USE_SPI - -#define USE_SPI_DEVICE_1 //MPU9250 -#define SPI1_NSS_PIN PC4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define USE_SPI_DEVICE_3 //dataflash -#define SPI3_NSS_PIN PB3 -#define SPI3_SCK_PIN PC10 -#define SPI3_MISO_PIN PC11 -#define SPI3_MOSI_PIN PC12 - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_ADC -#define VBAT_ADC_PIN PC1 -#define CURRENT_METER_ADC_PIN PC2 - -#undef USE_LED_STRIP - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define SERIALRX_PROVIDER SERIALRX_SBUS -#define SERIALRX_UART SERIAL_PORT_USART6 - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12)) diff --git a/src/main/target/SPARKY2/target.mk b/src/main/target/SPARKY2/target.mk deleted file mode 100644 index a07c15d242..0000000000 --- a/src/main/target/SPARKY2/target.mk +++ /dev/null @@ -1,9 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu9250.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_ak8963.c \ - drivers/compass/compass_hmc5883l.c diff --git a/src/main/target/SPEKTRUMF400/target.c b/src/main/target/SPEKTRUMF400/target.c deleted file mode 100644 index fb4461335c..0000000000 --- a/src/main/target/SPEKTRUMF400/target.c +++ /dev/null @@ -1,46 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/timer.h" -#include "drivers/timer_def.h" -#include "drivers/dma.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM3, CH4, PB1, TIM_USE_MOTOR, 0, 0), // pin 27 - M1 - DMA1_ST2 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_MOTOR, 0, 0), // pin 26 - M2 - DMA1_ST7 - DEF_TIM(TIM3, CH2, PB5, TIM_USE_MOTOR, 0, 0), // pin 57 - M3 - DMA1_ST5 - DEF_TIM(TIM3, CH1, PB4, TIM_USE_MOTOR, 0, 0), // pin 56 - M4 - DMA1_ST4 - DEF_TIM(TIM8, CH1, PC6, TIM_USE_LED, 0, 0), // LED_STRIP - DMA2_ST2 - - // Backdoor timers - DEF_TIM(TIM1, CH2, PA9, TIM_USE_NONE , 0, 0), // UART1_TX T1C2 - DEF_TIM(TIM1, CH3, PA10, TIM_USE_NONE , 0, 0), // UART1_RX T1C3 - - DEF_TIM(TIM2, CH3, PA2, TIM_USE_NONE , 0, 0), // UART2_TX T5C3,T9C1,T2C3 - DEF_TIM(TIM9, CH2, PA3, TIM_USE_NONE , 0, 0), // UART2_RX T5C4,T9C2,T2C4 - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_NONE , 0, 0), // UART4_TX T5C1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_NONE , 0, 0), // UART4_RX T5C2,T2C2 -}; diff --git a/src/main/target/SPEKTRUMF400/target.h b/src/main/target/SPEKTRUMF400/target.h deleted file mode 100644 index 0a6ddf1d67..0000000000 --- a/src/main/target/SPEKTRUMF400/target.h +++ /dev/null @@ -1,125 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "SKF4" - -#define USBD_PRODUCT_STRING "SpektrumF400" - -#define LED0_PIN PA15 -#define LED1_PIN PC8 - -#define USE_BEEPER -#define BEEPER_PIN PC2 -#define BEEPER_INVERTED - -#define USE_SPI - -#define USE_SPI_DEVICE_1 -#define SPI1_NSS_PIN PA4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -#define USE_SPI_DEVICE_2 -#define SPI2_NSS_PIN PB12 -#define SPI2_SCK_PIN PB13 -#define SPI2_MISO_PIN PB14 -#define SPI2_MOSI_PIN PB15 - -//#define USE_FLASHFS -//#define USE_FLASH_M25P16 - -//#define FLASH_CS_PIN PB12 -//#define FLASH_SPI_INSTANCE SPI2 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6500 -#define USE_GYRO_SPI_MPU9250 -#define GYRO_1_ALIGN CW270_DEG - -#define USE_ACC -#define USE_ACC_SPI_MPU6500 -#define USE_ACC_SPI_MPU9250 - -#define GYRO_1_CS_PIN PB12 -#define GYRO_1_SPI_INSTANCE SPI2 - -#define GYRO_1_EXTI_PIN PC13 -#define ENSURE_MPU_DATA_READY_IS_LOW - -#define USE_VCP - -#define USE_UART1 -#define UART1_TX_PIN PA9 -#define UART1_RX_PIN PA10 - -#define USE_UART2 -#define UART2_TX_PIN PA2 -#define UART2_RX_PIN PA3 - -#define USE_UART3 -#define UART3_RX_PIN PC11 -#define UART3_TX_PIN PC10 - -#define USE_UART4 -#define UART4_RX_PIN PA1 -#define UART4_TX_PIN PA0 - -#define USE_UART5 -//#define UART5_RX_PIN PC12 // XXX ??? -#define UART5_TX_PIN PC12 - -#define USE_SOFTSERIAL1 -#define USE_SOFTSERIAL2 - -#define SERIAL_PORT_COUNT 8 - -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PB8 - -#define USE_I2C - -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -#define USE_I2C_DEVICE_2 -#define I2C2_SCL NONE // PB10, Shared with UART3_TX -#define I2C2_SDA NONE // PB11, Shared with UART3_RX - -#define I2C_DEVICE (I2CDEV_1) - -#define USE_ADC -#define ADC_INSTANCE ADC1 -#define ADC1_DMA_OPT 1 // DMA 2 Stream 4 Channel 0 (compat default) -#define VBAT_ADC_PIN PC0 -#define CURRENT_METER_ADC_PIN PC3 - -#define TARGET_XTAL_MHZ 12 - -#define TARGET_IO_PORTA (0xffff & ~(BIT(14)|BIT(13))) -#define TARGET_IO_PORTB (0xffff & ~(BIT(2))) -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD BIT(2) - -#define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(5)|TIM_N(8)|TIM_N(9)) diff --git a/src/main/target/SPEKTRUMF400/target.mk b/src/main/target/SPEKTRUMF400/target.mk deleted file mode 100644 index a19a2a2e11..0000000000 --- a/src/main/target/SPEKTRUMF400/target.mk +++ /dev/null @@ -1,11 +0,0 @@ -F446_TARGETS += $(TARGET) - -#FEATURES = VCP ONBOARDFLASH -FEATURES = VCP - -HSE_VALUE = 12000000 - -TARGET_SRC = \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu9250.c diff --git a/src/main/target/SPRACINGH7EXTREME/config.c b/src/main/target/SPRACINGH7EXTREME/config.c deleted file mode 100644 index ae30859418..0000000000 --- a/src/main/target/SPRACINGH7EXTREME/config.c +++ /dev/null @@ -1,51 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "drivers/sdio.h" - -#include "io/serial.h" - -#include "osd/osd.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART1, FUNCTION_MSP }, - { SERIAL_PORT_USART2, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - osdConfigMutable()->core_temp_alarm = 85; - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; - sdioPinConfigure(); - SDIO_GPIO_Init(); -} -#endif diff --git a/src/main/target/SPRACINGH7EXTREME/target.c b/src/main/target/SPRACINGH7EXTREME/target.c deleted file mode 100644 index 1c3fe0fd15..0000000000 --- a/src/main/target/SPRACINGH7EXTREME/target.c +++ /dev/null @@ -1,58 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 10, 0 ), // LED Strip - DEF_TIM(TIM2, CH4, PB11, TIM_USE_TRANSPONDER, 0, 11, 0 ), // Transponder - - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM | TIM_USE_PWM, 0, 0, 0 ), // Also USART1 RX - - DEF_TIM(TIM15, CH1, PE5, TIM_USE_CAMERA_CONTROL, 0, 0, 0 ), - DEF_TIM(TIM15, CH2, PE6, TIM_USE_NONE, 0, 0, 0 ), - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0, 0 ), // M1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 2, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 3, 0 ), // M4 - - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 4, 1 ), // M5 - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 5, 1 ), // M6 - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 6, 2 ), // M7 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 7, 2 ), // M8 - - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 12, 0 ), // M9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0, 0 ), // M10 // Note: No DMA on TIM4_CH4, can use with BURST DSHOT using TIM4_UP - - DEF_TIM(TIM3, CH1, PA6, TIM_USE_NONE, 0, 0, 0 ), // Also TIM13/CH1 - DEF_TIM(TIM3, CH2, PA7, TIM_USE_NONE, 0, 0, 0 ), // Also TIM14/CH1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH2_N - DEF_TIM(TIM3, CH4, PB1, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH3_N -}; - diff --git a/src/main/target/SPRACINGH7EXTREME/target.h b/src/main/target/SPRACINGH7EXTREME/target.h deleted file mode 100644 index d525c99df0..0000000000 --- a/src/main/target/SPRACINGH7EXTREME/target.h +++ /dev/null @@ -1,243 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "SP7E" -#define USBD_PRODUCT_STRING "SPRacingH7EXTREME" - -#define USE_TARGET_CONFIG - -#define USE_SPRACING_PERSISTENT_RTC_WORKAROUND - -#define LED0_PIN PE3 - -#define USE_BEEPER -#define BEEPER_PIN PD7 -#define BEEPER_INVERTED - -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PE4 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PE4 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_QUADSPI -#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN PB2 - -#define QUADSPI1_BK1_IO0_PIN PD11 -#define QUADSPI1_BK1_IO1_PIN PD12 -#define QUADSPI1_BK1_IO2_PIN PE2 -#define QUADSPI1_BK1_IO3_PIN PD13 -#define QUADSPI1_BK1_CS_PIN PB10 - -#define QUADSPI1_BK2_IO0_PIN PE7 -#define QUADSPI1_BK2_IO1_PIN PE8 -#define QUADSPI1_BK2_IO2_PIN PE9 -#define QUADSPI1_BK2_IO3_PIN PE10 -#define QUADSPI1_BK2_CS_PIN NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#define USE_FLASH_CHIP -#define CONFIG_IN_EXTERNAL_FLASH -//#define CONFIG_IN_SDCARD -//#define CONFIG_IN_RAM -#if !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_SDCARD) && !defined(CONFIG_IN_EXTERNAL_FLASH) -#error "EEPROM storage location not defined" -#endif - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PB15 -#define UART1_TX_PIN PB14 - -#define USE_UART2 -#define UART2_RX_PIN NONE -#define UART2_TX_PIN PD5 // TX pin is bidirectional. - -#define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 - -#define USE_UART4 -#define UART4_RX_PIN PD0 -#define UART4_TX_PIN PD1 - -#define USE_UART5 -#define UART5_RX_PIN PB5 -#define UART5_TX_PIN PB13 - -#define USE_UART6 -#define UART6_RX_PIN PC7 // aka M7 -#define UART6_TX_PIN PC6 // aka M8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_VCP -#define USE_USB_ID - -#define SERIAL_PORT_COUNT 8 - -#define USE_SPI - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PD3 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 -#define SPI2_NSS_PIN PB12 - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PD6 -#define SPI3_NSS_PIN PA15 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN PE12 -#define SPI4_MISO_PIN PE13 -#define SPI4_MOSI_PIN PE14 -#define SPI4_NSS_PIN PE11 - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 - -#define USE_BARO -#define USE_BARO_BMP388 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6500 -#define USE_MULTI_GYRO -#undef USE_GYRO_REGISTER_DUMP - -#define GYRO_1_EXTI_PIN PD4 -#define GYRO_2_EXTI_PIN PE15 -#define ENSURE_MPU_DATA_READY_IS_LOW - -#define GYRO_1_CS_PIN SPI3_NSS_PIN -#define GYRO_1_SPI_INSTANCE SPI3 - -#define GYRO_2_CS_PIN SPI2_NSS_PIN -#define GYRO_2_SPI_INSTANCE SPI2 - -#define USE_ACC -#define USE_ACC_SPI_MPU6500 - -#define GYRO_1_ALIGN CW180_DEG -#define GYRO_2_ALIGN ALIGN_CUSTOM -#define GYRO_2_CUSTOM_ALIGN SENSOR_ALIGNMENT( 0, 0, 225) - -#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_BOTH - -#define USE_FLASHFS -#define USE_FLASH_TOOLS -#define USE_FLASH_W25N01G -#define FLASH_QUADSPI_INSTANCE QUADSPI - -#define USE_PID_AUDIO - -#define USE_TRANSPONDER -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI4 -#define MAX7456_SPI_CS_PIN SPI4_NSS_PIN - -#define USE_VTX_RTC6705 -#define USE_VTX_RTC6705_SOFTSPI -#define VTX_RTC6705_OPTIONAL // VTX/OSD board is OPTIONAL - -#define RTC6705_POWER_PIN PB1 // J14-6 -#define RTC6705_CS_PIN PB0 // J14-5 -#define RTC6705_SPICLK_PIN PA7 // J14-4 -#define RTC6705_SPI_MOSI_PIN PA6 // J14-3 - -#ifdef USE_DMA_SPEC -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC3_DMA_OPT 9 -//#define ADC2_DMA_OPT 10 // ADC2 not used. -#else -#define ADC1_DMA_STREAM DMA2_Stream0 -#define ADC3_DMA_STREAM DMA2_Stream1 -//#define ADC2_DMA_STREAM DMA2_Stream2 // ADC2 not used. -#endif - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN PD10 -#define SDCARD_DETECT_INVERTED -#define SDIO_DEVICE SDIODEV_1 -#define SDIO_USE_4BIT true -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 - -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT - -#define USE_ADC -#define USE_ADC_INTERNAL // ADC3 - -#define RSSI_ADC_PIN PC4 // ADC123 -#define VBAT_ADC_PIN PC1 // ADC12 -#define CURRENT_METER_ADC_PIN PC0 // ADC123 -#define EXTERNAL1_ADC_PIN PC5 // ADC12 - -#define CURRENT_METER_SCALE_DEFAULT 225 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 19 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12) | TIM_N(15) ) diff --git a/src/main/target/SPRACINGH7EXTREME/target.mk b/src/main/target/SPRACINGH7EXTREME/target.mk deleted file mode 100644 index 9f9d6c6d1d..0000000000 --- a/src/main/target/SPRACINGH7EXTREME/target.mk +++ /dev/null @@ -1,22 +0,0 @@ -H750xB_TARGETS += $(TARGET) - -HSE_VALUE = 8000000 - -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO - -EXST = yes -EXST_ADJUST_VMA = 0x97CE0000 - - -TARGET_SRC += \ - drivers/bus_quadspi_hal.c \ - drivers/bus_quadspi.c \ - drivers/max7456.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/vtx_rtc6705.c \ - drivers/vtx_rtc6705_soft_spi.c diff --git a/src/main/target/SPRACINGH7NANO/config.c b/src/main/target/SPRACINGH7NANO/config.c deleted file mode 100644 index 21508d4d36..0000000000 --- a/src/main/target/SPRACINGH7NANO/config.c +++ /dev/null @@ -1,44 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "io/serial.h" - -#include "osd/osd.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART1, FUNCTION_MSP }, - { SERIAL_PORT_USART2, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - osdConfigMutable()->core_temp_alarm = 85; - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); -} -#endif diff --git a/src/main/target/SPRACINGH7NANO/target.c b/src/main/target/SPRACINGH7NANO/target.c deleted file mode 100644 index d1315e26fb..0000000000 --- a/src/main/target/SPRACINGH7NANO/target.c +++ /dev/null @@ -1,60 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 10, 0 ), // LED Strip - DEF_TIM(TIM2, CH4, PB11, TIM_USE_TRANSPONDER, 0, 11, 0 ), // Transponder - - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM | TIM_USE_PWM, 0, 0, 0 ), // Also USART1 RX - - DEF_TIM(TIM15, CH1, PE5, TIM_USE_CAMERA_CONTROL, 0, 0, 0 ), - DEF_TIM(TIM15, CH2, PE6, TIM_USE_NONE, 0, 0, 0 ), - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0, 0 ), // M1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 2, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 3, 0 ), // M4 - - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 4, 1 ), // M5 / I2C4_SCL - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 5, 1 ), // M6 / I2C4_SDA - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 6, 2 ), // M7 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 7, 2 ), // M8 - - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 12, 0 ), // M9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0, 0 ), // M10 // Note: No DMA on TIM4_CH4, can use with BURST DSHOT using TIM4_UP - - DEF_TIM(TIM3, CH1, PA6, TIM_USE_NONE, 0, 0, 0 ), // Also TIM13/CH1 - DEF_TIM(TIM3, CH2, PA7, TIM_USE_NONE, 0, 0, 0 ), // Also TIM14/CH1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH2_N - DEF_TIM(TIM3, CH4, PB1, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH3_N -}; - - - diff --git a/src/main/target/SPRACINGH7NANO/target.h b/src/main/target/SPRACINGH7NANO/target.h deleted file mode 100644 index b7f6cbed11..0000000000 --- a/src/main/target/SPRACINGH7NANO/target.h +++ /dev/null @@ -1,234 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "SP7N" -#define USBD_PRODUCT_STRING "SPRacingH7NANO" - -#define USE_TARGET_CONFIG - -#define USE_SPRACING_PERSISTENT_RTC_WORKAROUND - -#define LED0_PIN PE3 - -#define USE_BEEPER -#define BEEPER_PIN PD7 -#define BEEPER_INVERTED - -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PE4 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PE4 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_QUADSPI -#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN PB2 - -#define QUADSPI1_BK1_IO0_PIN PD11 -#define QUADSPI1_BK1_IO1_PIN PD12 -#define QUADSPI1_BK1_IO2_PIN PE2 -#define QUADSPI1_BK1_IO3_PIN PD13 -#define QUADSPI1_BK1_CS_PIN NONE - -#define QUADSPI1_BK2_IO0_PIN PE7 -#define QUADSPI1_BK2_IO1_PIN PE8 -#define QUADSPI1_BK2_IO2_PIN PE9 -#define QUADSPI1_BK2_IO3_PIN PE10 -#define QUADSPI1_BK2_CS_PIN PB10 - -#define QUADSPI1_MODE QUADSPI_MODE_BK2_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_NONE | QUADSPI_BK2_CS_SOFTWARE | QUADSPI_CS_MODE_SEPARATE) - -#define USE_FLASH_CHIP -#define CONFIG_IN_EXTERNAL_FLASH -//#define CONFIG_IN_SDCARD -//#define CONFIG_IN_RAM -#if !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_SDCARD) && !defined(CONFIG_IN_EXTERNAL_FLASH) -#error "EEPROM storage location not defined" -#endif - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PB15 -#define UART1_TX_PIN PB14 - -#define USE_UART2 -#define UART2_RX_PIN NONE -#define UART2_TX_PIN PD5 // TX pin is bidirectional. - -#define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 - -#define USE_UART4 -#define UART4_RX_PIN PD0 -#define UART4_TX_PIN PD1 - -#define USE_UART5 -#define UART5_RX_PIN PB5 -#define UART5_TX_PIN PB13 - -#define USE_UART6 -#define UART6_RX_PIN PC7 // aka M7 -#define UART6_TX_PIN PC6 // aka M8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_VCP -#define USE_USB_ID - -#define SERIAL_PORT_COUNT 8 - -#define USE_SPI - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PD3 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 -#define SPI2_NSS_PIN PB12 - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PD6 -#define SPI3_NSS_PIN PA15 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN PE12 -#define SPI4_MISO_PIN PE13 -#define SPI4_MOSI_PIN PE14 -#define SPI4_NSS_PIN PE11 - -#define USE_I2C -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_I2C_DEVICE_4 // Shared with motor outputs 5/6 -#define I2C4_SCL PB6 -#define I2C4_SDA PB7 - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 - -#define USE_BARO -#define USE_BARO_BMP388 -#define USE_BARO_BMP280 -#define USE_BARO_MS5611 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6500 -#define USE_MULTI_GYRO -#undef USE_GYRO_REGISTER_DUMP - -#define GYRO_1_EXTI_PIN PE15 -#define GYRO_2_EXTI_PIN PD4 -#define ENSURE_MPU_DATA_READY_IS_LOW - - -#define GYRO_1_CS_PIN SPI2_NSS_PIN -#define GYRO_1_SPI_INSTANCE SPI2 - -#define GYRO_2_CS_PIN SPI3_NSS_PIN -#define GYRO_2_SPI_INSTANCE SPI3 - -#define USE_ACC -#define USE_ACC_SPI_MPU6500 - -#define GYRO_1_ALIGN CW0_DEG_FLIP -#define GYRO_2_ALIGN CW0_DEG_FLIP - -#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 - -#define USE_FLASHFS -#define USE_FLASH_TOOLS -#define USE_FLASH_W25N01G -#define FLASH_QUADSPI_INSTANCE QUADSPI - -// SD card not present on hardware, but pins are reserved. -//#define USE_SDCARD -#ifdef USE_SDCARD -#define SDCARD_DETECT_PIN PD10 -#define SDCARD_DETECT_INVERTED -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#else -#define ENABLE_BLACKBOX_LOGGING_ON_SPIFLASH_BY_DEFAULT -#endif - - -#define USE_TRANSPONDER - -// MAX7456 not present on hardware, but pins are reserved and available on stacking connector. -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI4 -#define MAX7456_SPI_CS_PIN SPI4_NSS_PIN - -#ifdef USE_DMA_SPEC -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC3_DMA_OPT 9 -//#define ADC2_DMA_OPT 10 // ADC2 not used. -#else -#define ADC1_DMA_STREAM DMA2_Stream0 -#define ADC3_DMA_STREAM DMA2_Stream1 -//#define ADC2_DMA_STREAM DMA2_Stream2 // ADC2 not used. -#endif - -#define USE_ADC -#define USE_ADC_INTERNAL // ADC3 - -#define RSSI_ADC_PIN PC4 // ADC123 -#define VBAT_ADC_PIN PC1 // ADC12 -#define CURRENT_METER_ADC_PIN PC0 // ADC123 -#define EXTERNAL1_ADC_PIN PC5 // ADC12 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 19 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12) | TIM_N(15) ) diff --git a/src/main/target/SPRACINGH7NANO/target.mk b/src/main/target/SPRACINGH7NANO/target.mk deleted file mode 100644 index 7a2eb8b6c0..0000000000 --- a/src/main/target/SPRACINGH7NANO/target.mk +++ /dev/null @@ -1,23 +0,0 @@ -H750xB_TARGETS += $(TARGET) - -HSE_VALUE = 8000000 - -EXST = yes -EXST_ADJUST_VMA = 0x97CE0000 - -FEATURES += VCP ONBOARDFLASH - -TARGET_SRC += \ - drivers/bus_quadspi_hal.c \ - drivers/bus_quadspi.c \ - drivers/max7456.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/barometer/barometer_bmp085.c \ - drivers/barometer/barometer_bmp280.c \ - drivers/barometer/barometer_bmp388.c \ - drivers/barometer/barometer_ms5611.c \ - diff --git a/src/main/target/SPRACINGH7ZERO/config.c b/src/main/target/SPRACINGH7ZERO/config.c deleted file mode 100644 index ae30859418..0000000000 --- a/src/main/target/SPRACINGH7ZERO/config.c +++ /dev/null @@ -1,51 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include -#include - -#include "platform.h" - -#ifdef USE_TARGET_CONFIG - -#include "config_helper.h" - -#include "drivers/sdio.h" - -#include "io/serial.h" - -#include "osd/osd.h" - -#include "pg/sdcard.h" - -static targetSerialPortFunction_t targetSerialPortFunction[] = { - { SERIAL_PORT_USART1, FUNCTION_MSP }, - { SERIAL_PORT_USART2, FUNCTION_MSP }, -}; - -void targetConfiguration(void) -{ - osdConfigMutable()->core_temp_alarm = 85; - targetSerialPortFunctionConfig(targetSerialPortFunction, ARRAYLEN(targetSerialPortFunction)); - sdcardConfigMutable()->mode = SDCARD_MODE_SDIO; - sdioPinConfigure(); - SDIO_GPIO_Init(); -} -#endif diff --git a/src/main/target/SPRACINGH7ZERO/target.c b/src/main/target/SPRACINGH7ZERO/target.c deleted file mode 100644 index 8698d17509..0000000000 --- a/src/main/target/SPRACINGH7ZERO/target.c +++ /dev/null @@ -1,59 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#include - -#include "platform.h" -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM1, CH1, PA8, TIM_USE_LED, 0, 10, 0 ), // LED Strip - DEF_TIM(TIM2, CH4, PB11, TIM_USE_TRANSPONDER, 0, 11, 0 ), // Transponder - - DEF_TIM(TIM12, CH2, PB15, TIM_USE_PPM | TIM_USE_PWM, 0, 0, 0 ), // Also USART1 RX - - DEF_TIM(TIM15, CH1, PE5, TIM_USE_CAMERA_CONTROL, 0, 0, 0 ), - DEF_TIM(TIM15, CH2, PE6, TIM_USE_NONE, 0, 0, 0 ), - - DEF_TIM(TIM5, CH1, PA0, TIM_USE_MOTOR, 0, 0, 0 ), // M1 - DEF_TIM(TIM5, CH2, PA1, TIM_USE_MOTOR, 0, 1, 0 ), - DEF_TIM(TIM5, CH3, PA2, TIM_USE_MOTOR, 0, 2, 0 ), - DEF_TIM(TIM5, CH4, PA3, TIM_USE_MOTOR, 0, 3, 0 ), // M4 - - DEF_TIM(TIM4, CH1, PB6, TIM_USE_MOTOR, 0, 4, 1 ), // M5 / I2C4_SCL - DEF_TIM(TIM4, CH2, PB7, TIM_USE_MOTOR, 0, 5, 1 ), // M6 / I2C4_SDA - - DEF_TIM(TIM8, CH1, PC6, TIM_USE_MOTOR, 0, 6, 2 ), // M7 - DEF_TIM(TIM8, CH2, PC7, TIM_USE_MOTOR, 0, 7, 2 ), // M8 - - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 12, 0 ), // M9 - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0, 0 ), // M10 // Note: No DMA on TIM4_CH4, can use with BURST DSHOT using TIM4_UP - - DEF_TIM(TIM3, CH1, PA6, TIM_USE_NONE, 0, 0, 0 ), // Also TIM13/CH1 - DEF_TIM(TIM3, CH2, PA7, TIM_USE_NONE, 0, 0, 0 ), // Also TIM14/CH1 - DEF_TIM(TIM3, CH3, PB0, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH2_N - DEF_TIM(TIM3, CH4, PB1, TIM_USE_NONE, 0, 0, 0 ), // Also TIM8/CH3_N -}; - - diff --git a/src/main/target/SPRACINGH7ZERO/target.h b/src/main/target/SPRACINGH7ZERO/target.h deleted file mode 100644 index 53bed03e55..0000000000 --- a/src/main/target/SPRACINGH7ZERO/target.h +++ /dev/null @@ -1,236 +0,0 @@ -/* - * This file is part of Cleanflight and Betaflight. - * - * Cleanflight and Betaflight are free software. You can redistribute - * this software and/or modify this software under the terms of the - * GNU General Public License as published by the Free Software - * Foundation, either version 3 of the License, or (at your option) - * any later version. - * - * Cleanflight and Betaflight are distributed in the hope that they - * will be useful, but WITHOUT ANY WARRANTY; without even the implied - * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. - * See the GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. - * - * If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "SP7Z" -#define USBD_PRODUCT_STRING "SPRacingH7ZERO" - -#define USE_TARGET_CONFIG - -#define USE_SPRACING_PERSISTENT_RTC_WORKAROUND - -#define LED0_PIN PE3 - -#define USE_BEEPER -#define BEEPER_PIN PD7 -#define BEEPER_INVERTED - -// Force two buttons to look at the single button so config reset on button works -#define USE_BUTTONS -#define BUTTON_A_PIN PE4 -#define BUTTON_A_PIN_INVERTED // Active high -#define BUTTON_B_PIN PE4 -#define BUTTON_B_PIN_INVERTED // Active high - -#define USE_QUADSPI -#define USE_QUADSPI_DEVICE_1 - -#define QUADSPI1_SCK_PIN PB2 - -#define QUADSPI1_BK1_IO0_PIN PD11 -#define QUADSPI1_BK1_IO1_PIN PD12 -#define QUADSPI1_BK1_IO2_PIN PE2 -#define QUADSPI1_BK1_IO3_PIN PD13 -#define QUADSPI1_BK1_CS_PIN PB10 - -#define QUADSPI1_BK2_IO0_PIN PE7 -#define QUADSPI1_BK2_IO1_PIN PE8 -#define QUADSPI1_BK2_IO2_PIN PE9 -#define QUADSPI1_BK2_IO3_PIN PE10 -#define QUADSPI1_BK2_CS_PIN NONE - -#define QUADSPI1_MODE QUADSPI_MODE_BK1_ONLY -#define QUADSPI1_CS_FLAGS (QUADSPI_BK1_CS_HARDWARE | QUADSPI_BK2_CS_NONE | QUADSPI_CS_MODE_LINKED) - -#define USE_FLASH_CHIP -#define CONFIG_IN_EXTERNAL_FLASH -//#define CONFIG_IN_SDCARD -//#define CONFIG_IN_RAM -#if !defined(CONFIG_IN_RAM) && !defined(CONFIG_IN_SDCARD) && !defined(CONFIG_IN_EXTERNAL_FLASH) -#error "EEPROM storage location not defined" -#endif - -#define USE_UART - -#define USE_UART1 -#define UART1_RX_PIN PB15 -#define UART1_TX_PIN PB14 - -#define USE_UART2 -#define UART2_RX_PIN NONE -#define UART2_TX_PIN PD5 // TX pin is bidirectional. - -#define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 - -#define USE_UART4 -#define UART4_RX_PIN PD0 -#define UART4_TX_PIN PD1 - -#define USE_UART5 -#define UART5_RX_PIN PB5 -#define UART5_TX_PIN PB13 - -#define USE_UART6 -#define UART6_RX_PIN PC7 // aka M7 -#define UART6_TX_PIN PC6 // aka M8 - -#define USE_UART8 -#define UART8_RX_PIN PE0 -#define UART8_TX_PIN PE1 - -#define USE_VCP -#define USE_USB_ID - -#define SERIAL_PORT_COUNT 8 - -#define USE_SPI - -#define USE_SPI_DEVICE_2 -#define SPI2_SCK_PIN PD3 -#define SPI2_MISO_PIN PC2 -#define SPI2_MOSI_PIN PC3 -#define SPI2_NSS_PIN PB12 - -#define USE_SPI_DEVICE_3 -#define SPI3_SCK_PIN PB3 -#define SPI3_MISO_PIN PB4 -#define SPI3_MOSI_PIN PD6 -#define SPI3_NSS_PIN PA15 - -#define USE_SPI_DEVICE_4 -#define SPI4_SCK_PIN PE12 -#define SPI4_MISO_PIN PE13 -#define SPI4_MOSI_PIN PE14 -#define SPI4_NSS_PIN PE11 - -#define USE_I2C -#define USE_I2C_DEVICE_1 // Connected to BMP388 only -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 -#define I2C_DEVICE (I2CDEV_1) - -#define USE_I2C_DEVICE_4 // Shared with motor outputs 5/6 -#define I2C4_SCL PB6 -#define I2C4_SDA PB7 - -#define USE_MAG -#define USE_MAG_HMC5883 -#define USE_MAG_QMC5883 - -#define USE_BARO -#define USE_BARO_BMP388 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6500 -#define USE_MULTI_GYRO -#undef USE_GYRO_REGISTER_DUMP - -#define GYRO_1_EXTI_PIN PD4 -#define GYRO_2_EXTI_PIN PE15 -#define ENSURE_MPU_DATA_READY_IS_LOW - - -#define GYRO_1_CS_PIN SPI3_NSS_PIN -#define GYRO_1_SPI_INSTANCE SPI3 - -#define GYRO_2_CS_PIN SPI2_NSS_PIN -#define GYRO_2_SPI_INSTANCE SPI2 - -#define USE_ACC -#define USE_ACC_SPI_MPU6500 - -#define GYRO_1_ALIGN CW180_DEG -#define GYRO_2_ALIGN CW90_DEG - -#define GYRO_CONFIG_USE_GYRO_DEFAULT GYRO_CONFIG_USE_GYRO_1 - -#define USE_FLASHFS -#define USE_FLASH_TOOLS -#define USE_FLASH_W25N01G -#define FLASH_QUADSPI_INSTANCE QUADSPI - -#define USE_SDCARD -#define USE_SDCARD_SDIO -#define SDCARD_DETECT_PIN PD10 -#define SDCARD_DETECT_INVERTED -#define SDIO_DEVICE SDIODEV_1 -#define SDIO_USE_4BIT true -#define SDIO_CK_PIN PC12 -#define SDIO_CMD_PIN PD2 -#define SDIO_D0_PIN PC8 -#define SDIO_D1_PIN PC9 -#define SDIO_D2_PIN PC10 -#define SDIO_D3_PIN PC11 - -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT - - -#define USE_TRANSPONDER - -#define USE_MAX7456 -#define MAX7456_SPI_INSTANCE SPI4 -#define MAX7456_SPI_CS_PIN SPI4_NSS_PIN - -#ifdef USE_DMA_SPEC -//#define UART1_TX_DMA_OPT 0 -//#define UART2_TX_DMA_OPT 1 -//#define UART3_TX_DMA_OPT 2 -//#define UART4_TX_DMA_OPT 3 -//#define UART5_TX_DMA_OPT 4 -//#define UART6_TX_DMA_OPT 5 -//#define UART7_TX_DMA_OPT 6 -//#define UART8_TX_DMA_OPT 7 -#define ADC1_DMA_OPT 8 -#define ADC3_DMA_OPT 9 -//#define ADC2_DMA_OPT 10 // ADC2 not used. -#else -#define ADC1_DMA_STREAM DMA2_Stream0 -#define ADC3_DMA_STREAM DMA2_Stream1 -//#define ADC2_DMA_STREAM DMA2_Stream2 // ADC2 not used. -#endif - -#define USE_ADC -#define USE_ADC_INTERNAL // ADC3 - -#define RSSI_ADC_PIN PC0 // ADC123 -#define VBAT_ADC_PIN PC4 // ADC123 -#define CURRENT_METER_ADC_PIN PC1 // ADC12 -#define EXTERNAL1_ADC_PIN PC5 // ADC12 - -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC -#define DEFAULT_CURRENT_METER_SOURCE CURRENT_METER_ADC - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL -#define DEFAULT_FEATURES (FEATURE_TRANSPONDER | FEATURE_RSSI_ADC | FEATURE_TELEMETRY | FEATURE_OSD | FEATURE_LED_STRIP) - -#define TARGET_IO_PORTA 0xffff -#define TARGET_IO_PORTB 0xffff -#define TARGET_IO_PORTC 0xffff -#define TARGET_IO_PORTD 0xffff -#define TARGET_IO_PORTE 0xffff -#define TARGET_IO_PORTF 0xffff -#define TARGET_IO_PORTG 0xffff - -#define USABLE_TIMER_CHANNEL_COUNT 19 - -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12) | TIM_N(15) ) diff --git a/src/main/target/SPRACINGH7ZERO/target.mk b/src/main/target/SPRACINGH7ZERO/target.mk deleted file mode 100644 index 37062410bd..0000000000 --- a/src/main/target/SPRACINGH7ZERO/target.mk +++ /dev/null @@ -1,26 +0,0 @@ -H750xB_TARGETS += $(TARGET) - -HSE_VALUE = 8000000 - -ifneq ($(EXST),) -EXST = yes -EXST_ADJUST_VMA = 0x97CE0000 -endif - -ifneq ($(EXST),yes) -TARGET_FLASH_SIZE := 1024 -LD_SCRIPT = $(LINKER_DIR)/stm32_flash_h750_1m.ld -endif - -FEATURES += VCP ONBOARDFLASH SDCARD_SDIO - -TARGET_SRC += \ - drivers/bus_quadspi_hal.c \ - drivers/bus_quadspi.c \ - drivers/max7456.c \ - drivers/accgyro/accgyro_mpu.c \ - drivers/accgyro/accgyro_mpu6500.c \ - drivers/accgyro/accgyro_spi_mpu6500.c \ - drivers/compass/compass_hmc5883l.c \ - drivers/compass/compass_qmc5883l.c \ - drivers/barometer/barometer_bmp388.c \ diff --git a/src/main/target/UAVPNG030MINI/target.c b/src/main/target/UAVPNG030MINI/target.c deleted file mode 100644 index 5ac94896a3..0000000000 --- a/src/main/target/UAVPNG030MINI/target.c +++ /dev/null @@ -1,39 +0,0 @@ -/* - * This file is part of Cleanflight. - * - * Cleanflight is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * Cleanflight is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with Cleanflight. If not, see . - */ - -#include - -#include -#include "drivers/io.h" - -#include "drivers/dma.h" -#include "drivers/timer.h" -#include "drivers/timer_def.h" - -const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT] = { - DEF_TIM(TIM3, CH1, PA2, TIM_USE_PPM, 0, 0), // PPM_IN_A - DEF_TIM(TIM3, CH1, PA3, TIM_USE_ANY, 0, 0), // Secondary PPM input PPM_IN_B (user can assign this as he wants) - - DEF_TIM(TIM3, CH3, PA8, TIM_USE_MOTOR, 0, 0), // PPM_OUT_A - DEF_TIM(TIM1, CH2, PE11, TIM_USE_MOTOR, 0, 0), // PPM_OUT_B - DEF_TIM(TIM1, CH3, PE13, TIM_USE_MOTOR, 0, 0), // PPM_OUT_C - DEF_TIM(TIM1, CH4, PE14, TIM_USE_MOTOR, 0, 0), // PPM_OUT_D - DEF_TIM(TIM3, CH3, PB5, TIM_USE_MOTOR, 0, 0), // PPM_OUT_E - DEF_TIM(TIM4, CH2, PD13, TIM_USE_MOTOR, 0, 0), // PPM_OUT_F - DEF_TIM(TIM4, CH3, PD14, TIM_USE_MOTOR, 0, 0), // PPM_OUT_G - DEF_TIM(TIM4, CH4, PD15, TIM_USE_MOTOR, 0, 0), // PPM_OUT_H -}; diff --git a/src/main/target/UAVPNG030MINI/target.h b/src/main/target/UAVPNG030MINI/target.h deleted file mode 100644 index 50f12b89bf..0000000000 --- a/src/main/target/UAVPNG030MINI/target.h +++ /dev/null @@ -1,134 +0,0 @@ -/* - * This is free software: you can redistribute it and/or modify - * it under the terms of the GNU General Public License as published by - * the Free Software Foundation, either version 3 of the License, or - * (at your option) any later version. - * - * This software is distributed in the hope that it will be useful, - * but WITHOUT ANY WARRANTY; without even the implied warranty of - * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the - * GNU General Public License for more details. - * - * You should have received a copy of the GNU General Public License - * along with this software. If not, see . - */ - -#pragma once - -#define TARGET_BOARD_IDENTIFIER "UAVP" - -#define USBD_PRODUCT_STRING "UAVP-NG HW-0.30-mini" - -#define LED0_PIN PE5 -#define LED1_PIN PE7 -#define LED2_PIN PE6 -#define LED3_PIN PE8 - -#define USE_BEEPER -#define BEEPER_PIN PB0 -#define BEEPER_INVERTED - -#define USE_ACC -#define USE_ACC_SPI_MPU6000 - -#define USE_GYRO -#define USE_GYRO_SPI_MPU6000 - -#define GYRO_1_CS_PIN PA4 -#define GYRO_1_SPI_INSTANCE SPI1 - -// TODO -#define GYRO_1_ALIGN CW180_DEG - -// MPU6000 interrupts -#define GYRO_1_EXTI_PIN PE0 - -#define USE_MAG -#define USE_MAG_HMC5883 -#define MAG_HMC5883_ALIGN CW90_DEG -#define MAG_I2C_INSTANCE I2CDEV_2 -#define HMC5883_I2C_INSTANCE I2CDEV_2 -#define MAG_INT_EXTI PE12 -#define USE_MAG_DATA_READY_SIGNAL - -#define USE_BARO -#define USE_BARO_MS5611 -#define USE_BARO_SPI_MS5611 -#define BARO_CS_PIN PE1 -#define BARO_SPI_INSTANCE SPI1 - -#if 0 // TODO: Enable SDCard and blackbox logging -#define ENABLE_BLACKBOX_LOGGING_ON_SDCARD_BY_DEFAULT -#define USE_SDCARD -#define USE_SDCARD_SPI -#define SDCARD_DETECT_INVERTED -#define SDCARD_DETECT_PIN PE2 -#define SDCARD_SPI_INSTANCE SPI2 -#define SDCARD_SPI_CS_PIN SPI2_NSS_PIN -#warning Missing channel for F4/F7 spec dma 1 stream 4; DMA_OPT assumed as 0 -#define SPI2_TX_DMA_OPT 0 // DMA 1 Stream 4 Channel unknown -#endif - -#define USE_VCP -//#define VBUS_SENSING_PIN PC5 - -#define USE_UART1 -#define UART1_RX_PIN PB7 -#define UART1_TX_PIN PB6 - -#define USE_UART2 -#define UART2_RX_PIN PD6 -#define UART2_TX_PIN PD5 - -#define USE_UART3 -#define UART3_RX_PIN PD9 -#define UART3_TX_PIN PD8 - -#define USE_UART6 -#define UART6_RX_PIN PC6 -#define UART6_TX_PIN PC7 - -#define SERIAL_PORT_COUNT 5 //VCP, USART1, USART2, USART3, USART6 - -// TODO -#define USE_ESCSERIAL -#define ESCSERIAL_TIMER_TX_PIN PA2 - -#define USE_SPI -#define USE_SPI_DEVICE_1 -#define SPI1_NSS_PIN PA4 -#define SPI1_SCK_PIN PA5 -#define SPI1_MISO_PIN PA6 -#define SPI1_MOSI_PIN PA7 - -/// I2C Configuration -#define USE_I2C -#define USE_I2C_PULLUP -#define USE_I2C_DEVICE_1 -#define I2C1_SCL PB8 -#define I2C1_SDA PB9 - -#define USE_I2C_DEVICE_2 -#define I2C2_SCL PB10 -#define I2C2_SDA PB11 - -#define I2C_DEVICE (I2CDEV_2) - -#define USE_ADC -#define VBAT_ADC_PIN PC1 -#define DEFAULT_VOLTAGE_METER_SOURCE VOLTAGE_METER_ADC - -#define DEFAULT_RX_FEATURE FEATURE_RX_SERIAL - -#define TARGET_IO_PORTA (0xffff & ~(BIT(0)|BIT(1)|BIT(10)|BIT(13)|BIT(14)|BIT(15))) -#define TARGET_IO_PORTB (0xffff & ~(BIT(2)|BIT(3)|BIT(4))) -#define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) -#define TARGET_IO_PORTD (0xffff & ~(BIT(0)|BIT(1))) -#define TARGET_IO_PORTE (0xffff & ~(BIT(15))) - -#define USABLE_TIMER_CHANNEL_COUNT 10 - -// Used Timers -//#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(12)) -// Defined Timers in timer.c -#define USED_TIMERS ( TIM_N(1) | TIM_N(3) | TIM_N(4)) diff --git a/src/main/target/UAVPNG030MINI/target.mk b/src/main/target/UAVPNG030MINI/target.mk deleted file mode 100644 index 3ecb836a84..0000000000 --- a/src/main/target/UAVPNG030MINI/target.mk +++ /dev/null @@ -1,6 +0,0 @@ -F405_TARGETS += $(TARGET) -FEATURES += VCP -TARGET_SRC = \ - drivers/accgyro/accgyro_spi_mpu6000.c \ - drivers/barometer/barometer_ms5611.c \ - drivers/compass/compass_hmc5883l.c diff --git a/src/test/Makefile b/src/test/Makefile index 992890e95a..03a1c4ab13 100644 --- a/src/test/Makefile +++ b/src/test/Makefile @@ -357,15 +357,13 @@ timer_definition_unittest_EXPAND := yes timer_definition_unittest_BLACKLIST := SITL timer_definition_unittest_SRC = \ - $(TARGET_DIR)/$(call get_base_target,$1)/target.c + $(TARGET_DIR)/$(TARGET)/target.c timer_definition_unittest_DEFINES = \ - TARGET=$1 \ - BASE_TARGET=$(call get_base_target,$1) + TARGET=$1 timer_definition_unittest_INCLUDE_DIRS = \ - $(TEST_DIR)/timer_definition_unittest.include \ - $(TARGET_DIR)/$(call get_base_target,$1) + $(TEST_DIR)/timer_definition_unittest.include transponder_ir_unittest_SRC := \ $(USER_DIR)/drivers/transponder_ir_ilap.c \ @@ -730,7 +728,7 @@ $1_SRC = $(addsuffix .o,$(call $(basename $1)_SRC,$(call target,$1))) $1_OBJS = $$(patsubst \ $(TEST_DIR)/%,$(OBJECT_DIR)/$1/%,$$(patsubst \ $(USER_DIR)/%,$(OBJECT_DIR)/$1/%,$$(patsubst \ - $(TARGET_DIR)/$(call get_base_target,$(call target,$1))/%,$(OBJECT_DIR)/$1/%,$$($1_SRC)))) + $(TARGET_DIR)/$(TARGET)/%,$(OBJECT_DIR)/$1/%,$$($1_SRC)))) $1_DEFINES = $(call $(basename $1)_DEFINES,$(call target,$1)) $1_INCLUDE_DIRS = $(call $(basename $1)_INCLUDE_DIRS,$(call target,$1)) endif @@ -760,7 +758,7 @@ $(OBJECT_DIR)/$1/%.c.o: $(TEST_DIR)/%.c ifneq ($1,$(basename $1)) # per-target tests may compile files from the target directory -$(OBJECT_DIR)/$1/%.c.o: $(TARGET_DIR)/$(call get_base_target,$(call target,$1))/%.c +$(OBJECT_DIR)/$1/%.c.o: $(TARGET_DIR)/$(TARGET)/%.c @echo "compiling target c file: $$<" "$(STDOUT)" $(V1) mkdir -p $$(dir $$@) $(V1) $(CC) $(C_FLAGS) $$(call test_cflags,$$($1_INCLUDE_DIRS)) \ @@ -806,15 +804,5 @@ $(foreach var,$(filter-out TARGET_SRC,$(filter %_SRC,$(.VARIABLES))),$(if $(filt target_list: - @echo ========== BASE TARGETS ========== - @echo $(BASE_TARGETS) - @echo ========== ALT TARGETS ========== - @echo $(ALT_TARGETS) @echo ========== VALID_TARGETS ========== @echo $(VALID_TARGETS) - @echo ========== BASE/ALT PAIRS ========== - @echo $(BASE_ALT_PAIRS) - @echo ========== ALT/BASE MAPPING ========== - @echo $(foreach target,$(ALT_TARGETS),$(target)\>$(call get_base_target,$(target))) - @echo ========== ALT/BASE FULL MAPPING ========== - @echo $(foreach target,$(VALID_TARGETS),$(target)\>$(call get_base_target,$(target)))