Skip to content

Commit

Permalink
Update unit tests
Browse files Browse the repository at this point in the history
  • Loading branch information
klutvott123 committed Apr 26, 2021
1 parent 8c28533 commit 3177cb3
Show file tree
Hide file tree
Showing 11 changed files with 15 additions and 15 deletions.
2 changes: 1 addition & 1 deletion src/test/unit/arming_prevention_unittest.cc
Expand Up @@ -59,7 +59,7 @@ extern "C" {
PG_REGISTER(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 0);

float rcCommand[4];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint16_t averageSystemLoadPercent = 0;
uint8_t cliMode = 0;
uint8_t debugMode = 0;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/flight_failsafe_unittest.cc
Expand Up @@ -543,7 +543,7 @@ TEST(FlightFailsafeTest, TestFailsafeNotActivatedWhenDisarmedAndRXLossIsDetected
// STUBS

extern "C" {
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcCommand[4];
int16_t debug[DEBUG16_VALUE_COUNT];
bool isUsingSticksToArm = true;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/flight_imu_unittest.cc
Expand Up @@ -204,7 +204,7 @@ TEST(FlightImuTest, TestSmallAngle)
extern "C" {
boxBitmask_t rcModeActivationMask;
float rcCommand[4];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];

gyro_t gyro;
acc_t acc;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/ledstrip_unittest.cc
Expand Up @@ -299,7 +299,7 @@ uint8_t armingFlags = 0;
uint8_t stateFlags = 0;
uint16_t flightModeFlags = 0;
float rcCommand[4];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
boxBitmask_t rcModeActivationMask;
gpsSolutionData_t gpsSol;

Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/link_quality_unittest.cc
Expand Up @@ -69,7 +69,7 @@ extern "C" {
float rMat[3][3];

pidProfile_t *currentPidProfile;
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint8_t GPS_numSat;
uint16_t GPS_distanceToHome;
int16_t GPS_directionToHome;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/osd_unittest.cc
Expand Up @@ -73,7 +73,7 @@ extern "C" {

pidProfile_t *currentPidProfile;
int16_t debug[DEBUG16_VALUE_COUNT];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint8_t GPS_numSat;
uint16_t GPS_distanceToHome;
int16_t GPS_directionToHome;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/rc_controls_unittest.cc
Expand Up @@ -640,7 +640,7 @@ uint8_t armingFlags = 0;
uint16_t flightModeFlags = 0;
int16_t heading;
uint8_t stateFlags = 0;
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
pidProfile_t *currentPidProfile;
rxRuntimeState_t rxRuntimeState;
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/rcdevice_unittest.cc
Expand Up @@ -53,7 +53,7 @@ extern "C" {

#include "rx/rx.h"

int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]; // interval [1000;2000]

extern rcdeviceSwitchState_t switchStates[BOXCAMERA3 - BOXCAMERA1 + 1];
extern runcamDevice_t *camDevice;
Expand Down
10 changes: 5 additions & 5 deletions src/test/unit/rx_crsf_unittest.cc
Expand Up @@ -46,7 +46,7 @@ extern "C" {
void crsfDataReceive(uint16_t c);
uint8_t crsfFrameCRC(void);
uint8_t crsfFrameStatus(void);
uint16_t crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan);
float crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan);

extern bool crsfFrameDone;
extern crsfFrame_t crsfFrame;
Expand Down Expand Up @@ -239,10 +239,10 @@ TEST(CrossFireTest, TestCapturedData)
EXPECT_EQ(983, crsfChannelData[3]);
uint8_t crc = crsfFrameCRC();
EXPECT_EQ(crc, crsfFrame.frame.payload[CRSF_FRAME_RC_CHANNELS_PAYLOAD_SIZE]);
EXPECT_EQ(999, crsfReadRawRC(NULL, 0));
EXPECT_EQ(1501, crsfReadRawRC(NULL, 1));
EXPECT_EQ(1492, crsfReadRawRC(NULL, 2));
EXPECT_EQ(1495, crsfReadRawRC(NULL, 3));
EXPECT_EQ(999, (uint16_t)crsfReadRawRC(NULL, 0));
EXPECT_EQ(1501, (uint16_t)crsfReadRawRC(NULL, 1));
EXPECT_EQ(1492, (uint16_t)crsfReadRawRC(NULL, 2));
EXPECT_EQ(1495, (uint16_t)crsfReadRawRC(NULL, 3));

++framePtr;
crsfFrame = *(const crsfFrame_t*)framePtr;
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/rx_ranges_unittest.cc
Expand Up @@ -44,7 +44,7 @@ boxBitmask_t rcModeActivationMask;
int16_t debug[DEBUG16_VALUE_COUNT];
uint8_t debugMode = 0;

extern uint16_t applyRxChannelRangeConfiguraton(int sample, const rxChannelRangeConfig_t *range);
extern float applyRxChannelRangeConfiguraton(float sample, const rxChannelRangeConfig_t *range);
}

#define RANGE_CONFIGURATION(min, max) new (rxChannelRangeConfig_t) {min, max}
Expand Down
2 changes: 1 addition & 1 deletion src/test/unit/vtx_unittest.cc
Expand Up @@ -62,7 +62,7 @@ extern "C" {
PG_REGISTER(motorConfig_t, motorConfig, PG_MOTOR_CONFIG, 0);

float rcCommand[4];
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
float rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
uint16_t averageSystemLoadPercent = 0;
uint8_t cliMode = 0;
uint8_t debugMode = 0;
Expand Down

0 comments on commit 3177cb3

Please sign in to comment.