1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 16:25:31 +03:00

Merge branch 'master' of https://github.com/betaflight/betaflight into motor-diag

# Conflicts:
#	src/main/io/osd.c
#	src/main/io/osd.h
#	src/test/unit/osd_unittest.cc
This commit is contained in:
Maciej Janowski 2018-10-29 21:16:24 +01:00
commit 9656dbba40
840 changed files with 15513 additions and 10766 deletions

View file

@ -13,22 +13,27 @@
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:
# <test_name>_SRC
# <test_name>_DEFINES
# <test_name>_INCLUDE_DIRS
# <test_name>_EXPAND (run for each target, call the above with target as $1)
# <test_name>_BLACKLIST (targets to exclude from an expanded test's run)
alignsensor_unittest_SRC := \
$(USER_DIR)/sensors/boardalignment.c \
$(USER_DIR)/common/maths.c
arming_prevention_unittest_SRC := \
$(USER_DIR)/fc/fc_core.c \
$(USER_DIR)/fc/fc_dispatch.c \
$(USER_DIR)/fc/core.c \
$(USER_DIR)/fc/dispatch.c \
$(USER_DIR)/fc/rc_controls.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/fc/runtime_config.c \
@ -38,9 +43,12 @@ 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
# This test is disabled due to build errors.
# Its source code is archived in unit/baro_bmp085_unittest.cc.txt
#
#baro_bmp085_unittest_SRC := \
# $(USER_DIR)/drivers/barometer/barometer_bmp085.c \
# $(USER_DIR)/drivers/io.c
baro_bmp280_unittest_SRC := \
@ -57,9 +65,12 @@ baro_ms5611_unittest_DEFINES := \
USE_BARO_MS5611 \
USE_BARO_SPI_MS5611
battery_unittest_SRC := \
$(USER_DIR)/sensors/battery.c \
$(USER_DIR)/common/maths.c
# This test is disabled due to build errors.
# Its source code is archived in unit/battery_unittest.cc.txt
#
#battery_unittest_SRC := \
# $(USER_DIR)/sensors/battery.c \
# $(USER_DIR)/common/maths.c
blackbox_unittest_SRC := \
@ -217,7 +228,8 @@ sensor_gyro_unittest_SRC := \
$(USER_DIR)/common/maths.c \
$(USER_DIR)/drivers/accgyro/accgyro_fake.c \
$(USER_DIR)/drivers/accgyro/gyro_sync.c \
$(USER_DIR)/pg/pg.c
$(USER_DIR)/pg/pg.c \
$(USER_DIR)/pg/gyrodev.c
telemetry_crsf_unittest_SRC := \
$(USER_DIR)/rx/crsf.c \
@ -264,15 +276,26 @@ telemetry_ibus_unittest_SRC := \
$(USER_DIR)/telemetry/ibus_shared.c \
$(USER_DIR)/telemetry/ibus.c
timer_definition_unittest_EXPAND := yes
# NERO and STM32F7X2 are universal targets with dynamic timer management.
# SITL is a simulator with empty timerHardware and many hearders in target.c.
timer_definition_unittest_BLACKLIST := NERO SITL STM32F7X2
timer_definition_unittest_SRC = \
$(TARGET_DIR)/$(call get_base_target,$1)/target.c
timer_definition_unittest_DEFINES = \
TARGET=$1 \
BASE_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
@ -289,7 +312,6 @@ rcdevice_unittest_SRC := \
$(USER_DIR)/common/bitarray.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/io/rcdevice.c \
$(USER_DIR)/io/rcdevice_osd.c \
$(USER_DIR)/io/rcdevice_cam.c \
pid_unittest_SRC := \
@ -300,9 +322,31 @@ pid_unittest_SRC := \
$(USER_DIR)/pg/pg.c \
$(USER_DIR)/fc/runtime_config.c
pid_unittest_DEFINES := \
USE_ITERM_RELAX \
USE_RC_SMOOTHING_FILTER \
USE_ABSOLUTE_CONTROL
rcdevice_unittest_DEFINES := \
USE_RCDEVICE
vtx_unittest_SRC := \
$(USER_DIR)/fc/core.c \
$(USER_DIR)/fc/dispatch.c \
$(USER_DIR)/fc/rc_controls.c \
$(USER_DIR)/fc/rc_modes.c \
$(USER_DIR)/fc/runtime_config.c \
$(USER_DIR)/drivers/vtx_common.c \
$(USER_DIR)/io/vtx_control.c \
$(USER_DIR)/io/vtx_string.c \
$(USER_DIR)/io/vtx.c \
$(USER_DIR)/common/bitarray.c
vtx_unittest_DEFINES := \
USE_VTX_COMMON \
USE_VTX_CONTROL \
USE_VTX_SMARTAUDIO
# Please tweak the following variable definitions as needed by your
# project, except GTEST_HEADERS, which you can use in your own targets
# but shouldn't modify.
@ -311,11 +355,6 @@ rcdevice_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++
@ -366,8 +405,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.
@ -448,66 +489,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_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_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_DEFINES),-D $(def)) \
-c $$< -o $$@
$(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)))

View file

