mirror of
https://github.com/betaflight/betaflight.git
synced 2025-07-24 00:35:39 +03:00
Fix function brace style
This commit is contained in:
parent
6a06f0e408
commit
9957ceb275
83 changed files with 494 additions and 251 deletions
|
@ -154,26 +154,33 @@ bool busWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO() {
|
||||
void spiPreinitByIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void IORelease() {
|
||||
void IORelease()
|
||||
{
|
||||
}
|
||||
|
||||
|
||||
|
|
|
@ -151,39 +151,49 @@ bool busWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO(IO_t) {
|
||||
void spiPreinitByIO(IO_t)
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
IO_t IOGetByTag(ioTag_t) {
|
||||
IO_t IOGetByTag(ioTag_t)
|
||||
{
|
||||
return IO_NONE;
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *) {
|
||||
void EXTIHandlerInit(extiCallbackRec_t *, extiHandlerCallback *)
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t) {
|
||||
void EXTIConfig(IO_t, extiCallbackRec_t *, int, ioConfig_t, extiTrigger_t)
|
||||
{
|
||||
}
|
||||
|
||||
void EXTIEnable(IO_t) {
|
||||
}
|
||||
void EXTIDisable(IO_t) {
|
||||
}
|
||||
void EXTIEnable(IO_t)
|
||||
{}
|
||||
|
||||
void EXTIDisable(IO_t)
|
||||
{}
|
||||
|
||||
|
||||
} // extern "C"
|
||||
|
|
|
@ -153,26 +153,33 @@ bool busRawWriteRegister(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
|||
bool busRawWriteRegisterStart(const extDevice_t*, uint8_t, uint8_t) {return true;}
|
||||
void busDeviceRegister(const extDevice_t*) {}
|
||||
|
||||
uint16_t spiCalculateDivider() {
|
||||
uint16_t spiCalculateDivider()
|
||||
{
|
||||
return 2;
|
||||
}
|
||||
|
||||
void spiSetClkDivisor() {
|
||||
void spiSetClkDivisor()
|
||||
{
|
||||
}
|
||||
|
||||
void spiPreinitByIO() {
|
||||
void spiPreinitByIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOConfigGPIO() {
|
||||
void IOConfigGPIO()
|
||||
{
|
||||
}
|
||||
|
||||
void IOHi() {
|
||||
void IOHi()
|
||||
{
|
||||
}
|
||||
|
||||
void IOInit() {
|
||||
void IOInit()
|
||||
{
|
||||
}
|
||||
|
||||
void IORelease() {
|
||||
void IORelease()
|
||||
{
|
||||
}
|
||||
|
||||
}
|
||||
|
|
|
@ -208,27 +208,33 @@ int32_t taskGuardCycles;
|
|||
|
||||
uint32_t micros(void) {return 0;}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return 100;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return 42;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentageRemaining(void) {
|
||||
uint8_t calculateBatteryPercentageRemaining(void)
|
||||
{
|
||||
return 67;
|
||||
}
|
||||
|
||||
uint8_t getMotorCount() {
|
||||
uint8_t getMotorCount()
|
||||
{
|
||||
return 4;
|
||||
}
|
||||
|
||||
size_t getEEPROMStorageSize() {
|
||||
size_t getEEPROMStorageSize()
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
|
@ -241,7 +247,8 @@ const box_t *findBoxByBoxId(boxId_e) { return &boxes[0]; }
|
|||
|
||||
int8_t unitTestDataArray[3];
|
||||
|
||||
void pgResetFn_unitTestData(int8_t *) {}
|
||||
void pgResetFn_unitTestData(int8_t *)
|
||||
{}
|
||||
|
||||
uint32_t getBeeperOffMask(void) { return 0; }
|
||||
uint32_t getPreferredBeeperOffMask(void) { return 0; }
|
||||
|
|
|
@ -63,7 +63,8 @@ static int callCounts[CALL_COUNT_ITEM_COUNT];
|
|||
|
||||
#define CALL_COUNTER(item) (callCounts[item])
|
||||
|
||||
void resetCallCounters(void) {
|
||||
void resetCallCounters(void)
|
||||
{
|
||||
memset(&callCounts, 0, sizeof(callCounts));
|
||||
}
|
||||
|
||||
|
@ -739,15 +740,18 @@ throttleStatus_e calculateThrottleStatus()
|
|||
|
||||
void delay(uint32_t) {}
|
||||
|
||||
bool featureIsEnabled(uint32_t mask) {
|
||||
bool featureIsEnabled(uint32_t mask)
|
||||
{
|
||||
return (mask & testFeatureMask);
|
||||
}
|
||||
|
||||
void disarm(flightLogDisarmReason_e) {
|
||||
void disarm(flightLogDisarmReason_e)
|
||||
{
|
||||
callCounts[COUNTER_MW_DISARM]++;
|
||||
}
|
||||
|
||||
void beeper(beeperMode_e mode) {
|
||||
void beeper(beeperMode_e mode)
|
||||
{
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
|
@ -761,7 +765,8 @@ bool isUsingSticksForArming(void)
|
|||
return isUsingSticksToArm;
|
||||
}
|
||||
|
||||
bool areSticksActive(uint8_t stickPercentLimit) {
|
||||
bool areSticksActive(uint8_t stickPercentLimit)
|
||||
{
|
||||
UNUSED(stickPercentLimit);
|
||||
return false;
|
||||
}
|
||||
|
|
|
@ -303,42 +303,50 @@ float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
|
|||
boxBitmask_t rcModeActivationMask;
|
||||
gpsSolutionData_t gpsSol;
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
void ws2811LedStripInit(ioTag_t ioTag) {
|
||||
void ws2811LedStripInit(ioTag_t ioTag)
|
||||
{
|
||||
UNUSED(ioTag);
|
||||
}
|
||||
|
||||
void ws2811UpdateStrip(ledStripFormatRGB_e, uint8_t) {}
|
||||
|
||||
void setLedValue(uint16_t index, const uint8_t value) {
|
||||
void setLedValue(uint16_t index, const uint8_t value)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(value);
|
||||
}
|
||||
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color) {
|
||||
void setLedHsv(uint16_t index, const hsvColor_t *color)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
void getLedHsv(uint16_t index, hsvColor_t *color) {
|
||||
void getLedHsv(uint16_t index, hsvColor_t *color)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
|
||||
void scaleLedValue(uint16_t index, const uint8_t scalePercent) {
|
||||
void scaleLedValue(uint16_t index, const uint8_t scalePercent)
|
||||
{
|
||||
UNUSED(index);
|
||||
UNUSED(scalePercent);
|
||||
}
|
||||
|
||||
void setStripColor(const hsvColor_t *color) {
|
||||
void setStripColor(const hsvColor_t *color)
|
||||
{
|
||||
UNUSED(color);
|
||||
}
|
||||
|
||||
void setStripColors(const hsvColor_t *colors) {
|
||||
void setStripColors(const hsvColor_t *colors)
|
||||
{
|
||||
UNUSED(colors);
|
||||
}
|
||||
|
||||
|
@ -355,14 +363,16 @@ uint32_t micros(void) { return 0; }
|
|||
uint32_t millis(void) { return 0; }
|
||||
|
||||
bool shouldSoundBatteryAlarm(void) { return false; }
|
||||
bool featureIsEnabled(uint32_t mask) {
|
||||
bool featureIsEnabled(uint32_t mask)
|
||||
{
|
||||
UNUSED(mask);
|
||||
return false;
|
||||
}
|
||||
|
||||
void tfp_sprintf(char *, char*, ...) { }
|
||||
|
||||
int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax) {
|
||||
int scaleRange(int x, int srcMin, int srcMax, int destMin, int destMax)
|
||||
{
|
||||
UNUSED(x);
|
||||
UNUSED(srcMin);
|
||||
UNUSED(srcMax);
|
||||
|
|
|
@ -163,7 +163,8 @@ void doTestArm(bool testEmpty = true)
|
|||
/*
|
||||
* Auxiliary function. Test is there're stats that must be shown
|
||||
*/
|
||||
bool isSomeStatEnabled(void) {
|
||||
bool isSomeStatEnabled(void)
|
||||
{
|
||||
return (osdConfigMutable()->enabled_stats != 0);
|
||||
}
|
||||
|
||||
|
|
|
@ -190,7 +190,8 @@ void doTestArm(bool testEmpty = true)
|
|||
/*
|
||||
* Auxiliary function. Test is there're stats that must be shown
|
||||
*/
|
||||
bool isSomeStatEnabled(void) {
|
||||
bool isSomeStatEnabled(void)
|
||||
{
|
||||
return (osdConfigMutable()->enabled_stats != 0);
|
||||
}
|
||||
|
||||
|
|
|
@ -118,7 +118,8 @@ pidProfile_t *pidProfile;
|
|||
int loopIter = 0;
|
||||
|
||||
// Always use same defaults for testing in future releases even when defaults change
|
||||
void setDefaultTestSettings(void) {
|
||||
void setDefaultTestSettings(void)
|
||||
{
|
||||
pgResetAll();
|
||||
pidProfile = pidProfilesMutable(1);
|
||||
pidProfile->pid[PID_ROLL] = { 40, 40, 30, 65 };
|
||||
|
@ -170,11 +171,13 @@ void setDefaultTestSettings(void) {
|
|||
gyro.targetLooptime = 8000;
|
||||
}
|
||||
|
||||
timeUs_t currentTestTime(void) {
|
||||
timeUs_t currentTestTime(void)
|
||||
{
|
||||
return targetPidLooptime * loopIter++;
|
||||
}
|
||||
|
||||
void resetTest(void) {
|
||||
void resetTest(void)
|
||||
{
|
||||
loopIter = 0;
|
||||
pidRuntime.tpaFactor = 1.0f;
|
||||
simulatedMotorMixRange = 0.0f;
|
||||
|
@ -212,14 +215,16 @@ void resetTest(void) {
|
|||
}
|
||||
}
|
||||
|
||||
void setStickPosition(int axis, float stickRatio) {
|
||||
void setStickPosition(int axis, float stickRatio)
|
||||
{
|
||||
simulatedPrevSetpointRate[axis] = simulatedSetpointRate[axis];
|
||||
simulatedSetpointRate[axis] = 1998.0f * stickRatio;
|
||||
simulatedRcDeflection[axis] = stickRatio;
|
||||
}
|
||||
|
||||
// All calculations will have 10% tolerance
|
||||
float calculateTolerance(float input) {
|
||||
float calculateTolerance(float input)
|
||||
{
|
||||
return fabsf(input * 0.1f);
|
||||
}
|
||||
|
||||
|
@ -235,7 +240,8 @@ TEST(pidControllerTest, testInitialisation)
|
|||
}
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testStabilisationDisabled) {
|
||||
TEST(pidControllerTest, testStabilisationDisabled)
|
||||
{
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
// Run few loops to make sure there is no error building up when stabilisation disabled
|
||||
|
||||
|
@ -255,7 +261,8 @@ TEST(pidControllerTest, testStabilisationDisabled) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testPidLoop) {
|
||||
TEST(pidControllerTest, testPidLoop)
|
||||
{
|
||||
// Make sure to start with fresh values
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -362,7 +369,8 @@ TEST(pidControllerTest, testPidLoop) {
|
|||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].D);
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testPidLevel) {
|
||||
TEST(pidControllerTest, testPidLevel)
|
||||
{
|
||||
// Make sure to start with fresh values
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -422,7 +430,8 @@ TEST(pidControllerTest, testPidLevel) {
|
|||
}
|
||||
|
||||
|
||||
TEST(pidControllerTest, testPidHorizon) {
|
||||
TEST(pidControllerTest, testPidHorizon)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -445,7 +454,8 @@ TEST(pidControllerTest, testPidHorizon) {
|
|||
EXPECT_NEAR(0.811f, calcHorizonLevelStrength(), calculateTolerance(0.82));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testMixerSaturation) {
|
||||
TEST(pidControllerTest, testMixerSaturation)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -491,7 +501,8 @@ TEST(pidControllerTest, testMixerSaturation) {
|
|||
}
|
||||
|
||||
// TODO - Add more scenarios
|
||||
TEST(pidControllerTest, testCrashRecoveryMode) {
|
||||
TEST(pidControllerTest, testCrashRecoveryMode)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->crash_recovery = PID_CRASH_RECOVERY_ON;
|
||||
pidInit(pidProfile);
|
||||
|
@ -516,7 +527,8 @@ TEST(pidControllerTest, testCrashRecoveryMode) {
|
|||
// Add additional verifications
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testFeedForward) {
|
||||
TEST(pidControllerTest, testFeedForward)
|
||||
{
|
||||
resetTest();
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
pidStabilisationState(PID_STABILISATION_ON);
|
||||
|
@ -561,7 +573,8 @@ TEST(pidControllerTest, testFeedForward) {
|
|||
EXPECT_FLOAT_EQ(0, pidData[FD_YAW].F);
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testItermRelax) {
|
||||
TEST(pidControllerTest, testItermRelax)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->iterm_relax = ITERM_RELAX_RP;
|
||||
ENABLE_ARMING_FLAG(ARMED);
|
||||
|
@ -635,7 +648,8 @@ TEST(pidControllerTest, testItermRelax) {
|
|||
}
|
||||
|
||||
// TODO - Add more tests
|
||||
TEST(pidControllerTest, testAbsoluteControl) {
|
||||
TEST(pidControllerTest, testAbsoluteControl)
|
||||
{
|
||||
resetTest();
|
||||
pidProfile->abs_control_gain = 10;
|
||||
pidInit(pidProfile);
|
||||
|
@ -663,11 +677,13 @@ TEST(pidControllerTest, testAbsoluteControl) {
|
|||
EXPECT_NEAR(-79.2, currentPidSetpoint, calculateTolerance(-79.2));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testDtermFiltering) {
|
||||
TEST(pidControllerTest, testDtermFiltering)
|
||||
{
|
||||
// TODO
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testItermRotationHandling) {
|
||||
TEST(pidControllerTest, testItermRotationHandling)
|
||||
{
|
||||
resetTest();
|
||||
pidInit(pidProfile);
|
||||
|
||||
|
@ -709,7 +725,8 @@ TEST(pidControllerTest, testItermRotationHandling) {
|
|||
EXPECT_NEAR(1139.6, pidData[FD_YAW].I, calculateTolerance(1139.6));
|
||||
}
|
||||
|
||||
TEST(pidControllerTest, testLaunchControl) {
|
||||
TEST(pidControllerTest, testLaunchControl)
|
||||
{
|
||||
// The launchControlGain is indirectly tested since when launch control is active the
|
||||
// the gain overrides the PID settings. If the logic to use launchControlGain wasn't
|
||||
// working then any I calculations would be incorrect.
|
||||
|
|
|
@ -60,7 +60,8 @@ extern "C" {
|
|||
#include "unittest_macros.h"
|
||||
#include "gtest/gtest.h"
|
||||
|
||||
void unsetArmingDisabled(armingDisableFlags_e flag) {
|
||||
void unsetArmingDisabled(armingDisableFlags_e flag)
|
||||
{
|
||||
UNUSED(flag);
|
||||
}
|
||||
|
||||
|
@ -202,37 +203,44 @@ static int callCounts[CALL_COUNT_ITEM_COUNT];
|
|||
#define CALL_COUNTER(item) (callCounts[item])
|
||||
|
||||
extern "C" {
|
||||
void beeperConfirmationBeeps(uint8_t) {
|
||||
void beeperConfirmationBeeps(uint8_t)
|
||||
{
|
||||
callCounts[COUNTER_QUEUE_CONFIRMATION_BEEP]++;
|
||||
}
|
||||
|
||||
void beeper(beeperMode_e mode) {
|
||||
void beeper(beeperMode_e mode)
|
||||
{
|
||||
UNUSED(mode);
|
||||
}
|
||||
|
||||
void changeControlRateProfile(uint8_t) {
|
||||
void changeControlRateProfile(uint8_t)
|
||||
{
|
||||
callCounts[COUNTER_CHANGE_CONTROL_RATE_PROFILE]++;
|
||||
}
|
||||
|
||||
}
|
||||
|
||||
void resetCallCounters(void) {
|
||||
void resetCallCounters(void)
|
||||
{
|
||||
memset(&callCounts, 0, sizeof(callCounts));
|
||||
}
|
||||
|
||||
uint32_t fixedMillis;
|
||||
|
||||
extern "C" {
|
||||
uint32_t millis(void) {
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return fixedMillis;
|
||||
}
|
||||
|
||||
uint32_t micros(void) {
|
||||
uint32_t micros(void)
|
||||
{
|
||||
return fixedMillis * 1000;
|
||||
}
|
||||
}
|
||||
|
||||
void resetMillis(void) {
|
||||
void resetMillis(void)
|
||||
{
|
||||
fixedMillis = 0;
|
||||
}
|
||||
|
||||
|
@ -628,7 +636,8 @@ bool failsafeIsActive() { return false; }
|
|||
bool rxIsReceivingSignal() { return true; }
|
||||
bool failsafeIsReceivingRxData() { return true; }
|
||||
|
||||
uint8_t getCurrentControlRateProfileIndex(void) {
|
||||
uint8_t getCurrentControlRateProfileIndex(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
void GPS_reset_home_position(void) {}
|
||||
|
@ -648,7 +657,8 @@ PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
|
|||
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
|
||||
void resetArmingDisabled(void) {}
|
||||
timeDelta_t getTaskDeltaTimeUs(taskId_e) { return 20000; }
|
||||
armingDisableFlags_e getArmingDisableFlags(void) {
|
||||
armingDisableFlags_e getArmingDisableFlags(void)
|
||||
{
|
||||
return (armingDisableFlags_e) 0;
|
||||
}
|
||||
bool isTryingToArm(void) { return false; }
|
||||
|
|
|
@ -175,7 +175,8 @@ static bool stubTelemetryCalled = false;
|
|||
static uint8_t stubTelemetryPacket[100];
|
||||
static uint8_t stubTelemetryIgnoreRxChars = 0;
|
||||
|
||||
uint8_t respondToIbusRequest(uint8_t const * const ibusPacket) {
|
||||
uint8_t respondToIbusRequest(uint8_t const * const ibusPacket)
|
||||
{
|
||||
uint8_t len = ibusPacket[0];
|
||||
EXPECT_LT(len, sizeof(stubTelemetryPacket));
|
||||
memcpy(stubTelemetryPacket, ibusPacket, len);
|
||||
|
|
|
@ -199,11 +199,13 @@ bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRaw
|
|||
return true;
|
||||
}
|
||||
|
||||
bool featureIsEnabled(uint32_t) {
|
||||
bool featureIsEnabled(uint32_t)
|
||||
{
|
||||
return false;
|
||||
}
|
||||
|
||||
void featureDisableImmediate(uint32_t) {
|
||||
void featureDisableImmediate(uint32_t)
|
||||
{
|
||||
}
|
||||
|
||||
bool rxMspFrameComplete(void)
|
||||
|
|
|
@ -224,13 +224,15 @@ TEST(CrossFireMSPTest, WriteResponseTest)
|
|||
|
||||
}
|
||||
|
||||
void testSendMspResponse(uint8_t *payload, const uint8_t ) {
|
||||
void testSendMspResponse(uint8_t *payload, const uint8_t )
|
||||
{
|
||||
sbuf_t *plOut = sbufInit(&payloadOutputBuf, payloadOutput, payloadOutput + 64);
|
||||
sbufWriteData(plOut, payload, *payload + 64);
|
||||
sbufSwitchToReader(&payloadOutputBuf, payloadOutput);
|
||||
}
|
||||
|
||||
TEST(CrossFireMSPTest, SendMspReply) {
|
||||
TEST(CrossFireMSPTest, SendMspReply)
|
||||
{
|
||||
initSharedMsp();
|
||||
const crsfMspFrame_t *framePtr = (const crsfMspFrame_t*)crsfPidRequest;
|
||||
crsfFrame = *(const crsfFrame_t*)framePtr;
|
||||
|
|
|
@ -342,35 +342,43 @@ portSharing_e determinePortSharing(const serialPortConfig_t *, serialPortFunctio
|
|||
|
||||
bool airmodeIsEnabled(void) {return airMode;}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
uint16_t getBatteryVoltage(void) {
|
||||
uint16_t getBatteryVoltage(void)
|
||||
{
|
||||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
uint16_t getLegacyBatteryVoltage(void) {
|
||||
uint16_t getLegacyBatteryVoltage(void)
|
||||
{
|
||||
return (testBatteryVoltage + 5) / 10;
|
||||
}
|
||||
|
||||
uint16_t getBatteryAverageCellVoltage(void) {
|
||||
uint16_t getBatteryAverageCellVoltage(void)
|
||||
{
|
||||
return 0;
|
||||
}
|
||||
|
||||
batteryState_e getBatteryState(void) {
|
||||
batteryState_e getBatteryState(void)
|
||||
{
|
||||
return BATTERY_OK;
|
||||
}
|
||||
|
||||
uint8_t calculateBatteryPercentageRemaining(void) {
|
||||
uint8_t calculateBatteryPercentageRemaining(void)
|
||||
{
|
||||
return 67;
|
||||
}
|
||||
|
||||
int32_t getEstimatedAltitudeCm(void) {
|
||||
int32_t getEstimatedAltitudeCm(void)
|
||||
{
|
||||
return gpsSol.llh.altCm; // function returns cm not m.
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void){
|
||||
int32_t getMAhDrawn(void)
|
||||
{
|
||||
return testmAhDrawn;
|
||||
}
|
||||
|
||||
|
|
|
@ -184,7 +184,8 @@ baro_t baro;
|
|||
int32_t getEstimatedAltitudeCm() { return 0; }
|
||||
int16_t getEstimatedVario() { return 0; }
|
||||
|
||||
uint32_t millis(void) {
|
||||
uint32_t millis(void)
|
||||
{
|
||||
return fixedMillis;
|
||||
}
|
||||
|
||||
|
@ -256,7 +257,8 @@ bool telemetryDetermineEnabledState(portSharing_e)
|
|||
return true;
|
||||
}
|
||||
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor) {
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor)
|
||||
{
|
||||
UNUSED(sensor);
|
||||
return true;
|
||||
}
|
||||
|
@ -291,11 +293,13 @@ uint16_t getLegacyBatteryVoltage(void)
|
|||
return (testBatteryVoltage + 5) / 10;
|
||||
}
|
||||
|
||||
int32_t getAmperage(void) {
|
||||
int32_t getAmperage(void)
|
||||
{
|
||||
return testAmperage;
|
||||
}
|
||||
|
||||
int32_t getMAhDrawn(void) {
|
||||
int32_t getMAhDrawn(void)
|
||||
{
|
||||
return testMAhDrawn;
|
||||
}
|
||||
|
||||
|
|
|
@ -61,7 +61,8 @@ extern "C" {
|
|||
}
|
||||
|
||||
static int16_t gyroTemperature;
|
||||
int16_t gyroGetTemperature(void) {
|
||||
int16_t gyroGetTemperature(void)
|
||||
{
|
||||
return gyroTemperature;
|
||||
}
|
||||
|
||||
|
@ -135,7 +136,8 @@ uint16_t getBatteryVoltage(void)
|
|||
return testBatteryVoltage;
|
||||
}
|
||||
|
||||
uint8_t getBatteryCellCount(void) {
|
||||
uint8_t getBatteryCellCount(void)
|
||||
{
|
||||
return testBatteryCellCount;
|
||||
}
|
||||
|
||||
|
@ -185,7 +187,8 @@ bool telemetryDetermineEnabledState(portSharing_e portSharing)
|
|||
}
|
||||
|
||||
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor) {
|
||||
bool telemetryIsSensorEnabled(sensor_e sensor)
|
||||
{
|
||||
UNUSED(sensor);
|
||||
return true;
|
||||
}
|
||||
|
|
|
@ -32,7 +32,8 @@ extern "C" {
|
|||
extern const timerHardware_t timerHardware[USABLE_TIMER_CHANNEL_COUNT];
|
||||
}
|
||||
|
||||
TEST(TimerDefinitionTest, Test_counterMismatch) {
|
||||
TEST(TimerDefinitionTest, Test_counterMismatch)
|
||||
{
|
||||
for (const timerHardware_t &t : timerHardware)
|
||||
EXPECT_EQ(&t - timerHardware, t.def_tim_counter)
|
||||
<< "Counter mismatch in timerHardware (in target.c) at position "
|
||||
|
@ -43,7 +44,8 @@ TEST(TimerDefinitionTest, Test_counterMismatch) {
|
|||
<< " array element appears to be " << &t - timerHardware - 1 << '.';
|
||||
}
|
||||
|
||||
TEST(TimerDefinitionTest, Test_duplicatePin) {
|
||||
TEST(TimerDefinitionTest, Test_duplicatePin)
|
||||
{
|
||||
std::set<TestPinEnum> usedPins;
|
||||
for (const timerHardware_t &t : timerHardware)
|
||||
EXPECT_TRUE(usedPins.emplace(t.pin).second)
|
||||
|
@ -56,7 +58,8 @@ TEST(TimerDefinitionTest, Test_duplicatePin) {
|
|||
|
||||
#if !defined(USE_TIMER_MGMT)
|
||||
namespace {
|
||||
std::string writeUsedTimers(const std::bitset<TEST_TIMER_SIZE> &tset) {
|
||||
std::string writeUsedTimers(const std::bitset<TEST_TIMER_SIZE> &tset)
|
||||
{
|
||||
std::stringstream used_timers;
|
||||
if (tset.any()) {
|
||||
unsigned int timer{0};
|
||||
|
|
|
@ -37,7 +37,8 @@ extern "C" {
|
|||
STATIC_UNIT_TESTED void updateTransponderDMABufferArcitimer(transponder_t *transponder, const uint8_t* transponderData);
|
||||
}
|
||||
|
||||
TEST(transponderTest, updateTransponderDMABufferArcitimer) {
|
||||
TEST(transponderTest, updateTransponderDMABufferArcitimer)
|
||||
{
|
||||
//input
|
||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0xF8, 0x1F, 0x0};
|
||||
//excepted
|
||||
|
@ -69,7 +70,8 @@ TEST(transponderTest, updateTransponderDMABufferArcitimer) {
|
|||
}
|
||||
}
|
||||
|
||||
TEST(transponderTest, updateTransponderDMABufferIlap) {
|
||||
TEST(transponderTest, updateTransponderDMABufferIlap)
|
||||
{
|
||||
uint8_t data[9] = {0x1F, 0xFC, 0x8F, 0x3, 0xF0, 0x1, 0x0, 0x0, 0x0};
|
||||
|
||||
uint8_t excepted[TRANSPONDER_DMA_BUFFER_SIZE_ILAP] = {
|
||||
|
|
|
@ -36,7 +36,8 @@ extern "C" {
|
|||
void schedulerIgnoreTaskStateTime(void) {}
|
||||
}
|
||||
|
||||
TEST(WS2812, updateDMABuffer) {
|
||||
TEST(WS2812, updateDMABuffer)
|
||||
{
|
||||
// given
|
||||
rgbColor24bpp_t color1 = { .raw = {0xFF,0xAA,0x55} };
|
||||
|
||||
|
@ -78,12 +79,14 @@ TEST(WS2812, updateDMABuffer) {
|
|||
}
|
||||
|
||||
extern "C" {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c) {
|
||||
rgbColor24bpp_t* hsvToRgb24(const hsvColor_t *c)
|
||||
{
|
||||
UNUSED(c);
|
||||
return NULL;
|
||||
}
|
||||
|
||||
bool ws2811LedStripHardwareInit(ioTag_t ioTag) {
|
||||
bool ws2811LedStripHardwareInit(ioTag_t ioTag)
|
||||
{
|
||||
UNUSED(ioTag);
|
||||
|
||||
return true;
|
||||
|
|
Loading…
Add table
Add a link
Reference in a new issue