1
0
Fork 0
mirror of https://github.com/betaflight/betaflight.git synced 2025-07-23 08:15:30 +03:00

Renamed 'rxRuntimeConfig' to 'rxRuntimeState'. (#9072)

Renamed 'rxRuntimeConfig' to 'rxRuntimeState'.
This commit is contained in:
Michael Keller 2019-10-22 11:27:36 +13:00 committed by GitHub
commit 9e44cd3ca5
No known key found for this signature in database
GPG key ID: 4AEE18F83AFDEB23
71 changed files with 463 additions and 463 deletions

View file

@ -69,7 +69,7 @@ extern "C" {
uint32_t targetPidLooptime;
bool cmsInMenu = false;
float axisPID_P[3], axisPID_I[3], axisPID_D[3], axisPIDSum[3];
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
uint16_t GPS_distanceToHome = 0;
int16_t GPS_directionToHome = 0;
acc_t acc = {};

View file

@ -377,7 +377,7 @@ TEST_F(CustomMixerIntegrationTest, TestCustomMixer)
extern "C" {
rollAndPitchInclination_t inclination;
rxRuntimeConfig_t rxRuntimeConfig;
rxRuntimeState_t rxRuntimeState;
int16_t axisPID[XYZ_AXIS_COUNT];
float rcCommand[4];

View file

@ -451,74 +451,74 @@ extern "C" {
void failsafeOnValidDataReceived(void) { }
void failsafeOnValidDataFailed(void) { }
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
void rxPwmInit(rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
}
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(initialRxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback);
bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback);
bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}

View file

@ -78,8 +78,8 @@ TEST_F(RcControlsModesTest, updateActivatedModesWithAllInputsAtMidde)
rcModeUpdate(&mask);
// and
memset(&rxRuntimeConfig, 0, sizeof(rxRuntimeConfig_t));
rxRuntimeConfig.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
memset(&rxRuntimeState, 0, sizeof(rxRuntimeState_t));
rxRuntimeState.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
// and
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
@ -152,8 +152,8 @@ TEST_F(RcControlsModesTest, updateActivatedModesUsingValidAuxConfigurationAndRXV
rcModeUpdate(&mask);
// and
memset(&rxRuntimeConfig, 0, sizeof(rxRuntimeConfig_t));
rxRuntimeConfig.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
memset(&rxRuntimeState, 0, sizeof(rxRuntimeState_t));
rxRuntimeState.channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT - NON_AUX_CHANNEL_COUNT;
// and
for (int index = AUX1; index < MAX_SUPPORTED_RC_CHANNEL_COUNT; index++) {
@ -642,7 +642,7 @@ int16_t heading;
uint8_t stateFlags = 0;
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
pidProfile_t *currentPidProfile;
rxRuntimeConfig_t rxRuntimeConfig;
rxRuntimeState_t rxRuntimeState;
PG_REGISTER(blackboxConfig_t, blackboxConfig, PG_BLACKBOX_CONFIG, 0);
PG_REGISTER(systemConfig_t, systemConfig, PG_SYSTEM_CONFIG, 2);
void resetArmingDisabled(void) {}

View file

@ -46,7 +46,7 @@ extern "C" {
void crsfDataReceive(uint16_t c);
uint8_t crsfFrameCRC(void);
uint8_t crsfFrameStatus(void);
uint16_t crsfReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan);
uint16_t crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan);
extern bool crsfFrameDone;
extern crsfFrame_t crsfFrame;

View file

@ -201,36 +201,36 @@ protected:
TEST_F(IbusRxInitUnitTest, Test_IbusRxNotEnabled)
{
const rxConfig_t initialRxConfig = {};
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
findSerialPortConfig_stub_retval = NULL;
EXPECT_FALSE(ibusInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_FALSE(ibusInit(&initialRxConfig, &rxRuntimeState));
//TODO: Question: I'd expect that runtime conf was not initialized unless there was a serial port to run but the implementation states otherwise
// EXPECT_EQ(0, rxRuntimeConfig.channelCount);
// EXPECT_EQ(0, rxRuntimeConfig.rxRefreshRate);
// EXPECT_EQ(NULL, rxRuntimeConfig.rcReadRawFn);
// EXPECT_EQ(NULL, rxRuntimeConfig.rcFrameStatusFn);
// EXPECT_EQ(0, rxRuntimeState.channelCount);
// EXPECT_EQ(0, rxRuntimeState.rxRefreshRate);
// EXPECT_EQ(NULL, rxRuntimeState.rcReadRawFn);
// EXPECT_EQ(NULL, rxRuntimeState.rcFrameStatusFn);
EXPECT_EQ(18, rxRuntimeConfig.channelCount);
EXPECT_EQ(20000, rxRuntimeConfig.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcFrameStatusFn);
EXPECT_EQ(18, rxRuntimeState.channelCount);
EXPECT_EQ(20000, rxRuntimeState.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeState.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeState.rcFrameStatusFn);
}
TEST_F(IbusRxInitUnitTest, Test_IbusRxEnabled)
{
const rxConfig_t initialRxConfig = {};
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
findSerialPortConfig_stub_retval = &serialTestInstanceConfig;
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeState));
EXPECT_EQ(18, rxRuntimeConfig.channelCount);
EXPECT_EQ(20000, rxRuntimeConfig.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcFrameStatusFn);
EXPECT_EQ(18, rxRuntimeState.channelCount);
EXPECT_EQ(20000, rxRuntimeState.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeState.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeState.rcFrameStatusFn);
EXPECT_TRUE(openSerial_called);
}
@ -240,7 +240,7 @@ TEST_F(IbusRxInitUnitTest, Test_IbusRxEnabled)
class IbusRxProtocollUnitTest : public ::testing::Test
{
protected:
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
virtual void SetUp()
{
serialTestResetPort();
@ -252,20 +252,20 @@ protected:
const rxConfig_t initialRxConfig = {};
findSerialPortConfig_stub_retval = &serialTestInstanceConfig;
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeState));
EXPECT_TRUE(initSharedIbusTelemetryCalled);
//handle that internal ibus position is not set to zero at init
microseconds_stub_value += 5000;
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
}
virtual void receivePacket(uint8_t const * const packet, const size_t length)
{
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
for (size_t i=0; i < length; i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
}
@ -274,7 +274,7 @@ protected:
TEST_F(IbusRxProtocollUnitTest, Test_InitialFrameState)
{
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//TODO: is it ok to have undefined channel values after init?
}
@ -289,17 +289,17 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived)
0x84, 0xfd}; //checksum
for (size_t i=0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
//report frame complete once
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have been updated
for (int i=0; i<18; i++) {
ASSERT_EQ(i, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_EQ(i, rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -314,16 +314,16 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceivedWithBadCrc)
isChecksumOkReturnValue = false;
for (size_t i=0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
//no frame complete
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have not been updated
for (int i=0; i<14; i++) {
ASSERT_NE(i + (0x33 << 8), rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_NE(i + (0x33 << 8), rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -340,25 +340,25 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_HalfPacketReceived_then_interPacketGap
0x84, 0xff}; //checksum
for (size_t i=0; i < sizeof(packet_half); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet_half[i], NULL);
}
microseconds_stub_value += 5000;
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
for (size_t i=0; i < sizeof(packet_full); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet_full[i], NULL);
}
//report frame complete once
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have been updated
for (int i=0; i<14; i++) {
ASSERT_EQ(i, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_EQ(i, rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -372,17 +372,17 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceived)
0x5b, 0x00}; //checksum
for (size_t i=0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
//report frame complete once
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have been updated
for (int i=0; i<14; i++) {
ASSERT_EQ(i, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_EQ(i, rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -396,16 +396,16 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6_OnePacketReceivedBadCrc)
0x00, 0x00}; //checksum
for (size_t i=0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
//no frame complete
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have not been updated
for (int i=0; i<14; i++) {
ASSERT_NE(i + (0x33 << 8), rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_NE(i + (0x33 << 8), rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -429,26 +429,26 @@ TEST_F(IbusRxProtocollUnitTest, Test_IA6B_OnePacketReceived_not_shared_port)
const rxConfig_t initialRxConfig = {};
findSerialPortConfig_stub_retval = &serialTestInstanceConfig;
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_TRUE(ibusInit(&initialRxConfig, &rxRuntimeState));
EXPECT_FALSE(initSharedIbusTelemetryCalled);
//handle that internal ibus position is not set to zero at init
microseconds_stub_value += 5000;
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
}
for (size_t i=0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
//report frame complete once
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
//check that channel values have been updated
for (int i=0; i<14; i++) {
ASSERT_EQ(i, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_EQ(i, rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -461,7 +461,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryPacketReceived)
receivePacket(packet, sizeof(packet));
//no frame complete signal to rx system, but telemetry system is called
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_TRUE(stubTelemetryCalled);
EXPECT_TRUE( 0 == memcmp( stubTelemetryPacket, packet, sizeof(packet)));
}
@ -475,12 +475,12 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx)
//given one packet received, that will respond with four characters to be ignored
receivePacket(packet, sizeof(packet));
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
EXPECT_TRUE(stubTelemetryCalled);
//when those four bytes are sent and looped back
resetStubTelemetry();
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
receivePacket(packet, sizeof(packet));
//then they are ignored
@ -488,7 +488,7 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryIgnoreTxEchoToRx)
//and then next packet can be received
receivePacket(packet, sizeof(packet));
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
EXPECT_TRUE(stubTelemetryCalled);
}
@ -501,16 +501,16 @@ TEST_F(IbusRxProtocollUnitTest, Test_OneTelemetryShouldNotIgnoreTxEchoAfterInter
//given one packet received, that will respond with four characters to be ignored
receivePacket(packet, sizeof(packet));
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
EXPECT_TRUE(stubTelemetryCalled);
//when there is an interPacketGap
microseconds_stub_value += 5000;
resetStubTelemetry();
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
//then next packet can be received
receivePacket(packet, sizeof(packet));
rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
EXPECT_TRUE(stubTelemetryCalled);
}

View file

@ -111,80 +111,80 @@ void failsafeOnRxResume(void) {}
uint32_t micros(void) { return 0; }
uint32_t millis(void) { return 0; }
void rxPwmInit(rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
void rxPwmInit(rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
}
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sbusInit(rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(initialRxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool spektrumInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sumdInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool sumhInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool crsfRxInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool jetiExBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool ibusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool xBusInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig, rcReadRawDataFnPtr *callback)
bool rxMspInit(rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState, rcReadRawDataFnPtr *callback)
{
UNUSED(rxConfig);
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(callback);
return true;
}

View file

@ -225,16 +225,16 @@ extern "C" {
void resetPPMDataReceivedState(void) {}
bool rxMspFrameComplete(void) { return false; }
void crsfRxInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void ibusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void jetiExBusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sbusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void spektrumInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sumdInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void sumhInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void xBusInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void rxMspInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void rxPwmInit(const rxConfig_t *, rxRuntimeConfig_t *) {}
void crsfRxInit(const rxConfig_t *, rxRuntimeState_t *) {}
void ibusInit(const rxConfig_t *, rxRuntimeState_t *) {}
void jetiExBusInit(const rxConfig_t *, rxRuntimeState_t *) {}
void sbusInit(const rxConfig_t *, rxRuntimeState_t *) {}
void spektrumInit(const rxConfig_t *, rxRuntimeState_t *) {}
void sumdInit(const rxConfig_t *, rxRuntimeState_t *) {}
void sumhInit(const rxConfig_t *, rxRuntimeState_t *) {}
void xBusInit(const rxConfig_t *, rxRuntimeState_t *) {}
void rxMspInit(const rxConfig_t *, rxRuntimeState_t *) {}
void rxPwmInit(const rxConfig_t *, rxRuntimeState_t *) {}
float pt1FilterGain(float f_cut, float dT)
{
UNUSED(f_cut);

View file

@ -85,7 +85,7 @@ extern "C" {
extern bool isError = false;
static const dsmReceiver_t empty = dsmReceiver_t();
static rxRuntimeConfig_t config = rxRuntimeConfig_t();
static rxRuntimeState_t config = rxRuntimeState_t();
static uint8_t packetLen;
static uint8_t packet[16];
static uint16_t rssi = 0;

View file

@ -151,30 +151,30 @@ protected:
TEST_F(SumdRxInitUnitTest, Test_SumdRxNotEnabled)
{
const rxConfig_t initialRxConfig = {};
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
findSerialPortConfig_stub_retval = NULL;
EXPECT_FALSE(sumdInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_FALSE(sumdInit(&initialRxConfig, &rxRuntimeState));
EXPECT_EQ(18, rxRuntimeConfig.channelCount);
EXPECT_EQ(11000, rxRuntimeConfig.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcFrameStatusFn);
EXPECT_EQ(18, rxRuntimeState.channelCount);
EXPECT_EQ(11000, rxRuntimeState.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeState.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeState.rcFrameStatusFn);
}
TEST_F(SumdRxInitUnitTest, Test_SumdRxEnabled)
{
const rxConfig_t initialRxConfig = {};
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
findSerialPortConfig_stub_retval = &serialTestInstanceConfig;
EXPECT_TRUE(sumdInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_TRUE(sumdInit(&initialRxConfig, &rxRuntimeState));
EXPECT_EQ(18, rxRuntimeConfig.channelCount);
EXPECT_EQ(11000, rxRuntimeConfig.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeConfig.rcFrameStatusFn);
EXPECT_EQ(18, rxRuntimeState.channelCount);
EXPECT_EQ(11000, rxRuntimeState.rxRefreshRate);
EXPECT_FALSE(NULL == rxRuntimeState.rcReadRawFn);
EXPECT_FALSE(NULL == rxRuntimeState.rcFrameStatusFn);
EXPECT_TRUE(openSerial_called);
}
@ -184,7 +184,7 @@ TEST_F(SumdRxInitUnitTest, Test_SumdRxEnabled)
class SumdRxProtocollUnitTest : public ::testing::Test
{
protected:
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
virtual void SetUp()
{
serialTestResetPort();
@ -192,22 +192,22 @@ protected:
const rxConfig_t initialRxConfig = {};
findSerialPortConfig_stub_retval = &serialTestInstanceConfig;
EXPECT_TRUE(sumdInit(&initialRxConfig, &rxRuntimeConfig));
EXPECT_TRUE(sumdInit(&initialRxConfig, &rxRuntimeState));
microseconds_stub_value += 5000;
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
}
virtual void checkValidChannels()
{
//report frame complete once
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
ASSERT_EQ(900, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 0));
ASSERT_EQ(1100, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 1));
ASSERT_EQ(1500, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 2));
ASSERT_EQ(1900, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 3));
ASSERT_EQ(2100, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 4));
ASSERT_EQ(900, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 0));
ASSERT_EQ(1100, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 1));
ASSERT_EQ(1500, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 2));
ASSERT_EQ(1900, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 3));
ASSERT_EQ(2100, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 4));
}
/*
@ -227,7 +227,7 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
checkValidChannels();
@ -247,7 +247,7 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
checkValidChannels();
@ -264,7 +264,7 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
@ -280,15 +280,15 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
EXPECT_EQ(RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_COMPLETE | RX_FRAME_FAILSAFE, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
for (size_t i = 0; i < 8; i++) {
ASSERT_EQ(1500, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, i));
ASSERT_EQ(1500, rxRuntimeState.rcReadRawFn(&rxRuntimeState, i));
}
}
@ -303,17 +303,17 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
ASSERT_EQ(900, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 0));
ASSERT_EQ(1100, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 1));
ASSERT_EQ(1500, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 2));
ASSERT_EQ(1900, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 3));
ASSERT_EQ(2100, rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, 4));
ASSERT_EQ(900, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 0));
ASSERT_EQ(1100, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 1));
ASSERT_EQ(1500, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 2));
ASSERT_EQ(1900, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 3));
ASSERT_EQ(2100, rxRuntimeState.rcReadRawFn(&rxRuntimeState, 4));
}
virtual void sendIncompletePacket()
@ -323,13 +323,13 @@ protected:
};
for (size_t i = 0; i < sizeof(packet); i++) {
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
stub_serialRxCallback(packet[i], NULL);
}
microseconds_stub_value += 5000;
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig));
EXPECT_EQ(RX_FRAME_PENDING, rxRuntimeState.rcFrameStatusFn(&rxRuntimeState));
}
};

View file

@ -71,7 +71,7 @@ extern "C" {
uint32_t targetPidLooptime;
bool cmsInMenu = false;
float axisPID_P[3], axisPID_I[3], axisPID_D[3], axisPIDSum[3];
rxRuntimeConfig_t rxRuntimeConfig = {};
rxRuntimeState_t rxRuntimeState = {};
}
uint32_t simulationFeatureFlags = 0;