@ -27,7 +27,7 @@ extern "C" {
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/fc_core.h"
#include "fc/core.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
@ -612,11 +612,55 @@ TEST(ArmingPreventionTest, WhenUsingSwitched3DModeThenNormalThrottleArmingCondit
EXPECT_EQ(0, getArmingDisableFlags());
}
TEST(ArmingPreventionTest, ParalyzeOnAtBoot)
{
// given
simulationFeatureFlags = 0;
simulationTime = 0;
gyroCalibDone = true;
// and
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
modeActivationConditionsMutable(0)->modeId = BOXARM;
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(1750);
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MAX);
modeActivationConditionsMutable(1)->auxChannelIndex = 1;
modeActivationConditionsMutable(1)->modeId = BOXPARALYZE;
modeActivationConditionsMutable(1)->range.startStep = CHANNEL_VALUE_TO_STEP(1750);
modeActivationConditionsMutable(1)->range.endStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MAX);
useRcControlsConfig(NULL);
// and
rxConfigMutable()->mincheck = 1050;
// given
rcData[THROTTLE] = 1000;
rcData[AUX1] = 1000;
rcData[AUX2] = 1800; // Paralyze on at boot
ENABLE_STATE(SMALL_ANGLE);
// when
updateActivatedModes();
updateArmingStatus();
// expect
EXPECT_FALSE(ARMING_FLAG(ARMED));
EXPECT_FALSE(isArmingDisabled());
EXPECT_EQ(0, getArmingDisableFlags());
EXPECT_FALSE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
// when
updateActivatedModes();
// expect
EXPECT_FALSE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
}
TEST(ArmingPreventionTest, Paralyze)
{
// given
simulationFeatureFlags = 0;
simulationTime = 30e6; // 30 seconds after boot
simulationTime = 0;
gyroCalibDone = true;
// and
@ -632,10 +676,8 @@ TEST(ArmingPreventionTest, Paralyze)
modeActivationConditionsMutable(2)->modeId = BOXBEEPERON;
modeActivationConditionsMutable(2)->range.startStep = CHANNEL_VALUE_TO_STEP(1750);
modeActivationConditionsMutable(2)->range.endStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MAX);
modeActivationConditionsMutable(3)->auxChannelIndex = 3;
modeActivationConditionsMutable(3)->modeId = BOXVTXPITMODE;
modeActivationConditionsMutable(3)->range.startStep = CHANNEL_VALUE_TO_STEP(1750);
modeActivationConditionsMutable(3)->range.endStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MAX);
modeActivationConditionsMutable(3)->linkedTo = BOXPARALYZE;
useRcControlsConfig(NULL);
// and
@ -644,9 +686,8 @@ TEST(ArmingPreventionTest, Paralyze)
// given
rcData[THROTTLE] = 1000;
rcData[AUX1] = 1000;
rcData[AUX2] = 1000;
rcData[AUX2] = 1800; // Start out with paralyze enabled
rcData[AUX3] = 1000;
rcData[AUX4] = 1000;
ENABLE_STATE(SMALL_ANGLE);
// when
@ -685,11 +726,29 @@ TEST(ArmingPreventionTest, Paralyze)
EXPECT_FALSE(ARMING_FLAG(ARMED));
EXPECT_FALSE(isArmingDisabled());
EXPECT_EQ(0, getArmingDisableFlags());
EXPECT_FALSE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
// given
// paraylze and enter pit mode
simulationTime = 10e6; // 10 seconds after boot
// when
updateActivatedModes();
// expect
EXPECT_FALSE(ARMING_FLAG(ARMED));
EXPECT_FALSE(isArmingDisabled());
EXPECT_EQ(0, getArmingDisableFlags());
EXPECT_FALSE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
// given
// disable paralyze once after the startup timer
rcData[AUX2] = 1000;
// when
updateActivatedModes();
// enable paralyze again
rcData[AUX2] = 1800;
rcData[AUX4] = 1800;
// when
updateActivatedModes();
@ -698,15 +757,12 @@ TEST(ArmingPreventionTest, Paralyze)
// expect
EXPECT_TRUE(isArmingDisabled());
EXPECT_EQ(ARMING_DISABLED_PARALYZE, getArmingDisableFlags());
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXVTXPITMODE));
EXPECT_FALSE(IS_RC_MODE_ACTIVE(BOXBEEPERON));
// and
preventModeChanges();
// given
// Try exiting pit mode and enable beeper
rcData[AUX4] = 1000;
// enable beeper
rcData[AUX3] = 1800;
// when
@ -717,7 +773,7 @@ TEST(ArmingPreventionTest, Paralyze)
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXBEEPERON));
// given
// exit paralyze mode and ensure arming is still disabled
// try exiting paralyze mode and ensure arming and pit mode are still disabled
rcData[AUX2] = 1000;
// when
@ -727,6 +783,8 @@ TEST(ArmingPreventionTest, Paralyze)
// expect
EXPECT_TRUE(isArmingDisabled());
EXPECT_EQ(ARMING_DISABLED_PARALYZE, getArmingDisableFlags());
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXPARALYZE));
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXVTXPITMODE));
}
// STUBS
@ -735,7 +793,7 @@ extern "C" {
uint32_t millis(void) { return micros() / 1000; }
bool rxIsReceivingSignal(void) { return simulationHaveRx; }
bool feature(uint32_t f) { return simulationFeatureFlags & f; }
bool featureIsEnabled(uint32_t f) { return simulationFeatureFlags & f; }
void warningLedFlash(void) {}
void warningLedDisable(void) {}
void warningLedUpdate(void) {}
@ -765,7 +823,7 @@ extern "C" {
void failsafeStartMonitoring(void) {}
void failsafeUpdateState(void) {}
bool failsafeIsActive(void) { return false; }
void pidResetITerm(void) {}
void pidResetIterm(void) {}
void updateAdjustmentStates(void) {}
void processRcAdjustments(controlRateConfig_t *) {}
void updateGpsWaypointsAndMode(void) {}
@ -792,4 +850,5 @@ extern "C" {
void rescheduleTask(cfTaskId_e, uint32_t) {}
bool usbCableIsInserted(void) { return false; }
bool usbVcpIsConnected(void) { return false; }
void pidSetAntiGravityState(bool) {}
}

View file

@ -273,7 +273,7 @@ uint8_t armingFlags = 0;
float rcCommand[4] = {0,0,0,0};
bool feature(uint32_t mask)
bool featureIsEnabled(uint32_t mask)
{
UNUSED(mask);
return false;

View file

@ -388,7 +388,7 @@ bool sensors(uint32_t) {return false;}
void serialWrite(serialPort_t *, uint8_t) {}
uint32_t serialTxBytesFree(const serialPort_t *) {return 0;}
bool isSerialTransmitBufferEmpty(const serialPort_t *) {return false;}
bool feature(uint32_t) {return false;}
bool featureIsEnabled(uint32_t) {return false;}
void mspSerialReleasePortIfAllocated(serialPort_t *) {}
serialPortConfig_t *findSerialPortConfig(serialPortFunction_e ) {return NULL;}
serialPort_t *findSharedSerialPort(uint16_t , serialPortFunction_e ) {return NULL;}
@ -398,5 +398,6 @@ portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunctio
failsafePhase_e failsafePhase(void) {return FAILSAFE_IDLE;}
bool rxAreFlightChannelsValid(void) {return false;}
bool rxIsReceivingSignal(void) {return false;}
bool isRssiConfigured(void) {return false;}
}

View file

@ -210,6 +210,7 @@ uint8_t getCurrentControlRateProfileIndex(void){ return 1; }
void changeControlRateProfile(uint8_t) {}
void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *) {}
void writeEEPROM() {}
void writeEEPROMWithFeatures(uint32_t) {}
serialPortConfig_t *serialFindPortConfiguration(serialPortIdentifier_e) {return NULL; }
baudRate_e lookupBaudRateIndex(uint32_t){return BAUD_9600; }
serialPortUsage_t *findSerialPortUsageByIdentifier(serialPortIdentifier_e){ return NULL; }
@ -240,6 +241,7 @@ const char *armingDisableFlagNames[]= {
void getTaskInfo(cfTaskId_e, cfTaskInfo_t *) {}
void getCheckFuncInfo(cfCheckFuncInfo_t *) {}
void schedulerResetTaskMaxExecutionTime(cfTaskId_e) {}
const char * const targetName = "UNITTEST";
const char* const buildDate = "Jan 01 2017";
@ -280,4 +282,6 @@ bool boardInformationIsSet(void) { return true; };
bool setBoardName(char *newBoardName) { UNUSED(newBoardName); return true; };
bool setManufacturerId(char *newManufacturerId) { UNUSED(newManufacturerId); return true; };
bool persistBoardInformation(void) { return true; };
void activeAdjustmentRangeReset(void) {}
}

View file

@ -555,6 +555,11 @@ uint32_t millis(void)
return sysTickUptime;
}
uint32_t micros(void)
{
return millis() * 1000;
}
throttleStatus_e calculateThrottleStatus()
{
return throttleStatus;
@ -562,7 +567,7 @@ throttleStatus_e calculateThrottleStatus()
void delay(uint32_t) {}
bool feature(uint32_t mask) {
bool featureIsEnabled(uint32_t mask) {
return (mask & testFeatureMask);
}

View file

@ -243,4 +243,5 @@ void performBaroCalibrationCycle(void) {}
int32_t baroCalculateAltitude(void) { return 0; }
bool gyroGetAccumulationAverage(float *) { return false; }
bool accGetAccumulationAverage(float *) { return false; }
void mixerSetThrottleAngleCorrection(int) {};
}

View file

@ -392,7 +392,7 @@ uint8_t armingFlags;
void delay(uint32_t) {}
bool feature(uint32_t mask) {
bool featureIsEnabled(uint32_t mask) {
return (mask & testFeatureMask);
}

View file

@ -352,7 +352,7 @@ void delay(uint32_t ms)
uint32_t micros(void) { return 0; }
bool shouldSoundBatteryAlarm(void) { return false; }
bool feature(uint32_t mask) {
bool featureIsEnabled(uint32_t mask) {
UNUSED(mask);
return false;
}

View file

@ -26,6 +26,7 @@ extern "C" {
#include "build/debug.h"
#include "blackbox/blackbox.h"
#include "blackbox/blackbox_io.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
@ -37,7 +38,7 @@ extern "C" {
#include "drivers/serial.h"
#include "fc/config.h"
#include "fc/fc_core.h"
#include "fc/core.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
@ -45,9 +46,11 @@ extern "C" {
#include "flight/pid.h"
#include "flight/imu.h"
#include "io/beeper.h"
#include "io/gps.h"
#include "io/osd.h"
#include "sensors/acceleration.h"
#include "sensors/battery.h"
#include "rx/rx.h"
@ -56,7 +59,7 @@ extern "C" {
void osdRefresh(timeUs_t currentTimeUs);
void osdFormatTime(char * buff, osd_timer_precision_e precision, timeUs_t time);
void osdFormatTimer(char *buff, bool showSymbol, int timerIndex);
int osdConvertTemperatureToSelectedUnit(int tempInDeciDegrees);
int osdConvertTemperatureToSelectedUnit(int tempInDegreesCelcius);
uint16_t rssi;
attitudeEulerAngles_t attitude;
@ -73,6 +76,9 @@ extern "C" {
float motorOutputLow = 1000;
acc_t acc;
float accAverage[XYZ_AXIS_COUNT];
PG_REGISTER(batteryConfig_t, batteryConfig, PG_BATTERY_CONFIG, 0);
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
@ -303,6 +309,9 @@ TEST(OsdTest, TestStatsImperial)
osdStatSetState(OSD_STAT_RTC_DATE_TIME, true);
osdStatSetState(OSD_STAT_MAX_DISTANCE, true);
osdStatSetState(OSD_STAT_BLACKBOX_NUMBER, false);
osdStatSetState(OSD_STAT_MAX_G_FORCE, false);
osdStatSetState(OSD_STAT_MAX_ESC_TEMP, false);
osdStatSetState(OSD_STAT_MAX_ESC_RPM, false);
// and
// using imperial unit system
@ -937,11 +946,15 @@ TEST(OsdTest, TestConvertTemperatureUnits)
{
/* In Celsius */
osdConfigMutable()->units = OSD_UNIT_METRIC;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(330), 330);
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(40), 40);
/* In Fahrenheit */
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(330), 914);
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(40), 104);
/* In Fahrenheit with rounding */
osdConfigMutable()->units = OSD_UNIT_IMPERIAL;
EXPECT_EQ(osdConvertTemperatureToSelectedUnit(41), 106);
}
// STUBS
@ -968,7 +981,7 @@ extern "C" {
return false;
}
bool isAirmodeActive() {
bool airmodeIsEnabled() {
return false;
}
@ -1004,7 +1017,7 @@ extern "C" {
return simulationMahDrawn;
}
int32_t getEstimatedAltitude() {
int32_t getEstimatedAltitudeCm() {
return simulationAltitude;
}
@ -1016,6 +1029,14 @@ extern "C" {
return 0;
}
bool isBlackboxDeviceWorking() {
return true;
}
bool isBlackboxDeviceFull() {
return false;
}
bool isSerialTransmitBufferEmpty(const serialPort_t *) {
return false;
}
@ -1039,4 +1060,6 @@ extern "C" {
float pidItermAccelerator(void) { return 1.0; }
uint8_t getMotorCount(void){ return 4; }
bool areMotorsRunning(void){ return true; }
bool pidOsdAntiGravityActive(void) { return false; }
bool failsafeIsActive(void) { return false; }
}

View file

@ -24,7 +24,7 @@
#include "gtest/gtest.h"
#include "build/debug.h"
bool simulateMixerSaturated = false;
bool simulatedAirmodeEnabled = true;
float simulatedSetpointRate[3] = { 0,0,0 };
float simulatedRcDeflection[3] = { 0,0,0 };
float simulatedThrottlePIDAttenuation = 1.0f;
@ -46,8 +46,8 @@ extern "C" {
#include "drivers/sound_beeper.h"
#include "drivers/time.h"
#include "fc/fc_core.h"
#include "fc/fc_rc.h"
#include "fc/core.h"
#include "fc/rc.h"
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
@ -67,7 +67,7 @@ extern "C" {
float getThrottlePIDAttenuation(void) { return simulatedThrottlePIDAttenuation; }
float getMotorMixRange(void) { return simulatedMotorMixRange; }
float getSetpointRate(int axis) { return simulatedSetpointRate[axis]; }
bool mixerIsOutputSaturated(int, float) { return simulateMixerSaturated; }
bool isAirmodeActivated() { return simulatedAirmodeEnabled; }
float getRcDeflectionAbs(int axis) { return ABS(simulatedRcDeflection[axis]); }
void systemBeep(bool) { }
bool gyroOverflowDetected(void) { return false; }
@ -84,10 +84,10 @@ int loopIter = 0;
void setDefaultTestSettings(void) {
pgResetAll();
pidProfile = pidProfilesMutable(1);
pidProfile->pid[PID_ROLL] = { 40, 40, 30 };
pidProfile->pid[PID_PITCH] = { 58, 50, 35 };
pidProfile->pid[PID_YAW] = { 70, 45, 20 };
pidProfile->pid[PID_LEVEL] = { 50, 50, 75 };
pidProfile->pid[PID_ROLL] = { 40, 40, 30, 65 };
pidProfile->pid[PID_PITCH] = { 58, 50, 35, 60 };
pidProfile->pid[PID_YAW] = { 70, 45, 20, 60 };
pidProfile->pid[PID_LEVEL] = { 50, 50, 75, 0 };
pidProfile->pidSumLimit = PIDSUM_LIMIT;
pidProfile->pidSumLimitYaw = PIDSUM_LIMIT_YAW;
@ -101,11 +101,11 @@ void setDefaultTestSettings(void) {
pidProfile->vbatPidCompensation = 0;
pidProfile->pidAtMinThrottle = PID_STABILISATION_ON;
pidProfile->levelAngleLimit = 55;
pidProfile->setpointRelaxRatio = 100;
pidProfile->dtermSetpointWeight = 0;
pidProfile->feedForwardTransition = 100;
pidProfile->yawRateAccelLimit = 100;
pidProfile->rateAccelLimit = 0;
pidProfile->itermThrottleThreshold = 350;
pidProfile->antiGravityMode = ANTI_GRAVITY_SMOOTH;
pidProfile->itermThrottleThreshold = 250;
pidProfile->itermAcceleratorGain = 1000;
pidProfile->crash_time = 500;
pidProfile->crash_delay = 0;
@ -122,6 +122,11 @@ void setDefaultTestSettings(void) {
pidProfile->throttle_boost = 0;
pidProfile->throttle_boost_cutoff = 15;
pidProfile->iterm_rotation = false;
pidProfile->smart_feedforward = false,
pidProfile->iterm_relax = ITERM_RELAX_OFF,
pidProfile->iterm_relax_cutoff = 11,
pidProfile->iterm_relax_type = ITERM_RELAX_SETPOINT,
pidProfile->abs_control_gain = 0,
gyro.targetLooptime = 4000;
}
@ -132,7 +137,6 @@ timeUs_t currentTestTime(void) {
void resetTest(void) {
loopIter = 0;
simulateMixerSaturated = false;
simulatedThrottlePIDAttenuation = 1.0f;
simulatedMotorMixRange = 0.0f;
@ -144,6 +148,7 @@ void resetTest(void) {
pidData[axis].P = 0;
pidData[axis].I = 0;
pidData[axis].D = 0;
pidData[axis].F = 0;
pidData[axis].Sum = 0;
simulatedSetpointRate[axis] = 0;
simulatedRcDeflection[axis] = 0;
@ -266,7 +271,15 @@ TEST(pidControllerTest, testPidLoop) {
ASSERT_NEAR(-8.7, pidData[FD_YAW].I, calculateTolerance(-8.7));
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
ASSERT_NEAR(-132.25, pidData[FD_YAW].D, calculateTolerance(-132.25));
// Simulate Iterm behaviour during mixer saturation
simulatedMotorMixRange = 1.2f;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
ASSERT_NEAR(-23.5, pidData[FD_ROLL].I, calculateTolerance(-23.5));
ASSERT_NEAR(19.6, pidData[FD_PITCH].I, calculateTolerance(19.6));
ASSERT_NEAR(-8.8, pidData[FD_YAW].I, calculateTolerance(-8.8));
simulatedMotorMixRange = 0;
// Match the stick to gyro to stop error
simulatedSetpointRate[FD_ROLL] = 100;
@ -276,14 +289,13 @@ TEST(pidControllerTest, testPidLoop) {
for(int loop = 0; loop < 5; loop++) {
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
}
// Iterm is stalled as it is not accumulating anymore
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].P);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].P);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
ASSERT_NEAR(-23.5, pidData[FD_ROLL].I, calculateTolerance(-23.5));
ASSERT_NEAR(19.6, pidData[FD_PITCH].I, calculateTolerance(19.6));
ASSERT_NEAR(-10.6, pidData[FD_YAW].I, calculateTolerance(-10.5));
ASSERT_NEAR(-10.6, pidData[FD_YAW].I, calculateTolerance(-10.6));
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
@ -312,53 +324,42 @@ TEST(pidControllerTest, testPidLevel) {
// Test Angle mode response
enableFlightMode(ANGLE_MODE);
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
float currentPidSetpoint = 30;
rollAndPitchTrims_t angleTrim = { { 0, 0 } };
// Loop 1
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].P);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].P);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
currentPidSetpoint = pidLevel(FD_ROLL, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
currentPidSetpoint = pidLevel(FD_PITCH, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
// Test attitude response
setStickPosition(FD_ROLL, 1.0f);
setStickPosition(FD_PITCH, -1.0f);
attitude.values.roll = 550;
attitude.values.pitch = -550;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
currentPidSetpoint = pidLevel(FD_ROLL, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(275, currentPidSetpoint);
currentPidSetpoint = pidLevel(FD_PITCH, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(-275, currentPidSetpoint);
// Loop 2
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].P);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].P);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
setStickPosition(FD_ROLL, -0.5f);
setStickPosition(FD_PITCH, 0.5f);
currentPidSetpoint = pidLevel(FD_ROLL, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(-137.5, currentPidSetpoint);
currentPidSetpoint = pidLevel(FD_PITCH, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(137.5, currentPidSetpoint);
// Disable ANGLE_MODE on full stick inputs
attitude.values.roll = -275;
attitude.values.pitch = 275;
currentPidSetpoint = pidLevel(FD_ROLL, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
currentPidSetpoint = pidLevel(FD_PITCH, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
// Disable ANGLE_MODE
disableFlightMode(ANGLE_MODE);
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
// Expect full rate output
ASSERT_NEAR(2559.8, pidData[FD_ROLL].P, calculateTolerance(2559.8));
ASSERT_NEAR(-3711.6, pidData[FD_PITCH].P, calculateTolerance(-3711.6));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
ASSERT_NEAR(150, pidData[FD_ROLL].I, calculateTolerance(150));
ASSERT_NEAR(-150, pidData[FD_PITCH].I, calculateTolerance(-150));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
currentPidSetpoint = pidLevel(FD_ROLL, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
currentPidSetpoint = pidLevel(FD_PITCH, pidProfile, &angleTrim, currentPidSetpoint);
EXPECT_FLOAT_EQ(0, currentPidSetpoint);
}
@ -368,51 +369,21 @@ TEST(pidControllerTest, testPidHorizon) {
pidStabilisationState(PID_STABILISATION_ON);
enableFlightMode(HORIZON_MODE);
// Loop 1
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].P);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].P);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
// Test full stick response
setStickPosition(FD_ROLL, 1.0f);
setStickPosition(FD_PITCH, -1.0f);
attitude.values.roll = 550;
attitude.values.pitch = -550;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
EXPECT_FLOAT_EQ(0, calcHorizonLevelStrength());
// Expect full rate output on full stick
ASSERT_NEAR(2559.8, pidData[FD_ROLL].P, calculateTolerance(2559.8));
ASSERT_NEAR(-3711.6, pidData[FD_PITCH].P, calculateTolerance(-3711.6));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
ASSERT_NEAR(150, pidData[FD_ROLL].I, calculateTolerance(150));
ASSERT_NEAR(-150, pidData[FD_PITCH].I, calculateTolerance(-150));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
// Test zero stick response
setStickPosition(FD_ROLL, 0);
setStickPosition(FD_PITCH, 0);
EXPECT_FLOAT_EQ(1, calcHorizonLevelStrength());
// Test full stick response
// Test small stick response
setStickPosition(FD_ROLL, 0.1f);
setStickPosition(FD_PITCH, -0.1f);
attitude.values.roll = 536;
attitude.values.pitch = -536;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
ASSERT_NEAR(0.75, pidData[FD_ROLL].P, calculateTolerance(0.75));
ASSERT_NEAR(-1.09, pidData[FD_PITCH].P, calculateTolerance(-1.09));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
ASSERT_NEAR(150, pidData[FD_ROLL].I, calculateTolerance(150));
ASSERT_NEAR(-150, pidData[FD_PITCH].I, calculateTolerance(-150));
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].D);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].D);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
ASSERT_NEAR(0.82, calcHorizonLevelStrength(), calculateTolerance(0.82));
}
TEST(pidControllerTest, testMixerSaturation) {
@ -423,14 +394,41 @@ TEST(pidControllerTest, testMixerSaturation) {
// Test full stick response
setStickPosition(FD_ROLL, 1.0f);
setStickPosition(FD_PITCH, -1.0f);
simulateMixerSaturated = true;
setStickPosition(FD_YAW, 1.0f);
simulatedMotorMixRange = 2.0f;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
// Expect no iterm accumulation
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].P);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].I);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].I);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].I);
// Test itermWindup limit
// First store values without exceeding iterm windup limit
resetTest();
ENABLE_ARMING_FLAG(ARMED);
pidStabilisationState(PID_STABILISATION_ON);
setStickPosition(FD_ROLL, 0.1f);
setStickPosition(FD_PITCH, -0.1f);
setStickPosition(FD_YAW, 0.1f);
simulatedMotorMixRange = 0.0f;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
float rollTestIterm = pidData[FD_ROLL].I;
float pitchTestIterm = pidData[FD_PITCH].I;
float yawTestIterm = pidData[FD_YAW].I;
// Now compare values when exceeding the limit
resetTest();
ENABLE_ARMING_FLAG(ARMED);
pidStabilisationState(PID_STABILISATION_ON);
setStickPosition(FD_ROLL, 0.1f);
setStickPosition(FD_PITCH, -0.1f);
setStickPosition(FD_YAW, 0.1f);
simulatedMotorMixRange = (pidProfile->itermWindupPointPercent + 1) / 100.0f;
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
ASSERT_LT(pidData[FD_ROLL].I, rollTestIterm);
ASSERT_GE(pidData[FD_PITCH].I, pitchTestIterm);
ASSERT_LT(pidData[FD_YAW].I, yawTestIterm);
}
// TODO - Add more scenarios
@ -458,8 +456,155 @@ TEST(pidControllerTest, testCrashRecoveryMode) {
// Add additional verifications
}
TEST(pidControllerTest, pidSetpointTransition) {
// TODO
TEST(pidControllerTest, testFeedForward) {
resetTest();
ENABLE_ARMING_FLAG(ARMED);
pidStabilisationState(PID_STABILISATION_ON);
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].F);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].F);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
// Match the stick to gyro to stop error
setStickPosition(FD_ROLL, 1.0f);
setStickPosition(FD_PITCH, -1.0f);
setStickPosition(FD_YAW, -1.0f);
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
ASSERT_NEAR(2232.78, pidData[FD_ROLL].F, calculateTolerance(2232.78));
ASSERT_NEAR(-2061.03, pidData[FD_PITCH].F, calculateTolerance(-2061.03));
ASSERT_NEAR(-82.52, pidData[FD_YAW].F, calculateTolerance(-82.5));
// Match the stick to gyro to stop error
setStickPosition(FD_ROLL, 0.5f);
setStickPosition(FD_PITCH, -0.5f);
setStickPosition(FD_YAW, -0.5f);
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
ASSERT_NEAR(-558.20, pidData[FD_ROLL].F, calculateTolerance(-558.20));
ASSERT_NEAR(515.26, pidData[FD_PITCH].F, calculateTolerance(515.26));
ASSERT_NEAR(-41.26, pidData[FD_YAW].F, calculateTolerance(-41.26));
for (int loop =0; loop <= 15; loop++) {
gyro.gyroADCf[FD_ROLL] += gyro.gyroADCf[FD_ROLL];
pidController(pidProfile, &rollAndPitchTrims, currentTestTime());
}
EXPECT_FLOAT_EQ(0, pidData[FD_ROLL].F);
EXPECT_FLOAT_EQ(0, pidData[FD_PITCH].F);
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
}
TEST(pidControllerTest, testItermRelax) {
resetTest();
pidProfile->iterm_relax = ITERM_RELAX_RP;
ENABLE_ARMING_FLAG(ARMED);
pidStabilisationState(PID_STABILISATION_ON);
pidProfile->iterm_relax_type = ITERM_RELAX_SETPOINT;
pidInit(pidProfile);
float itermErrorRate = 0;
float currentPidSetpoint = 0;
float gyroRate = 0;
applyItermRelax(FD_PITCH, 0, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, 0);
itermErrorRate = -10;
currentPidSetpoint = 10;
pidData[FD_PITCH].I = 10;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
ASSERT_NEAR(-6.66, itermErrorRate, calculateTolerance(-6.66));
currentPidSetpoint += ITERM_RELAX_SETPOINT_THRESHOLD;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, 0);
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, 0);
pidProfile->iterm_relax_type = ITERM_RELAX_GYRO;
pidInit(pidProfile);
currentPidSetpoint = 100;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, 0);
gyroRate = 10;
itermErrorRate = -10;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
ASSERT_NEAR(7, itermErrorRate, calculateTolerance(7));
gyroRate += 100;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
ASSERT_NEAR(-10, itermErrorRate, calculateTolerance(-10));
pidProfile->iterm_relax = ITERM_RELAX_RP_INC;
pidInit(pidProfile);
itermErrorRate = -10;
pidData[FD_PITCH].I = 10;
currentPidSetpoint = 10;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, -10);
itermErrorRate = 10;
pidData[FD_PITCH].I = -10;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, 10);
itermErrorRate = -10;
currentPidSetpoint = 10;
applyItermRelax(FD_PITCH, pidData[FD_PITCH].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, -100);
pidProfile->iterm_relax_type = ITERM_RELAX_SETPOINT;
pidInit(pidProfile);
itermErrorRate = -10;
currentPidSetpoint = ITERM_RELAX_SETPOINT_THRESHOLD;
applyItermRelax(FD_YAW, pidData[FD_YAW].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
EXPECT_FLOAT_EQ(itermErrorRate, -10);
pidProfile->iterm_relax = ITERM_RELAX_RPY;
pidInit(pidProfile);
applyItermRelax(FD_YAW, pidData[FD_YAW].I, gyroRate, &itermErrorRate, &currentPidSetpoint);
ASSERT_NEAR(-3.6, itermErrorRate, calculateTolerance(-3.6));
}
// TODO - Add more tests
TEST(pidControllerTest, testAbsoluteControl) {
resetTest();
pidProfile->abs_control_gain = 10;
pidInit(pidProfile);
ENABLE_ARMING_FLAG(ARMED);
pidStabilisationState(PID_STABILISATION_ON);
float gyroRate = 0;
bool itermRelaxIsEnabled = false;
float setpointLpf = 6;
float setpointHpf = 30;
float itermErrorRate = 10;
float currentPidSetpoint = 10;
applyAbsoluteControl(FD_PITCH, gyroRate, itermRelaxIsEnabled, setpointLpf, setpointHpf,
&currentPidSetpoint, &itermErrorRate);
ASSERT_NEAR(10.8, itermErrorRate, calculateTolerance(10.8));
ASSERT_NEAR(10.8, currentPidSetpoint, calculateTolerance(10.8));
itermRelaxIsEnabled = true;
applyAbsoluteControl(FD_PITCH, gyroRate, itermRelaxIsEnabled, setpointLpf, setpointHpf,
&currentPidSetpoint, &itermErrorRate);
ASSERT_NEAR(10.8, itermErrorRate, calculateTolerance(10.8));
ASSERT_NEAR(10.8, currentPidSetpoint, calculateTolerance(10.8));
gyroRate = -53;
axisError[FD_PITCH] = -60;
applyAbsoluteControl(FD_PITCH, gyroRate, itermRelaxIsEnabled, setpointLpf, setpointHpf,
&currentPidSetpoint, &itermErrorRate);
ASSERT_NEAR(-79.2, itermErrorRate, calculateTolerance(-79.2));
ASSERT_NEAR(-79.2, currentPidSetpoint, calculateTolerance(-79.2));
}
TEST(pidControllerTest, testDtermFiltering) {
@ -467,5 +612,43 @@ TEST(pidControllerTest, testDtermFiltering) {
}
TEST(pidControllerTest, testItermRotationHandling) {
// TODO
resetTest();
pidInit(pidProfile);
rotateItermAndAxisError();
EXPECT_FLOAT_EQ(pidData[FD_ROLL].I, 0);
EXPECT_FLOAT_EQ(pidData[FD_PITCH].I, 0);
EXPECT_FLOAT_EQ(pidData[FD_YAW].I, 0);
pidProfile->iterm_rotation = true;
pidInit(pidProfile);
rotateItermAndAxisError();
EXPECT_FLOAT_EQ(pidData[FD_ROLL].I, 0);
EXPECT_FLOAT_EQ(pidData[FD_PITCH].I, 0);
EXPECT_FLOAT_EQ(pidData[FD_YAW].I, 0);
pidData[FD_ROLL].I = 10;
pidData[FD_PITCH].I = 1000;
pidData[FD_YAW].I = 1000;
gyro.gyroADCf[FD_ROLL] = -1000;
rotateItermAndAxisError();
EXPECT_FLOAT_EQ(pidData[FD_ROLL].I, 10);
ASSERT_NEAR(860.37, pidData[FD_PITCH].I, calculateTolerance(860.37));
ASSERT_NEAR(1139.6, pidData[FD_YAW].I, calculateTolerance(1139.6));
pidProfile->abs_control_gain = 10;
pidInit(pidProfile);
pidData[FD_ROLL].I = 10;
pidData[FD_PITCH].I = 1000;
pidData[FD_YAW].I = 1000;
gyro.gyroADCf[FD_ROLL] = -1000;
// FIXME - axisError changes don't affect the system. This is a potential bug or intendend behaviour?
axisError[FD_PITCH] = 1000;
axisError[FD_YAW] = 1000;
rotateItermAndAxisError();
EXPECT_FLOAT_EQ(pidData[FD_ROLL].I, 10);
ASSERT_NEAR(860.37, pidData[FD_PITCH].I, calculateTolerance(860.37));
ASSERT_NEAR(1139.6, pidData[FD_YAW].I, calculateTolerance(1139.6));
}

View file

@ -52,7 +52,7 @@ extern "C" {
#include "fc/rc_controls.h"
#include "fc/runtime_config.h"
#include "fc/fc_core.h"
#include "fc/core.h"
#include "scheduler/scheduler.h"
}
@ -224,6 +224,10 @@ extern "C" {
uint32_t millis(void) {
return fixedMillis;
}
uint32_t micros(void) {
return fixedMillis * 1000;
}
}
void resetMillis(void) {
@ -705,7 +709,7 @@ void gyroStartCalibration(bool isFirstArmingCalibration)
}
void applyAndSaveAccelerometerTrimsDelta(rollAndPitchTrims_t*) {}
void handleInflightCalibrationStickPosition(void) {}
bool feature(uint32_t) { return false;}
bool featureIsEnabled(uint32_t) { return false;}
bool sensors(uint32_t) { return false;}
void tryArm(void) {}
void disarm(void) {}

File diff suppressed because it is too large Load diff

View file

@ -186,11 +186,11 @@ bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadR
return true;
}
bool feature(uint32_t) {
bool featureIsEnabled(uint32_t) {
return false;
}
void featureClear(uint32_t) {
void featureDisable(uint32_t) {
}
bool rxMspFrameComplete(void)

View file

@ -69,7 +69,7 @@ extern "C" {
cfTask_t cfTasks[TASK_COUNT] = {
[TASK_SYSTEM] = {
.taskName = "SYSTEM",
.taskFunc = taskSystem,
.taskFunc = taskSystemLoad,
.desiredPeriod = TASK_PERIOD_HZ(10),
.staticPriority = TASK_PRIORITY_MEDIUM_HIGH,
},
@ -122,8 +122,6 @@ extern "C" {
TEST(SchedulerUnittest, TestPriorites)
{
EXPECT_EQ(20, TASK_COUNT);
EXPECT_EQ(TASK_PRIORITY_MEDIUM_HIGH, cfTasks[TASK_SYSTEM].staticPriority);
EXPECT_EQ(TASK_PRIORITY_REALTIME, cfTasks[TASK_GYROPID].staticPriority);
EXPECT_EQ(TASK_PRIORITY_MEDIUM, cfTasks[TASK_ACCEL].staticPriority);
@ -238,64 +236,68 @@ TEST(SchedulerUnittest, TestQueueArray)
queueClear();
taskQueueArray[TASK_COUNT_UNITTEST + 1] = deadBeefPtr; // note, must set deadBeefPtr after queueClear
unsigned enqueuedTasks = 0;
EXPECT_EQ(enqueuedTasks, taskQueueSize);
for (int taskId = 0; taskId < TASK_COUNT_UNITTEST - 1; ++taskId) {
setTaskEnabled(static_cast<cfTaskId_e>(taskId), true);
EXPECT_EQ(taskId + 1, taskQueueSize);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
if (cfTasks[taskId].taskFunc) {
setTaskEnabled(static_cast<cfTaskId_e>(taskId), true);
enqueuedTasks++;
EXPECT_EQ(enqueuedTasks, taskQueueSize);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
}
}
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
EXPECT_NE(static_cast<cfTask_t*>(0), taskQueueArray[TASK_COUNT_UNITTEST - 2]);
const cfTask_t *lastTaskPrev = taskQueueArray[TASK_COUNT_UNITTEST - 2];
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_NE(static_cast<cfTask_t*>(0), taskQueueArray[enqueuedTasks - 1]);
const cfTask_t *lastTaskPrev = taskQueueArray[enqueuedTasks - 1];
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
setTaskEnabled(TASK_SYSTEM, false);
EXPECT_EQ(TASK_COUNT_UNITTEST - 2, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]); // NULL at end of queue
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_EQ(enqueuedTasks - 1, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[enqueuedTasks - 2]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks - 1]); // NULL at end of queue
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
taskQueueArray[TASK_COUNT_UNITTEST - 2] = 0;
taskQueueArray[enqueuedTasks - 1] = 0;
setTaskEnabled(TASK_SYSTEM, true);
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_EQ(enqueuedTasks, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[enqueuedTasks - 1]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
cfTaskInfo_t taskInfo;
getTaskInfo(static_cast<cfTaskId_e>(TASK_COUNT_UNITTEST - 1), &taskInfo);
getTaskInfo(static_cast<cfTaskId_e>(enqueuedTasks + 1), &taskInfo);
EXPECT_EQ(false, taskInfo.isEnabled);
setTaskEnabled(static_cast<cfTaskId_e>(TASK_COUNT_UNITTEST - 1), true);
EXPECT_EQ(TASK_COUNT_UNITTEST, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]); // check no buffer overrun
setTaskEnabled(static_cast<cfTaskId_e>(enqueuedTasks), true);
EXPECT_EQ(enqueuedTasks, taskQueueSize);
EXPECT_EQ(lastTaskPrev, taskQueueArray[enqueuedTasks - 1]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]); // check no buffer overrun
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
setTaskEnabled(TASK_SYSTEM, false);
EXPECT_EQ(TASK_COUNT_UNITTEST - 1, taskQueueSize);
//EXPECT_EQ(lastTaskPrev, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_EQ(enqueuedTasks - 1, taskQueueSize);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
setTaskEnabled(TASK_ACCEL, false);
EXPECT_EQ(TASK_COUNT_UNITTEST - 2, taskQueueSize);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_EQ(enqueuedTasks - 2, taskQueueSize);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks - 1]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
setTaskEnabled(TASK_BATTERY_VOLTAGE, false);
EXPECT_EQ(TASK_COUNT_UNITTEST - 3, taskQueueSize);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 3]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 2]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST - 1]);
EXPECT_EQ(NULL, taskQueueArray[TASK_COUNT_UNITTEST]);
EXPECT_EQ(enqueuedTasks - 2, taskQueueSize);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks - 2]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks - 1]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks]);
EXPECT_EQ(NULL, taskQueueArray[enqueuedTasks + 1]);
EXPECT_EQ(deadBeefPtr, taskQueueArray[TASK_COUNT_UNITTEST + 1]);
}

