From 17b66067bb3715ef65bc772eb72a954d85101d76 Mon Sep 17 00:00:00 2001 From: Andrej Podzimek Date: Mon, 10 Sep 2018 22:56:19 +0200 Subject: [PATCH 1/3] Adding a reusable mapping function between alt and base targets. --- make/targets.mk | 51 ++------------------------------- make/targets_list.mk | 67 ++++++++++++++++++++++++++++++++++++++++++++ 2 files changed, 70 insertions(+), 48 deletions(-) create mode 100644 make/targets_list.mk diff --git a/make/targets.mk b/make/targets.mk index ac2182e9e..99d9ee844 100644 --- a/make/targets.mk +++ b/make/targets.mk @@ -1,58 +1,13 @@ -OFFICIAL_TARGETS = ALIENFLIGHTF3 ALIENFLIGHTF4 ANYFCF7 BETAFLIGHTF3 BLUEJAYF4 FURYF4 REVO SIRINFPV SPARKY SPRACINGF3 SPRACINGF3EVO SPRACINGF3NEO SPRACINGF4EVO SPRACINGF7DUAL STM32F3DISCOVERY -ALT_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.mk))))) -NOBUILD_TARGETS = $(sort $(filter-out target, $(basename $(notdir $(wildcard $(ROOT)/src/main/target/*/*.nomk))))) -OPBL_TARGETS = $(filter %_OPBL, $(ALT_TARGETS)) - -VALID_TARGETS = $(dir $(wildcard $(ROOT)/src/main/target/*/target.mk)) -VALID_TARGETS := $(subst /,, $(subst ./src/main/target/,, $(VALID_TARGETS))) -VALID_TARGETS := $(VALID_TARGETS) $(ALT_TARGETS) -VALID_TARGETS := $(sort $(VALID_TARGETS)) -VALID_TARGETS := $(filter-out $(NOBUILD_TARGETS), $(VALID_TARGETS)) +include $(ROOT)/make/targets_list.mk 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 -UNSUPPORTED_TARGETS := \ - AFROMINI \ - ALIENFLIGHTF1 \ - BEEBRAIN \ - CC3D \ - CC3D_OPBL \ - CJMCU \ - MICROSCISKY \ - NAZE - -SUPPORTED_TARGETS := $(filter-out $(UNSUPPORTED_TARGETS), $(VALID_TARGETS)) - -TARGETS_TOTAL := $(words $(SUPPORTED_TARGETS)) -TARGET_GROUPS := 5 -TARGETS_PER_GROUP := $(shell expr $(TARGETS_TOTAL) / $(TARGET_GROUPS) ) - -ST := 1 -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_1_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) - -ST := $(shell expr $(ET) + 1) -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_2_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) - -ST := $(shell expr $(ET) + 1) -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_3_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) - -ST := $(shell expr $(ET) + 1) -ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) -GROUP_4_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) - -GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS), $(SUPPORTED_TARGETS)) - -ifeq ($(filter $(TARGET),$(ALT_TARGETS)), $(TARGET)) -BASE_TARGET := $(firstword $(subst /,, $(subst ./src/main/target/,, $(dir $(wildcard $(ROOT)/src/main/target/*/$(TARGET).mk))))) +BASE_TARGET := $(call get_base_target,$(TARGET)) +ifneq ($(TARGET),$(BASE_TARGET)) include $(ROOT)/src/main/target/$(BASE_TARGET)/$(TARGET).mk -else -BASE_TARGET := $(TARGET) endif ifeq ($(filter $(TARGET),$(OPBL_TARGETS)), $(TARGET)) diff --git a/make/targets_list.mk b/make/targets_list.mk new file mode 100644 index 000000000..fa2a59a49 --- /dev/null +++ b/make/targets_list.mk @@ -0,0 +1,67 @@ +OFFICIAL_TARGETS = \ + ALIENFLIGHTF3 \ + ALIENFLIGHTF4 \ + ANYFCF7 \ + BETAFLIGHTF3 \ + BLUEJAYF4 \ + FURYF4 REVO \ + SIRINFPV \ + SPARKY \ + SPRACINGF3 \ + SPRACINGF3EVO \ + SPRACINGF3NEO \ + SPRACINGF4EVO \ + SPRACINGF7DUAL \ + STM32F3DISCOVERY + +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))))) +OPBL_TARGETS = $(sort $(filter %_OPBL,$(ALT_TARGETS))) + +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 \ + ALIENFLIGHTF1 \ + BEEBRAIN \ + CC3D \ + CC3D_OPBL \ + CJMCU \ + MICROSCISKY \ + NAZE + +SUPPORTED_TARGETS := $(filter-out $(UNSUPPORTED_TARGETS), $(VALID_TARGETS)) + +TARGETS_TOTAL := $(words $(SUPPORTED_TARGETS)) +TARGET_GROUPS := 5 +TARGETS_PER_GROUP := $(shell expr $(TARGETS_TOTAL) / $(TARGET_GROUPS) ) + +ST := 1 +ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) +GROUP_1_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) + +ST := $(shell expr $(ET) + 1) +ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) +GROUP_2_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) + +ST := $(shell expr $(ET) + 1) +ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) +GROUP_3_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) + +ST := $(shell expr $(ET) + 1) +ET := $(shell expr $(ST) + $(TARGETS_PER_GROUP)) +GROUP_4_TARGETS := $(wordlist $(ST), $(ET), $(SUPPORTED_TARGETS)) + +GROUP_OTHER_TARGETS := $(filter-out $(GROUP_1_TARGETS) $(GROUP_2_TARGETS) $(GROUP_3_TARGETS) $(GROUP_4_TARGETS), $(SUPPORTED_TARGETS)) From 9d553380c3ccbd49ee653d76d78a116d0c21de9f Mon Sep 17 00:00:00 2001 From: Andrej Podzimek Date: Mon, 10 Sep 2018 22:58:01 +0200 Subject: [PATCH 2/3] Adding a per-target unit test for timer metadata consistency. --- src/test/Makefile | 162 ++++++++++++------ src/test/unit/timer_definition_unittest.cc | 103 +++++++++++ .../drivers/dma.h | 0 .../drivers/io.h | 0 .../drivers/timer.h | 21 +++ .../drivers/timer_def.h | 0 .../mock_enums.h | 66 +++++++ .../pg/bus_bst.h | 1 + .../pg/bus_i2c.h | 5 + .../pg/bus_spi.h | 5 + .../platform.h | 5 + 11 files changed, 317 insertions(+), 51 deletions(-) create mode 100644 src/test/unit/timer_definition_unittest.cc create mode 100644 src/test/unit/timer_definition_unittest.include/drivers/dma.h create mode 100644 src/test/unit/timer_definition_unittest.include/drivers/io.h create mode 100644 src/test/unit/timer_definition_unittest.include/drivers/timer.h create mode 100644 src/test/unit/timer_definition_unittest.include/drivers/timer_def.h create mode 100644 src/test/unit/timer_definition_unittest.include/mock_enums.h create mode 100644 src/test/unit/timer_definition_unittest.include/pg/bus_bst.h create mode 100644 src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h create mode 100644 src/test/unit/timer_definition_unittest.include/pg/bus_spi.h create mode 100644 src/test/unit/timer_definition_unittest.include/platform.h diff --git a/src/test/Makefile b/src/test/Makefile index 565b05887..cb83f95e9 100644 --- a/src/test/Makefile +++ b/src/test/Makefile @@ -13,15 +13,19 @@ USER_DIR = ../main TEST_DIR = unit ROOT = ../.. +OBJECT_DIR = ../../obj/test +TARGET_DIR = $(USER_DIR)/target include $(ROOT)/make/system-id.mk +include $(ROOT)/make/targets_list.mk # specify which files that are included in the test in addition to the unittest file. # variables available: # _SRC # _DEFINES # _INCLUDE_DIRS - +# _EXPAND (run for each target, call the above with target as $1) +# _BLACKLIST (targets to exclude from an expanded test's run) alignsensor_unittest_SRC := \ $(USER_DIR)/sensors/boardalignment.c \ @@ -39,9 +43,9 @@ atomic_unittest_SRC := \ $(USER_DIR)/build/atomic.c \ $(TEST_DIR)/atomic_unittest_c.c -baro_bmp085_unittest_SRC := \ - $(USER_DIR)/drivers/barometer/barometer_bmp085.c \ - $(USER_DIR)/drivers/io.c +#baro_bmp085_unittest_SRC := \ +# $(USER_DIR)/drivers/barometer/barometer_bmp085.c \ +# $(USER_DIR)/drivers/io.c baro_bmp280_unittest_SRC := \ @@ -58,9 +62,9 @@ baro_ms5611_unittest_DEFINES := \ USE_BARO_MS5611 \ USE_BARO_SPI_MS5611 -battery_unittest_SRC := \ - $(USER_DIR)/sensors/battery.c \ - $(USER_DIR)/common/maths.c +#battery_unittest_SRC := \ +# $(USER_DIR)/sensors/battery.c \ +# $(USER_DIR)/common/maths.c blackbox_unittest_SRC := \ @@ -265,15 +269,24 @@ telemetry_ibus_unittest_SRC := \ $(USER_DIR)/telemetry/ibus_shared.c \ $(USER_DIR)/telemetry/ibus.c +timer_definition_unittest_EXPAND := yes + +# SITL is a simulator; NERO and STM32F7X2 don't define USED_TIMERS in target.h. +timer_definition_unittest_BLACKLIST := STM32F7X2 SITL NERO + +timer_definition_unittest_SRC = \ + $(TARGET_DIR)/$(call get_base_target,$1)/target.c + +timer_definition_unittest_DEFINES = \ + TARGET=$(call get_base_target,$1) + +timer_definition_unittest_INCLUDE_DIRS = \ + $(TEST_DIR)/timer_definition_unittest.include \ + $(TARGET_DIR)/$(call get_base_target,$1) transponder_ir_unittest_SRC := \ - $(USER_DIR)/drivers/transponder_ir_ilap.c \ - $(USER_DIR)/drivers/transponder_ir_arcitimer.c - - -type_conversion_unittest_SRC := \ - $(USER_DIR)/common/typeconversion.c - + $(USER_DIR)/drivers/transponder_ir_ilap.c \ + $(USER_DIR)/drivers/transponder_ir_arcitimer.c ws2811_unittest_SRC := \ $(USER_DIR)/drivers/light_ws2811strip.c @@ -328,11 +341,6 @@ vtx_unittest_DEFINES := \ # Remember to tweak this if you move this file. GTEST_DIR = ../../lib/test/gtest - -USER_INCLUDE_DIR = $(USER_DIR) - -OBJECT_DIR = ../../obj/test - # Use clang/clang++ by default CC := clang CXX := clang++ @@ -383,8 +391,10 @@ LDFLAGS += -Wl,-T,$(TEST_DIR)/pg.ld -Wl,-Map,$(OBJECT_DIR)/$@.map endif # Gather up all of the tests. -TEST_SRC = $(sort $(wildcard $(TEST_DIR)/*.cc)) -TESTS = $(TEST_SRC:$(TEST_DIR)/%.cc=%) +TEST_SRCS = $(sort $(wildcard $(TEST_DIR)/*.cc)) +TEST_BASENAMES = $(TEST_SRCS:$(TEST_DIR)/%.cc=%) +TESTS = $(foreach test,$(TEST_BASENAMES),$(if $($(test)_EXPAND),$(foreach \ + target,$(filter-out $($(test)_BLACKLIST),$(VALID_TARGETS)),$(test).$(target)),$(test))) # All Google Test headers. Usually you shouldn't change this # definition. @@ -465,69 +475,119 @@ $(OBJECT_DIR)/gtest_main.a : $(OBJECT_DIR)/gtest-all.o $(OBJECT_DIR)/gtest_main. $(OBJECT_DIR)/gtest_main.d -# includes in test dir must override includes in user dir -TEST_INCLUDE_DIRS := $(TEST_DIR) \ - $(USER_INCLUDE_DIR) - -TEST_CFLAGS = $(addprefix -I,$(TEST_INCLUDE_DIRS)) - +# includes in test dir must override includes in user dir, unless the user +# specifies a list of endorsed directories in ${target}_INCLUDE_DIRS. +test_include_dirs = $1 $(TEST_DIR) $(USER_DIR) +test_cflags = $(addprefix -I,$(call test_include_dirs,$1)) +# target name extractor +# param $1 = expanded test name in the form of test.target +target = $(1:$(basename $1).%=%) # canned recipe for all test builds -# param $1 = testname +# +# variable expansion rules of thumb (number of $'s): +# * parameters: one $, e.g. $1 +# * statically accessed variables set elsewhere: one $, e.g. $(C_FLAGS) +# * dynamically accessed variables set elsewhere: one $, e.g. $($1_SRC) +# * make functions accessing only the above: one $, e.g. $(basename $1) +# * dynamically set and accessed variables: two $, e.g. $$($1_OBJS) +# * make functions accessing dynamically set variables: two $, +# e.g. $$(call test_cflags,$$($1_INCLUDE_DIRS)) +# +# param $1 = plain test name for global tests, test.target for per-target tests define test-specific-stuff -$$1_OBJS = $$(patsubst $$(TEST_DIR)%,$$(OBJECT_DIR)/$1%, $$(patsubst $$(USER_DIR)%,$$(OBJECT_DIR)/$1%,$$($1_SRC:=.o))) +ifeq ($1,$(basename $1)) +# standard global test +$1_OBJS = $(patsubst \ + $(TEST_DIR)/%,$(OBJECT_DIR)/$1/%,$(patsubst \ + $(USER_DIR)/%,$(OBJECT_DIR)/$1/%,$($1_SRC:=.o))) +else +# test executed for each target, $1 has the form of test.target +$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)))) +$1_DEFINES = $(call $(basename $1)_DEFINES,$(call target,$1)) +$1_INCLUDE_DIRS = $(call $(basename $1)_INCLUDE_DIRS,$(call target,$1)) +endif # $$(info $1 -v-v-------) -# $$(info $1_SRC: $($1_SRC)) -# $$(info $1_OBJS: $$($$1_OBJS)) +# $$(info $1_SRC: $$($1_SRC)) +# $$(info $1_OBJS: $$($1_OBJS)) # $$(info $1 -^-^-------) - -#include generated dependencies --include $$($$1_OBJS:.o=.d) --include $(OBJECT_DIR)/$1/$1.d - +# include generated dependencies +-include $$($1_OBJS:.o=.d) +-include $(OBJECT_DIR)/$1/$(basename $1).d $(OBJECT_DIR)/$1/%.c.o: $(USER_DIR)/%.c @echo "compiling $$<" "$(STDOUT)" $(V1) mkdir -p $$(dir $$@) - $(V1) $(CC) $(C_FLAGS) $(TEST_CFLAGS) \ - $(foreach def,$($1_INCLUDE_DIRS),-I $(def)) \ - $(foreach def,$($1_DEFINES),-D $(def)) \ + $(V1) $(CC) $(C_FLAGS) $$(call test_cflags,$$($1_INCLUDE_DIRS)) \ + $$(foreach def,$$($1_DEFINES),-D $$(def)) \ -c $$< -o $$@ $(OBJECT_DIR)/$1/%.c.o: $(TEST_DIR)/%.c @echo "compiling test c file: $$<" "$(STDOUT)" $(V1) mkdir -p $$(dir $$@) - $(V1) $(CC) $(C_FLAGS) $(TEST_CFLAGS) \ - $(foreach def,$($1_INCLUDE_DIRS),-I $(def)) \ - $(foreach def,$($1_DEFINES),-D $(def)) \ + $(V1) $(CC) $(C_FLAGS) $$(call test_cflags,$$($1_INCLUDE_DIRS)) \ + $$(foreach def,$$($1_DEFINES),-D $$(def)) \ -c $$< -o $$@ -$(OBJECT_DIR)/$1/$1.o: $(TEST_DIR)/$1.cc +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 + @echo "compiling target c file: $$<" "$(STDOUT)" + $(V1) mkdir -p $$(dir $$@) + $(V1) $(CC) $(C_FLAGS) $$(call test_cflags,$$($1_INCLUDE_DIRS)) \ + $$(foreach def,$$($1_DEFINES),-D $$(def)) \ + -c $$< -o $$@ +endif + +$(OBJECT_DIR)/$1/$(basename $1).o: $(TEST_DIR)/$(basename $1).cc @echo "compiling $$<" "$(STDOUT)" $(V1) mkdir -p $$(dir $$@) - $(V1) $(CXX) $(CXX_FLAGS) $(TEST_CFLAGS) \ - $(foreach def,$($1_INCLUDE_DIRS),-I $(def)) \ - $(foreach def,$($1_DEFINES),-D $(def)) \ + $(V1) $(CXX) $(CXX_FLAGS) $$(call test_cflags,$$($1_INCLUDE_DIRS)) \ + $$(foreach def,$$($1_DEFINES),-D $$(def)) \ -c $$< -o $$@ - -$(OBJECT_DIR)/$1/$1 : $$($$1_OBJS) \ - $(OBJECT_DIR)/$1/$1.o \ +$(OBJECT_DIR)/$1/$(basename $1): $$($1_OBJS) \ + $(OBJECT_DIR)/$1/$(basename $1).o \ $(OBJECT_DIR)/gtest_main.a @echo "linking $$@" "$(STDOUT)" $(V1) mkdir -p $(dir $$@) $(V1) $(CXX) $(CXX_FLAGS) $(LDFLAGS) $$^ -o $$@ -test_$1: $(OBJECT_DIR)/$1/$1 +test_$1: $(OBJECT_DIR)/$1/$(basename $1) $(V1) $$< $$(EXEC_OPTS) "$(STDOUT)" && echo "running $$@: PASS" endef -#apply the canned recipe above to all tests + $(eval $(foreach test,$(TESTS),$(call test-specific-stuff,$(test)))) + +$(foreach test,$(TESTS),$(if $($(basename $(test))_SRC),,$(error \ + Test 'unit/$(basename $(test)).cc' has no '$(basename $(test))_SRC' variable defined))) +$(foreach var,$(filter-out TARGET_SRC,$(filter %_SRC,$(.VARIABLES))),$(if $(filter $(var:_SRC=)%,$(TESTS)),,$(error \ + Variable '$(var)' has no 'unit/$(var:_SRC=).cc' test))) + + +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))) + diff --git a/src/test/unit/timer_definition_unittest.cc b/src/test/unit/timer_definition_unittest.cc new file mode 100644 index 000000000..41acd81b9 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.cc @@ -0,0 +1,103 @@ +/* + * This file is part of Betaflight. + * + * Betaflight 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. + * + * Betaflight is distributed in the hope that it will be useful, + * but WITHOUT ANY WARRANTY; without even the implied warranty of + * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the + * GNU General Public License for more details. + * + * You should have received a copy of the GNU General Public License + * along with Betaflight. If not, see . + */ + +extern "C" { + #include + #include + extern const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT]; +} + +#include +#include +#include +#include +#include +#include "gtest/gtest.h" + +TEST(TimerDefinitionTest, Test_counterMismatch) { + for (const timerHardware_t &t : timerHardware) + ASSERT_EQ(&t - timerHardware, t.def_tim_counter) + << "Counter mismatch in timerHardware (in target.c) at position " + << &t - timerHardware << "; the array may have uninitialized " + << "trailing elements. This happens when USABLE_TIMER_CHANNEL_COUNT" + << " is not equal to the number of array initializers. Current " + << "value is " << USABLE_TIMER_CHANNEL_COUNT << ", last initialized" + << " array element appears to be " << &t - timerHardware - 1 << '.'; +} + +TEST(TimerDefinitionTest, Test_duplicatePin) { + std::set usedPins; + for (const timerHardware_t &t : timerHardware) + EXPECT_TRUE(usedPins.emplace(t.pin).second) + << "Pin " << TEST_PIN_NAMES[t.pin] << " is used more than once. " + << "This is a problem with the timerHardware array (in target.c). " + << "Check the array for typos. Then check the size of the array " + << "initializers; it must be USABLE_TIMER_CHANNEL_COUNT."; + EXPECT_EQ(USABLE_TIMER_CHANNEL_COUNT, usedPins.size()); +} + +namespace { +std::string writeUsedTimers(const std::bitset &tset) { + std::stringstream used_timers; + if (tset.any()) { + unsigned int timer{0}; + for (; timer < TEST_TIMER_SIZE; ++timer) + if (tset[timer]) { + used_timers << "( TIM_N(" << timer << ')'; + break; + } + for (++timer; timer < TEST_TIMER_SIZE; ++timer) + if (tset[timer]) used_timers << " | TIM_N(" << timer << ')'; + used_timers << " )"; + } else { + used_timers << "(0)"; + } + return used_timers.str(); +} +} + +TEST(TimerDefinitionTest, Test_usedTimers) +{ + std::bitset expected; + for (const timerHardware_t &t : timerHardware) + expected |= TIM_N(t.timer); + const std::bitset actual{USED_TIMERS}; + EXPECT_EQ(expected, actual) + << "Used timers mismatch. target.c says " << expected << ", but " + << "target.h says " << actual << ". This has two possible causes: " + << "(1) The USED_TIMERS bitmap (in target.h) is outdated and out of " + << "sync with timerHardware (in target.c). (2) There is an " + << "inconsistency between USABLE_TIMER_CHANNEL_COUNT and the length " + << "of timerHardware's initializer list."; + std::cerr + << "USED_TIMERS definition based on timerHardware:" << std::endl + << writeUsedTimers(expected) << std::endl; +} + +// STUBS + +extern "C" { + void spiPinConfigure(int) {} + int spiPinConfig(int) { return 0; } + void spiInit(int) {} + + int i2cConfig(int) { return 0; } + void i2cHardwareConfigure(int) {} + void i2cInit(int) {} + + void bstInit(int) {} +} diff --git a/src/test/unit/timer_definition_unittest.include/drivers/dma.h b/src/test/unit/timer_definition_unittest.include/drivers/dma.h new file mode 100644 index 000000000..e69de29bb diff --git a/src/test/unit/timer_definition_unittest.include/drivers/io.h b/src/test/unit/timer_definition_unittest.include/drivers/io.h new file mode 100644 index 000000000..e69de29bb diff --git a/src/test/unit/timer_definition_unittest.include/drivers/timer.h b/src/test/unit/timer_definition_unittest.include/drivers/timer.h new file mode 100644 index 000000000..2becfe977 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/drivers/timer.h @@ -0,0 +1,21 @@ +#include + +typedef struct timerHardware_s { + enum TestTimerEnum timer; + enum TestChannelEnum channel; + enum TestPinEnum pin; + enum TestTimUseEnum purpose; + unsigned int def_tim_counter; +} timerHardware_t; + +// F7 and F4 have 6 arguments, F3 and F1 have 5 arguments. +#define DEF_TIM(timer_, channel_, pin_, purpose_, ...) \ +{ \ + .timer = timer_, \ + .channel = channel_, \ + .pin = pin_, \ + .purpose = purpose_, \ + .def_tim_counter = __COUNTER__, \ +} + +#define TIM_N(n) (1 << (n)) diff --git a/src/test/unit/timer_definition_unittest.include/drivers/timer_def.h b/src/test/unit/timer_definition_unittest.include/drivers/timer_def.h new file mode 100644 index 000000000..e69de29bb diff --git a/src/test/unit/timer_definition_unittest.include/mock_enums.h b/src/test/unit/timer_definition_unittest.include/mock_enums.h new file mode 100644 index 000000000..782aefce1 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/mock_enums.h @@ -0,0 +1,66 @@ +#pragma once + +enum TestTimerEnum { + TIM0, TIM1, TIM2, TIM3, TIM4, TIM5, TIM6, TIM7, TIM8, TIM9, + TIM10, TIM11, TIM12, TIM13, TIM14, TIM15, TIM16, TIM17, TIM18, TIM19, TIM20, + TEST_TIMER_SIZE, +}; + +enum TestChannelEnum { + CH0, CH1, CH2, CH3, CH4, CH5, CH6, CH7, CH9, CH10, CH1N, CH2N, CH3N, + TEST_CHANNEL_SIZE, +}; + +// Keep this in sync with TEST_PIN_NAMES below. +enum TestPinEnum { + PA0, PA1, PA2, PA3, PA4, PA5, PA6, PA7, PA8, PA9, + PA10, PA11, PA12, PA13, PA14, PA15, + PB0, PB1, PB2, PB3, PB4, PB5, PB6, PB7, PB8, PB9, + PB10, PB11, PB12, PB13, PB14, PB15, + PC0, PC1, PC2, PC3, PC4, PC5, PC6, PC7, PC8, PC9, + PC10, PC11, PC12, PC13, PC14, PC15, + PD0, PD1, PD2, PD3, PD4, PD5, PD6, PD7, PD8, PD9, + PD10, PD11, PD12, PD13, PD14, PD15, + PE0, PE1, PE2, PE3, PE4, PE5, PE6, PE7, PE8, PE9, + PE10, PE11, PE12, PE13, PE14, PE15, + PF0, PF1, PF2, PF3, PF4, PF5, PF6, PF7, PF8, PF9, + PF10, PF11, PF12, PF13, PF14, PF15, + PG0, PG1, PG2, PG3, PG4, PG5, PG6, PG7, PG8, PG9, + PG10, PG11, PG12, PG13, PG14, PG15, + PH0, PH1, PH2, PH3, PH4, PH5, PH6, PH7, PH8, PH9, + PH10, PH11, PH12, PH13, PH14, PH15, TEST_PIN_SIZE, +}; + +// Keep this in sync with TestPinEnum above. +const char *const TEST_PIN_NAMES[TEST_PIN_SIZE] = { + "PA0", "PA1", "PA2", "PA3", "PA4", "PA5", "PA6", "PA7", "PA8", "PA9", + "PA10", "PA11", "PA12", "PA13", "PA14", "PA15", + "PB0", "PB1", "PB2", "PB3", "PB4", "PB5", "PB6", "PB7", "PB8", "PB9", + "PB10", "PB11", "PB12", "PB13", "PB14", "PB15", + "PC0", "PC1", "PC2", "PC3", "PC4", "PC5", "PC6", "PC7", "PC8", "PC9", + "PC10", "PC11", "PC12", "PC13", "PC14", "PC15", + "PD0", "PD1", "PD2", "PD3", "PD4", "PD5", "PD6", "PD7", "PD8", "PD9", + "PD10", "PD11", "PD12", "PD13", "PD14", "PD15", + "PE0", "PE1", "PE2", "PE3", "PE4", "PE5", "PE6", "PE7", "PE8", "PE9", + "PE10", "PE11", "PE12", "PE13", "PE14", "PE15", + "PF0", "PF1", "PF2", "PF3", "PF4", "PF5", "PF6", "PF7", "PF8", "PF9", + "PF10", "PF11", "PF12", "PF13", "PF14", "PF15", + "PG0", "PG1", "PG2", "PG3", "PG4", "PG5", "PG6", "PG7", "PG8", "PG9", + "PG10", "PG11", "PG12", "PG13", "PG14", "PG15", + "PH0", "PH1", "PH2", "PH3", "PH4", "PH5", "PH6", "PH7", "PH8", "PH9", + "PH10", "PH11", "PH12", "PH13", "PH14", "PH15", +}; + +enum TestTimUseEnum { + TIM_USE_ANY, + TIM_USE_BEEPER, + TIM_USE_CAMERA_CONTROL, + TIM_USE_LED, + TIM_USE_MOTOR, + TIM_USE_NONE, + TIM_USE_PPM, + TIM_USE_PWM, + TIM_USE_SERVO, + TIM_USE_TRANSPONDER, + TEST_TIM_USE_SIZE, +}; diff --git a/src/test/unit/timer_definition_unittest.include/pg/bus_bst.h b/src/test/unit/timer_definition_unittest.include/pg/bus_bst.h new file mode 100644 index 000000000..7b40e9d91 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/pg/bus_bst.h @@ -0,0 +1 @@ +void bstInit(int); diff --git a/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h b/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h new file mode 100644 index 000000000..b822be69b --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/pg/bus_i2c.h @@ -0,0 +1,5 @@ +#define I2CDEV_2 (1) + +int i2cConfig(int); +void i2cHardwareConfigure(int); +void i2cInit(int); diff --git a/src/test/unit/timer_definition_unittest.include/pg/bus_spi.h b/src/test/unit/timer_definition_unittest.include/pg/bus_spi.h new file mode 100644 index 000000000..910d373e6 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/pg/bus_spi.h @@ -0,0 +1,5 @@ +#define SPIDEV_1 (0) + +void spiPinConfigure(int); +int spiPinConfig(int); +void spiInit(int); diff --git a/src/test/unit/timer_definition_unittest.include/platform.h b/src/test/unit/timer_definition_unittest.include/platform.h new file mode 100644 index 000000000..c4fbc3046 --- /dev/null +++ b/src/test/unit/timer_definition_unittest.include/platform.h @@ -0,0 +1,5 @@ +#include +#include "target/common_pre.h" +#include "target.h" +#include "target/common_post.h" +#include "target/common_defaults_post.h" From c96c735430f6b266958de0616bd65b54a9c57ef3 Mon Sep 17 00:00:00 2001 From: Andrej Podzimek Date: Mon, 10 Sep 2018 22:54:33 +0200 Subject: [PATCH 3/3] Fixing mismatches in USED_TIMERS definitions. --- src/main/target/AIKONF4/target.h | 2 +- src/main/target/AIR32/target.h | 2 +- src/main/target/AIRHEROF3/target.h | 2 +- src/main/target/ALIENFLIGHTF3/target.h | 2 +- src/main/target/ANYFCF7/target.h | 2 +- src/main/target/BEEROTORF4/target.h | 2 +- src/main/target/BETAFLIGHTF3/target.h | 2 +- src/main/target/BLUEJAYF4/target.h | 2 +- src/main/target/COLIBRI_RACE/target.h | 2 +- src/main/target/CRAZYBEEF3FR/target.h | 2 +- src/main/target/CRAZYFLIE2/target.h | 4 ++-- src/main/target/DOGE/target.h | 2 +- src/main/target/F4BY/target.h | 2 +- src/main/target/FRSKYF3/target.h | 2 +- src/main/target/FRSKYF4/target.h | 2 +- src/main/target/HAKRCF722/target.h | 2 +- src/main/target/IRCFUSIONF3/target.h | 2 +- src/main/target/KISSFC/target.h | 2 +- src/main/target/KISSFCV2F7/target.h | 2 +- src/main/target/KIWIF4/target.h | 4 ++-- src/main/target/LUX_RACE/target.h | 3 ++- src/main/target/MOTOLAB/target.h | 2 +- src/main/target/NUCLEOF446RE/target.h | 4 ++-- src/main/target/NUCLEOF7/target.h | 4 ++-- src/main/target/NUCLEOF722/target.h | 4 ++-- src/main/target/OMNIBUSF4/target.h | 2 +- src/main/target/OMNIBUSF4FW/target.h | 4 ++++ src/main/target/OMNINXT/target.h | 2 +- src/main/target/RACEBASE/target.h | 2 +- src/main/target/RCEXPLORERF3/target.h | 2 +- src/main/target/REVOLT/target.h | 4 ++-- src/main/target/RG_SSD_F3/target.h | 2 +- src/main/target/SINGULARITY/target.h | 2 +- src/main/target/SPARKY/target.h | 2 +- src/main/target/SPARKY2/target.h | 2 +- src/main/target/SPRACINGF4EVO/target.h | 6 +----- src/main/target/SPRACINGF4NEO/target.h | 4 ++++ src/main/target/STM32F4DISCOVERY/target.h | 2 +- src/main/target/VRRACE/target.h | 2 +- src/main/target/WORMFC/target.h | 2 +- src/main/target/X_RACERSPI/target.h | 4 ++-- src/main/target/YUPIF7/target.h | 2 +- 42 files changed, 56 insertions(+), 51 deletions(-) diff --git a/src/main/target/AIKONF4/target.h b/src/main/target/AIKONF4/target.h index 728c51b98..93a5b40b2 100644 --- a/src/main/target/AIKONF4/target.h +++ b/src/main/target/AIKONF4/target.h @@ -141,5 +141,5 @@ #define TARGET_IO_PORTC ( BIT(12) | BIT(11) | BIT(10) | BIT(9) | BIT(8) | BIT(7) | BIT(6) | BIT(4) | BIT(3) | BIT(2) | BIT(1) | BIT(0) ) #define TARGET_IO_PORTD ( BIT(2) ) -#define USABLE_TIMER_CHANNEL_COUNT 16 +#define USABLE_TIMER_CHANNEL_COUNT 13 #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/AIR32/target.h b/src/main/target/AIR32/target.h index 182954485..fd673bc86 100644 --- a/src/main/target/AIR32/target.h +++ b/src/main/target/AIR32/target.h @@ -110,4 +110,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/AIRHEROF3/target.h b/src/main/target/AIRHEROF3/target.h index f0304fcd7..9b5295aa1 100644 --- a/src/main/target/AIRHEROF3/target.h +++ b/src/main/target/AIRHEROF3/target.h @@ -100,4 +100,4 @@ #define TARGET_IO_PORTF (BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 14 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) diff --git a/src/main/target/ALIENFLIGHTF3/target.h b/src/main/target/ALIENFLIGHTF3/target.h index 900531574..15adf8e8e 100644 --- a/src/main/target/ALIENFLIGHTF3/target.h +++ b/src/main/target/ALIENFLIGHTF3/target.h @@ -130,4 +130,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/ANYFCF7/target.h b/src/main/target/ANYFCF7/target.h index ef9fc4e30..336824640 100644 --- a/src/main/target/ANYFCF7/target.h +++ b/src/main/target/ANYFCF7/target.h @@ -169,4 +169,4 @@ #define TARGET_IO_PORTD 0xffff #define TARGET_IO_PORTE 0xffff -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) | TIM_N(12) ) diff --git a/src/main/target/BEEROTORF4/target.h b/src/main/target/BEEROTORF4/target.h index bb5592055..946035030 100644 --- a/src/main/target/BEEROTORF4/target.h +++ b/src/main/target/BEEROTORF4/target.h @@ -162,4 +162,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/BETAFLIGHTF3/target.h b/src/main/target/BETAFLIGHTF3/target.h index f7267ad9d..c8fa27628 100644 --- a/src/main/target/BETAFLIGHTF3/target.h +++ b/src/main/target/BETAFLIGHTF3/target.h @@ -157,4 +157,4 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/BLUEJAYF4/target.h b/src/main/target/BLUEJAYF4/target.h index b346aefda..c3ab86170 100644 --- a/src/main/target/BLUEJAYF4/target.h +++ b/src/main/target/BLUEJAYF4/target.h @@ -175,4 +175,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 8 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) ) diff --git a/src/main/target/COLIBRI_RACE/target.h b/src/main/target/COLIBRI_RACE/target.h index cd4ddbce9..f6312ee5e 100644 --- a/src/main/target/COLIBRI_RACE/target.h +++ b/src/main/target/COLIBRI_RACE/target.h @@ -138,4 +138,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 12 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15) | TIM_N(16)) diff --git a/src/main/target/CRAZYBEEF3FR/target.h b/src/main/target/CRAZYBEEF3FR/target.h index 7c59e745f..0cbad7eae 100644 --- a/src/main/target/CRAZYBEEF3FR/target.h +++ b/src/main/target/CRAZYBEEF3FR/target.h @@ -142,4 +142,4 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 4 -#define USED_TIMERS (TIM_N(2) | TIM_N(8) | TIM_N(15)) +#define USED_TIMERS (TIM_N(2) | TIM_N(8)) diff --git a/src/main/target/CRAZYFLIE2/target.h b/src/main/target/CRAZYFLIE2/target.h index c98588c1e..477e816a7 100644 --- a/src/main/target/CRAZYFLIE2/target.h +++ b/src/main/target/CRAZYFLIE2/target.h @@ -37,11 +37,11 @@ #define USBD_PRODUCT_STRING "Crazyflie 2.0" #endif -#define USABLE_TIMER_CHANNEL_COUNT 14 - #if defined(CRAZYFLIE2BQ) +#define USABLE_TIMER_CHANNEL_COUNT 5 #define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(14) ) #else +#define USABLE_TIMER_CHANNEL_COUNT 4 #define USED_TIMERS ( TIM_N(2) | TIM_N(4) ) #endif diff --git a/src/main/target/DOGE/target.h b/src/main/target/DOGE/target.h index d2ce79589..e59cad300 100644 --- a/src/main/target/DOGE/target.h +++ b/src/main/target/DOGE/target.h @@ -140,4 +140,4 @@ // channel mapping in drivers/pwm_mapping.c // only 6 outputs available on hardware #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(16)) diff --git a/src/main/target/F4BY/target.h b/src/main/target/F4BY/target.h index d6c976487..d2416e1f2 100644 --- a/src/main/target/F4BY/target.h +++ b/src/main/target/F4BY/target.h @@ -159,4 +159,4 @@ #define TARGET_IO_PORTE 0xffff #define USABLE_TIMER_CHANNEL_COUNT 17 -#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) |TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(9) ) diff --git a/src/main/target/FRSKYF3/target.h b/src/main/target/FRSKYF3/target.h index 08057eedb..74edfd3f3 100644 --- a/src/main/target/FRSKYF3/target.h +++ b/src/main/target/FRSKYF3/target.h @@ -165,4 +165,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 9 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8)) diff --git a/src/main/target/FRSKYF4/target.h b/src/main/target/FRSKYF4/target.h index 708f0732e..fd9f15e69 100644 --- a/src/main/target/FRSKYF4/target.h +++ b/src/main/target/FRSKYF4/target.h @@ -130,4 +130,4 @@ #define TARGET_IO_PORTD BIT(2) #define USABLE_TIMER_CHANNEL_COUNT 13 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) ) diff --git a/src/main/target/HAKRCF722/target.h b/src/main/target/HAKRCF722/target.h index d13a23220..1cb231f3e 100755 --- a/src/main/target/HAKRCF722/target.h +++ b/src/main/target/HAKRCF722/target.h @@ -143,4 +143,4 @@ #define TARGET_IO_PORTD 0xffff #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1)|TIM_N(2)|TIM_N(3)|TIM_N(4)|TIM_N(8)|TIM_N(12)) +#define USED_TIMERS (TIM_N(1) | TIM_N(3 ) |TIM_N(4) | TIM_N(8) | TIM_N(12)) diff --git a/src/main/target/IRCFUSIONF3/target.h b/src/main/target/IRCFUSIONF3/target.h index 21c9a500e..a36b9fd4d 100644 --- a/src/main/target/IRCFUSIONF3/target.h +++ b/src/main/target/IRCFUSIONF3/target.h @@ -112,4 +112,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 17 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/KISSFC/target.h b/src/main/target/KISSFC/target.h index c043b4a75..abb1d3a04 100644 --- a/src/main/target/KISSFC/target.h +++ b/src/main/target/KISSFC/target.h @@ -112,4 +112,4 @@ #define TARGET_IO_PORTF (BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(17)) diff --git a/src/main/target/KISSFCV2F7/target.h b/src/main/target/KISSFCV2F7/target.h index b50f8c03f..c92c962a0 100644 --- a/src/main/target/KISSFCV2F7/target.h +++ b/src/main/target/KISSFCV2F7/target.h @@ -114,4 +114,4 @@ #define USABLE_TIMER_CHANNEL_COUNT 8 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) +#define USED_TIMERS ( TIM_N(2) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) diff --git a/src/main/target/KIWIF4/target.h b/src/main/target/KIWIF4/target.h index 4a69c7d76..0a97194b9 100644 --- a/src/main/target/KIWIF4/target.h +++ b/src/main/target/KIWIF4/target.h @@ -182,6 +182,6 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 12 +#define USABLE_TIMER_CHANNEL_COUNT 5 -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(9) ) +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/LUX_RACE/target.h b/src/main/target/LUX_RACE/target.h index fba843d81..85790a023 100644 --- a/src/main/target/LUX_RACE/target.h +++ b/src/main/target/LUX_RACE/target.h @@ -177,7 +177,8 @@ #ifdef LUXV2_RACE #define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS (TIM_N(1) | TIM_N(3) | TIM_N(8) | TIM_N(16)) #else #define USABLE_TIMER_CHANNEL_COUNT 12 +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15) | TIM_N(16)) #endif -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(15)) diff --git a/src/main/target/MOTOLAB/target.h b/src/main/target/MOTOLAB/target.h index 034b571f9..10667e889 100644 --- a/src/main/target/MOTOLAB/target.h +++ b/src/main/target/MOTOLAB/target.h @@ -107,4 +107,4 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/NUCLEOF446RE/target.h b/src/main/target/NUCLEOF446RE/target.h index e55ee0763..b9d8c5e2f 100644 --- a/src/main/target/NUCLEOF446RE/target.h +++ b/src/main/target/NUCLEOF446RE/target.h @@ -174,5 +174,5 @@ #define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) #define TARGET_IO_PORTD BIT(2) -#define USABLE_TIMER_CHANNEL_COUNT 12 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) ) +#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/NUCLEOF7/target.h b/src/main/target/NUCLEOF7/target.h index a11dbc444..e01daeb22 100644 --- a/src/main/target/NUCLEOF7/target.h +++ b/src/main/target/NUCLEOF7/target.h @@ -58,7 +58,7 @@ #define USE_FAKE_BARO #define USE_BARO_MS5611 -#define USABLE_TIMER_CHANNEL_COUNT 16 +#define USABLE_TIMER_CHANNEL_COUNT 11 #define USE_VCP #define USE_USB_DETECT @@ -158,4 +158,4 @@ #define TARGET_IO_PORTF 0xffff #define TARGET_IO_PORTG 0xffff -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) +#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/NUCLEOF722/target.h b/src/main/target/NUCLEOF722/target.h index b91770509..327961e86 100644 --- a/src/main/target/NUCLEOF722/target.h +++ b/src/main/target/NUCLEOF722/target.h @@ -58,7 +58,7 @@ #define USE_FAKE_BARO #define USE_BARO_MS5611 -#define USABLE_TIMER_CHANNEL_COUNT 11 +#define USABLE_TIMER_CHANNEL_COUNT 9 #define USE_VCP #define USE_USB_DETECT @@ -164,4 +164,4 @@ #define TARGET_IO_PORTE 0xffff #define TARGET_IO_PORTF 0xffff -#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) +#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/OMNIBUSF4/target.h b/src/main/target/OMNIBUSF4/target.h index f726e4fd8..82439e110 100644 --- a/src/main/target/OMNIBUSF4/target.h +++ b/src/main/target/OMNIBUSF4/target.h @@ -282,5 +282,5 @@ #define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(10) | TIM_N(12) | TIM_N(8) | TIM_N(9)) #else #define USABLE_TIMER_CHANNEL_COUNT 14 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12) ) #endif diff --git a/src/main/target/OMNIBUSF4FW/target.h b/src/main/target/OMNIBUSF4FW/target.h index 902fbcbcd..4e8a3c409 100644 --- a/src/main/target/OMNIBUSF4FW/target.h +++ b/src/main/target/OMNIBUSF4FW/target.h @@ -178,5 +178,9 @@ #define TARGET_IO_PORTC (0xffff & ~(BIT(15)|BIT(14)|BIT(13))) #define TARGET_IO_PORTD BIT(2) +#if defined(OMNIBUSF4FW) || defined(OMNIBUSF4FW1) #define USABLE_TIMER_CHANNEL_COUNT 15 +#else +#define USABLE_TIMER_CHANNEL_COUNT 14 +#endif #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(10) | TIM_N(11)) diff --git a/src/main/target/OMNINXT/target.h b/src/main/target/OMNINXT/target.h index 60f859de6..6863cf1c6 100644 --- a/src/main/target/OMNINXT/target.h +++ b/src/main/target/OMNINXT/target.h @@ -197,5 +197,5 @@ #define TARGET_IO_PORTC (0xffff) #define TARGET_IO_PORTD BIT(2) -#define USABLE_TIMER_CHANNEL_COUNT 22 +#define USABLE_TIMER_CHANNEL_COUNT 21 #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(10) | TIM_N(11) | TIM_N(12)) diff --git a/src/main/target/RACEBASE/target.h b/src/main/target/RACEBASE/target.h index 0116fdcf2..b0dccb5a8 100644 --- a/src/main/target/RACEBASE/target.h +++ b/src/main/target/RACEBASE/target.h @@ -144,4 +144,4 @@ #endif #define USABLE_TIMER_CHANNEL_COUNT 6 -#define USED_TIMERS (TIM_N(2) | TIM_N(3)| TIM_N(4) | TIM_N(8) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2)| TIM_N(3) | TIM_N(8) | TIM_N(17)) diff --git a/src/main/target/RCEXPLORERF3/target.h b/src/main/target/RCEXPLORERF3/target.h index f2ff549e9..b63dda846 100644 --- a/src/main/target/RCEXPLORERF3/target.h +++ b/src/main/target/RCEXPLORERF3/target.h @@ -133,4 +133,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 7 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/REVOLT/target.h b/src/main/target/REVOLT/target.h index 129dc1588..eff9a5d64 100644 --- a/src/main/target/REVOLT/target.h +++ b/src/main/target/REVOLT/target.h @@ -171,5 +171,5 @@ #define TARGET_IO_PORTC 0xffff #define TARGET_IO_PORTD (BIT(2)) -#define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS ( TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(11) ) +#define USABLE_TIMER_CHANNEL_COUNT 6 +#define USED_TIMERS ( TIM_N(2) | TIM_N(4) | TIM_N(8) | TIM_N(11) ) diff --git a/src/main/target/RG_SSD_F3/target.h b/src/main/target/RG_SSD_F3/target.h index c58ab907e..bb5ebe463 100644 --- a/src/main/target/RG_SSD_F3/target.h +++ b/src/main/target/RG_SSD_F3/target.h @@ -146,6 +146,6 @@ #define TARGET_IO_PORTD (BIT(2)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) -#define USED_TIMERS (TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(16)) #define USABLE_TIMER_CHANNEL_COUNT 9 diff --git a/src/main/target/SINGULARITY/target.h b/src/main/target/SINGULARITY/target.h index 7f251a178..4a65c293d 100644 --- a/src/main/target/SINGULARITY/target.h +++ b/src/main/target/SINGULARITY/target.h @@ -105,5 +105,5 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 10 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) |TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) |TIM_N(17)) diff --git a/src/main/target/SPARKY/target.h b/src/main/target/SPARKY/target.h index eddbc4f51..dcf8e4443 100644 --- a/src/main/target/SPARKY/target.h +++ b/src/main/target/SPARKY/target.h @@ -107,4 +107,4 @@ #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(4)) #define USABLE_TIMER_CHANNEL_COUNT 11 -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(17)) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(15) | TIM_N(16) | TIM_N(17)) diff --git a/src/main/target/SPARKY2/target.h b/src/main/target/SPARKY2/target.h index 2c073e0df..f6d429ede 100644 --- a/src/main/target/SPARKY2/target.h +++ b/src/main/target/SPARKY2/target.h @@ -132,4 +132,4 @@ #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(12) | TIM_N(8) | TIM_N(9)) +#define USED_TIMERS ( TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(8) | TIM_N(12)) diff --git a/src/main/target/SPRACINGF4EVO/target.h b/src/main/target/SPRACINGF4EVO/target.h index da7b608f0..fd032fd86 100644 --- a/src/main/target/SPRACINGF4EVO/target.h +++ b/src/main/target/SPRACINGF4EVO/target.h @@ -218,14 +218,10 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 16 // 4xPWM, 8xESC, 2xESC via UART3 RX/TX, 1xLED Strip, 1xIR. -#if (SPRACINGF4NEO_REV >= 2) +#if (SPRACINGF4EVO_REV >= 2) #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9)) #else #define USE_TIM10_TIM11_FOR_MOTORS -#ifdef USE_TIM10_TIM11_FOR_MOTORS #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9) | TIM_N(10) | TIM_N(11)) -#else -#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(9)) -#endif #endif diff --git a/src/main/target/SPRACINGF4NEO/target.h b/src/main/target/SPRACINGF4NEO/target.h index c97aa92d4..e59ffa10e 100644 --- a/src/main/target/SPRACINGF4NEO/target.h +++ b/src/main/target/SPRACINGF4NEO/target.h @@ -224,4 +224,8 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 14 // 4xPWM, 6xESC, 2xESC via UART3 RX/TX, 1xLED Strip, 1xIR. +#if (SPRACINGF4NEO_REV >= 3) +#define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(4) | TIM_N(8) | TIM_N(9)) +#else #define USED_TIMERS (TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(8) | TIM_N(9)) +#endif diff --git a/src/main/target/STM32F4DISCOVERY/target.h b/src/main/target/STM32F4DISCOVERY/target.h index 269a7bb39..03a19e29a 100644 --- a/src/main/target/STM32F4DISCOVERY/target.h +++ b/src/main/target/STM32F4DISCOVERY/target.h @@ -124,4 +124,4 @@ #define TARGET_IO_PORTD 0xffff #define USABLE_TIMER_CHANNEL_COUNT 7 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/VRRACE/target.h b/src/main/target/VRRACE/target.h index 338d7bedd..f56545c00 100644 --- a/src/main/target/VRRACE/target.h +++ b/src/main/target/VRRACE/target.h @@ -172,4 +172,4 @@ #define TARGET_IO_PORTE 0xffff #define USABLE_TIMER_CHANNEL_COUNT 12 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(5) | TIM_N(12) | TIM_N(8) | TIM_N(9) ) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(9) ) diff --git a/src/main/target/WORMFC/target.h b/src/main/target/WORMFC/target.h index 9646f0615..6b5b02353 100644 --- a/src/main/target/WORMFC/target.h +++ b/src/main/target/WORMFC/target.h @@ -136,4 +136,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 7 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8)) +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) ) diff --git a/src/main/target/X_RACERSPI/target.h b/src/main/target/X_RACERSPI/target.h index 767c5ce4a..7f6d04d00 100644 --- a/src/main/target/X_RACERSPI/target.h +++ b/src/main/target/X_RACERSPI/target.h @@ -124,5 +124,5 @@ #define TARGET_IO_PORTC (BIT(13)|BIT(14)|BIT(15)) #define TARGET_IO_PORTF (BIT(0)|BIT(1)|BIT(3)|BIT(4)) -#define USABLE_TIMER_CHANNEL_COUNT 17 -#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) +#define USABLE_TIMER_CHANNEL_COUNT 15 +#define USED_TIMERS ( TIM_N(1) | TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(8) | TIM_N(15) | TIM_N(16) | TIM_N(17) ) diff --git a/src/main/target/YUPIF7/target.h b/src/main/target/YUPIF7/target.h index ba90a91cf..fe806c86b 100644 --- a/src/main/target/YUPIF7/target.h +++ b/src/main/target/YUPIF7/target.h @@ -145,4 +145,4 @@ #define TARGET_IO_PORTD (BIT(2)) #define USABLE_TIMER_CHANNEL_COUNT 9 -#define USED_TIMERS (TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12)) +#define USED_TIMERS (TIM_N(2) | TIM_N(3) | TIM_N(4) | TIM_N(5) | TIM_N(8) | TIM_N(12))