View file

@ -40,7 +40,7 @@ extern "C" {
#include "sensors/acceleration.h"
#include "sensors/sensors.h"
STATIC_UNIT_TESTED gyroSensor_e gyroDetect(gyroDev_t *dev);
STATIC_UNIT_TESTED gyroHardware_e gyroDetect(gyroDev_t *dev);
struct gyroSensor_s;
STATIC_UNIT_TESTED void performGyroCalibration(struct gyroSensor_s *gyroSensor, uint8_t gyroMovementCalibrationThreshold);
STATIC_UNIT_TESTED bool fakeGyroRead(gyroDev_t *gyro);
@ -57,7 +57,7 @@ extern gyroDev_t * const gyroDevPtr;
TEST(SensorGyro, Detect)
{
const gyroSensor_e detected = gyroDetect(gyroDevPtr);
const gyroHardware_e detected = gyroDetect(gyroDevPtr);
EXPECT_EQ(GYRO_FAKE, detected);
EXPECT_EQ(GYRO_FAKE, detectedSensors[SENSOR_INDEX_GYRO]);
}

View file

@ -59,6 +59,7 @@
#define USE_UART5
#define USE_SOFTSERIAL1
#define USE_SOFTSERIAL2
#define USE_TASK_STATISTICS
#define SERIAL_PORT_COUNT 8

View file

@ -69,6 +69,7 @@ extern "C" {
int sbufBytesRemaining(sbuf_t *buf);
void initSharedMsp();
uint16_t testBatteryVoltage = 0;
int32_t testAmperage = 0;
uint8_t mspTxData[64]; //max frame size
sbuf_t mspTxDataBuf;
@ -259,6 +260,9 @@ extern "C" {
uint16_t getBatteryVoltage(void) {
return testBatteryVoltage;
}
uint16_t getBatteryAverageCellVoltage(void) {
return 0;
}
bool isAmperageConfigured(void) { return true; }
int32_t getAmperage(void) {
return testAmperage;
@ -268,9 +272,13 @@ extern "C" {
return 67;
}
bool feature(uint32_t) {return false;}
int32_t getEstimatedAltitudeCm(void) {
return 0;
}
bool isAirmodeActive(void) {return true;}
bool featureIsEnabled(uint32_t) {return false;}
bool airmodeIsEnabled(void) {return true;}
mspResult_e mspFcProcessCommand(mspPacket_t *cmd, mspPacket_t *reply, mspPostProcessFnPtr *mspPostProcessFn) {

View file

@ -104,7 +104,7 @@ TEST(TelemetryCrsfTest, TestGPS)
int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
EXPECT_EQ(CRSF_FRAME_GPS_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(17, frame[1]); // length
EXPECT_EQ(0x02, frame[2]); // type
int32_t lattitude = frame[3] << 24 | frame[4] << 16 | frame[5] << 8 | frame[6];
@ -124,8 +124,8 @@ TEST(TelemetryCrsfTest, TestGPS)
gpsSol.llh.lat = 56 * GPS_DEGREES_DIVIDER;
gpsSol.llh.lon = 163 * GPS_DEGREES_DIVIDER;
ENABLE_STATE(GPS_FIX);
gpsSol.llh.alt = 2345; // altitude in m
gpsSol.groundSpeed = 163; // speed in 0.1m/s, 16.3 m/s = 58.68 km/h, so CRSF (km/h *10) value is 587
gpsSol.llh.altCm = 2345 * 100; // altitude in cm / 100 + 1000m offset, so CRSF value should be 3345
gpsSol.groundSpeed = 1630; // speed in cm/s, 16.3 m/s = 58.68 km/h, so CRSF (km/h *10) value is 587
gpsSol.numSat = 9;
gpsSol.groundCourse = 1479; // degrees * 10
frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_GPS);
@ -151,7 +151,7 @@ TEST(TelemetryCrsfTest, TestBattery)
testBatteryVoltage = 0; // 0.1V units
int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_BATTERY_SENSOR);
EXPECT_EQ(CRSF_FRAME_BATTERY_SENSOR_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(10, frame[1]); // length
EXPECT_EQ(0x08, frame[2]); // type
uint16_t voltage = frame[3] << 8 | frame[4]; // mV * 100
@ -188,7 +188,7 @@ TEST(TelemetryCrsfTest, TestAttitude)
attitude.values.yaw = 0;
int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_ATTITUDE);
EXPECT_EQ(CRSF_FRAME_ATTITUDE_PAYLOAD_SIZE + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(8, frame[1]); // length
EXPECT_EQ(0x1e, frame[2]); // type
int16_t pitch = frame[3] << 8 | frame[4]; // rad / 10000
@ -220,7 +220,7 @@ TEST(TelemetryCrsfTest, TestFlightMode)
airMode = false;
int frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(7, frame[1]); // length
EXPECT_EQ(0x21, frame[2]); // type
EXPECT_EQ('A', frame[3]);
@ -235,7 +235,7 @@ TEST(TelemetryCrsfTest, TestFlightMode)
EXPECT_EQ(ANGLE_MODE, FLIGHT_MODE(ANGLE_MODE));
frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
EXPECT_EQ(5 + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(7, frame[1]); // length
EXPECT_EQ(0x21, frame[2]); // type
EXPECT_EQ('S', frame[3]);
@ -250,7 +250,7 @@ TEST(TelemetryCrsfTest, TestFlightMode)
EXPECT_EQ(HORIZON_MODE, FLIGHT_MODE(HORIZON_MODE));
frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(6, frame[1]); // length
EXPECT_EQ(0x21, frame[2]); // type
EXPECT_EQ('H', frame[3]);
@ -263,7 +263,7 @@ TEST(TelemetryCrsfTest, TestFlightMode)
airMode = true;
frameLen = getCrsfFrame(frame, CRSF_FRAMETYPE_FLIGHT_MODE);
EXPECT_EQ(4 + FRAME_HEADER_FOOTER_LEN, frameLen);
EXPECT_EQ(CRSF_ADDRESS_BROADCAST, frame[0]); // address
EXPECT_EQ(CRSF_SYNC_BYTE, frame[0]); // address
EXPECT_EQ(6, frame[1]); // length
EXPECT_EQ(0x21, frame[2]); // type
EXPECT_EQ('A', frame[3]);
@ -293,7 +293,7 @@ void beeperConfirmationBeeps(uint8_t beepCount) {UNUSED(beepCount);}
uint32_t micros(void) {return 0;}
bool feature(uint32_t) {return true;}
bool featureIsEnabled(uint32_t) {return true;}
uint32_t serialRxBytesWaiting(const serialPort_t *) {return 0;}
uint32_t serialTxBytesFree(const serialPort_t *) {return 0;}
@ -312,7 +312,7 @@ bool telemetryCheckRxPortShared(const serialPortConfig_t *) {return true;}
portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunction_e) {return PORTSHARING_NOT_SHARED;}
bool isAirmodeActive(void) {return airMode;}
bool airmodeIsEnabled(void) {return airMode;}
int32_t getAmperage(void) {
return testAmperage;
@ -322,6 +322,10 @@ uint16_t getBatteryVoltage(void) {
return testBatteryVoltage;
}
uint16_t getBatteryAverageCellVoltage(void) {
return 0;
}
batteryState_e getBatteryState(void) {
return BATTERY_OK;
}
@ -330,6 +334,10 @@ uint8_t calculateBatteryPercentageRemaining(void) {
return 67;
}
int32_t getEstimatedAltitudeCm(void) {
return gpsSol.llh.altCm; // function returns cm not m.
}
int32_t getMAhDrawn(void){
return testmAhDrawn;
}

View file

@ -180,8 +180,8 @@ uint32_t fixedMillis = 0;
baro_t baro;
uint32_t getEstimatedAltitude() { return 0; }
uint32_t getEstimatedVario() { return 0; }
int32_t getEstimatedAltitudeCm() { return 0; }
int16_t getEstimatedVario() { return 0; }
uint32_t millis(void) {
return fixedMillis;
@ -265,6 +265,16 @@ batteryState_e getBatteryState(void)
return BATTERY_OK;
}
batteryState_e getVoltageState(void)
{
return BATTERY_OK;
}
batteryState_e getConsumptionState(void)
{
return BATTERY_OK;
}
uint16_t getBatteryVoltage(void)
{
return testBatteryVoltage;

View file

@ -35,7 +35,7 @@ extern "C" {
#include "sensors/barometer.h"
#include "sensors/acceleration.h"
#include "scheduler/scheduler.h"
#include "fc/fc_tasks.h"
#include "fc/tasks.h"
}
#include "unittest_macros.h"
@ -108,7 +108,7 @@ throttleStatus_e calculateThrottleStatus(void)
return throttleStatus;
}
bool feature(uint32_t mask)
bool featureIsEnabled(uint32_t mask)
{
return (definedFeatures & mask) != 0;
}

View file

@ -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 <http://www.gnu.org/licenses/>.
*/
extern "C" {
#include <target.h>
#include <drivers/timer.h>
extern const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT];
}
#include <bitset>
#include <iostream>
#include <set>
#include <sstream>
#include <string>
#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<TestPinEnum> 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<TEST_TIMER_SIZE> &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<TEST_TIMER_SIZE> expected;
for (const timerHardware_t &t : timerHardware)
expected |= TIM_N(t.timer);
const std::bitset<TEST_TIMER_SIZE> 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) {}
}

View file

@ -0,0 +1,21 @@
#include <mock_enums.h>
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))

View file

@ -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,
};

View file

@ -0,0 +1 @@
void bstInit(int);

View file

@ -0,0 +1,5 @@
#define I2CDEV_2 (1)
int i2cConfig(int);
void i2cHardwareConfigure(int);
void i2cInit(int);

View file

@ -0,0 +1,5 @@
#define SPIDEV_1 (0)
void spiPinConfigure(int);
int spiPinConfig(int);
void spiInit(int);

View file

@ -0,0 +1,5 @@
#include <mock_enums.h>
#include "target/common_pre.h"
#include "target.h"
#include "target/common_post.h"
#include "target/common_defaults_post.h"

View file

@ -0,0 +1,176 @@
/*
* 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 <http://www.gnu.org/licenses/>.
*/
#include <stdint.h>
extern "C" {
#include "blackbox/blackbox.h"
#include "build/debug.h"
#include "common/maths.h"
#include "config/feature.h"
#include "pg/pg.h"
#include "pg/pg_ids.h"
#include "pg/rx.h"
#include "fc/config.h"
#include "fc/controlrate_profile.h"
#include "fc/core.h"
#include "fc/rc_controls.h"
#include "fc/rc_modes.h"
#include "fc/runtime_config.h"
#include "flight/failsafe.h"
#include "flight/imu.h"
#include "flight/mixer.h"
#include "flight/pid.h"
#include "flight/servos.h"
#include "io/beeper.h"
#include "io/gps.h"
#include "io/vtx.h"
#include "rx/rx.h"
#include "scheduler/scheduler.h"
#include "sensors/acceleration.h"
#include "sensors/gyro.h"
#include "telemetry/telemetry.h"
vtxSettingsConfig_t vtxGetSettings(void);
PG_REGISTER(accelerometerConfig_t, accelerometerConfig, PG_ACCELEROMETER_CONFIG, 0);
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
PG_REGISTER(gyroConfig_t, gyroConfig, PG_GYRO_CONFIG, 0);
PG_REGISTER(mixerConfig_t, mixerConfig, PG_MIXER_CONFIG, 0);
PG_REGISTER(pidConfig_t, pidConfig, PG_PID_CONFIG, 0);
PG_REGISTER(rxConfig_t, rxConfig, PG_RX_CONFIG, 0);
PG_REGISTER(servoConfig_t, servoConfig, PG_SERVO_CONFIG, 0);
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 0);
PG_REGISTER(telemetryConfig_t, telemetryConfig, PG_TELEMETRY_CONFIG, 0);
PG_REGISTER(failsafeConfig_t, failsafeConfig, PG_FAILSAFE_CONFIG, 0);
float rcCommand[4];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint16_t averageSystemLoadPercent = 0;
uint8_t cliMode = 0;
uint8_t debugMode = 0;
int16_t debug[DEBUG16_VALUE_COUNT];
pidProfile_t *currentPidProfile;
controlRateConfig_t *currentControlRateProfile;
attitudeEulerAngles_t attitude;
gpsSolutionData_t gpsSol;
uint32_t targetPidLooptime;
bool cmsInMenu = false;
float axisPID_P[3], axisPID_I[3], axisPID_D[3], axisPIDSum[3];
rxRuntimeConfig_t rxRuntimeConfig = {};
}
uint32_t simulationFeatureFlags = 0;
uint32_t simulationTime = 0;
bool gyroCalibDone = false;
bool simulationHaveRx = false;
#include "gtest/gtest.h"
TEST(VtxTest, PitMode)
{
// given
modeActivationConditionsMutable(0)->auxChannelIndex = 0;
modeActivationConditionsMutable(0)->modeId = BOXVTXPITMODE;
modeActivationConditionsMutable(0)->range.startStep = CHANNEL_VALUE_TO_STEP(1750);
modeActivationConditionsMutable(0)->range.endStep = CHANNEL_VALUE_TO_STEP(CHANNEL_RANGE_MAX);
// and
vtxSettingsConfigMutable()->band = 0;
vtxSettingsConfigMutable()->freq = 5800;
vtxSettingsConfigMutable()->pitModeFreq = 5300;
// expect
EXPECT_EQ(5800, vtxGetSettings().freq);
// and
// enable vtx pit mode
rcData[AUX1] = 1800;
// when
updateActivatedModes();
// expect
EXPECT_TRUE(IS_RC_MODE_ACTIVE(BOXVTXPITMODE));
EXPECT_EQ(5300, vtxGetSettings().freq);
}
// STUBS
extern "C" {
uint32_t micros(void) { return simulationTime; }
uint32_t millis(void) { return micros() / 1000; }
bool rxIsReceivingSignal(void) { return simulationHaveRx; }
bool featureIsEnabled(uint32_t f) { return simulationFeatureFlags & f; }
void warningLedFlash(void) {}
void warningLedDisable(void) {}
void warningLedUpdate(void) {}
void beeper(beeperMode_e) {}
void beeperConfirmationBeeps(uint8_t) {}
void beeperWarningBeeps(uint8_t) {}
void beeperSilence(void) {}
void systemBeep(bool) {}
void saveConfigAndNotify(void) {}
void blackboxFinish(void) {}
bool accIsCalibrationComplete(void) { return true; }
bool isBaroCalibrationComplete(void) { return true; }
bool isGyroCalibrationComplete(void) { return gyroCalibDone; }
void gyroStartCalibration(bool) {}
bool isFirstArmingGyroCalibrationRunning(void) { return false; }
void pidController(const pidProfile_t *, const rollAndPitchTrims_t *, timeUs_t) {}
void pidStabilisationState(pidStabilisationState_e) {}
void mixTable(timeUs_t , uint8_t) {};
void writeMotors(void) {};
void writeServos(void) {};
bool calculateRxChannelsAndUpdateFailsafe(timeUs_t) { return true; }
bool isMixerUsingServos(void) { return false; }
void gyroUpdate(timeUs_t) {}
timeDelta_t getTaskDeltaTime(cfTaskId_e) { return 0; }
void updateRSSI(timeUs_t) {}
bool failsafeIsMonitoring(void) { return false; }
void failsafeStartMonitoring(void) {}
void failsafeUpdateState(void) {}
bool failsafeIsActive(void) { return false; }
void pidResetIterm(void) {}
void updateAdjustmentStates(void) {}
void processRcAdjustments(controlRateConfig_t *) {}
void updateGpsWaypointsAndMode(void) {}
void mspSerialReleaseSharedTelemetryPorts(void) {}
void telemetryCheckState(void) {}
void mspSerialAllocatePorts(void) {}
void gyroReadTemperature(void) {}
void updateRcCommands(void) {}
void applyAltHold(void) {}
void resetYawAxis(void) {}
int16_t calculateThrottleAngleCorrection(uint8_t) { return 0; }
void processRcCommand(void) {}
void updateGpsStateForHomeAndHoldMode(void) {}
void blackboxUpdate(timeUs_t) {}
void transponderUpdate(timeUs_t) {}
void GPS_reset_home_position(void) {}
void accSetCalibrationCycles(uint16_t) {}
void baroSetCalibrationCycles(uint16_t) {}
void changePidProfile(uint8_t) {}
void changeControlRateProfile(uint8_t) {}
void dashboardEnablePageCycling(void) {}
void dashboardDisablePageCycling(void) {}
bool imuQuaternionHeadfreeOffsetSet(void) { return true; }
void rescheduleTask(cfTaskId_e, uint32_t) {}
bool usbCableIsInserted(void) { return false; }
bool usbVcpIsConnected(void) { return false; }
void pidSetAntiGravityState(bool newState) { UNUSED(newState); }
}