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

@ -3314,13 +3314,13 @@ static void cliBeeper(char *cmdline)
#if defined(USE_RX_SPI) || defined (USE_SERIALRX_SRXL2)
void cliRxBind(char *cmdline){
UNUSED(cmdline);
switch (rxRuntimeConfig.rxProvider) {
switch (rxRuntimeState.rxProvider) {
default:
cliPrint("Not supported.");
break;
case RX_PROVIDER_SERIAL:
switch (rxRuntimeConfig.serialrxProvider) {
switch (rxRuntimeState.serialrxProvider) {
default:
cliPrint("Not supported.");
break;

View File

@ -293,10 +293,10 @@ void tasksInit(void)
#ifdef USE_TELEMETRY
if (featureIsEnabled(FEATURE_TELEMETRY)) {
setTaskEnabled(TASK_TELEMETRY, true);
if (rxRuntimeConfig.serialrxProvider == SERIALRX_JETIEXBUS) {
if (rxRuntimeState.serialrxProvider == SERIALRX_JETIEXBUS) {
// Reschedule telemetry to 500hz for Jeti Exbus
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
} else if (rxRuntimeConfig.serialrxProvider == SERIALRX_CRSF) {
} else if (rxRuntimeState.serialrxProvider == SERIALRX_CRSF) {
// Reschedule telemetry to 500hz, 2ms for CRSF
rescheduleTask(TASK_TELEMETRY, TASK_PERIOD_HZ(500));
}

View File

@ -202,7 +202,7 @@ int16_t determineServoMiddleOrForwardFromChannel(servoIndex_e servoIndex)
{
const uint8_t channelToForwardFrom = servoParams(servoIndex)->forwardFromChannel;
if (channelToForwardFrom != CHANNEL_FORWARDING_DISABLED && channelToForwardFrom < rxRuntimeConfig.channelCount) {
if (channelToForwardFrom != CHANNEL_FORWARDING_DISABLED && channelToForwardFrom < rxRuntimeState.channelCount) {
return rcData[channelToForwardFrom];
}

View File

@ -261,12 +261,12 @@ static void drawRxChannel(uint8_t channelIndex, uint8_t width)
#define RX_CHANNELS_PER_PAGE_COUNT 14
static void showRxPage(void)
{
for (int channelIndex = 0; channelIndex < rxRuntimeConfig.channelCount && channelIndex < RX_CHANNELS_PER_PAGE_COUNT; channelIndex += 2) {
for (int channelIndex = 0; channelIndex < rxRuntimeState.channelCount && channelIndex < RX_CHANNELS_PER_PAGE_COUNT; channelIndex += 2) {
i2c_OLED_set_line(bus, (channelIndex / 2) + PAGE_TITLE_LINE_COUNT);
drawRxChannel(channelIndex, HALF_SCREEN_CHARACTER_COLUMN_COUNT);
if (channelIndex >= rxRuntimeConfig.channelCount) {
if (channelIndex >= rxRuntimeState.channelCount) {
continue;
}

View File

@ -1066,7 +1066,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
break;
case MSP_RC:
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
for (int i = 0; i < rxRuntimeState.channelCount; i++) {
sbufWriteU16(dst, rcData[i]);
}
break;
@ -1368,7 +1368,7 @@ static bool mspProcessOutCommand(uint8_t cmdMSP, sbuf_t *dst)
break;
case MSP_RXFAIL_CONFIG:
for (int i = 0; i < rxRuntimeConfig.channelCount; i++) {
for (int i = 0; i < rxRuntimeState.channelCount; i++) {
sbufWriteU8(dst, rxFailsafeChannelConfigs(i)->mode);
sbufWriteU16(dst, RXFAIL_STEP_TO_CHANNEL_VALUE(rxFailsafeChannelConfigs(i)->step));
}

View File

@ -354,7 +354,7 @@ static rx_spi_received_e flySkyReadAndProcess(uint8_t *payload, const uint32_t t
return result;
}
bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState)
{
IO_t extiPin = IOGetByTag(rxSpiConfig->extiIoTag);
if (!extiPin) {
@ -368,14 +368,14 @@ bool flySkyInit(const rxSpiConfig_t *rxSpiConfig, struct rxRuntimeConfig_s *rxRu
uint8_t startRxChannel;
if (protocol == RX_SPI_A7105_FLYSKY_2A) {
rxRuntimeConfig->channelCount = FLYSKY_2A_CHANNEL_COUNT;
rxRuntimeState->channelCount = FLYSKY_2A_CHANNEL_COUNT;
timings = &flySky2ATimings;
rxId = U_ID_0 ^ U_ID_1 ^ U_ID_2;
startRxChannel = flySky2ABindChannels[0];
A7105Init(0x5475c52A, extiPin, IO_NONE);
A7105Config(flySky2ARegs, sizeof(flySky2ARegs));
} else {
rxRuntimeConfig->channelCount = FLYSKY_CHANNEL_COUNT;
rxRuntimeState->channelCount = FLYSKY_CHANNEL_COUNT;
timings = &flySkyTimings;
startRxChannel = 0;
A7105Init(0x5475c52A, extiPin, IO_NONE);

View File

@ -31,7 +31,7 @@ typedef struct flySkyConfig_s {
PG_DECLARE(flySkyConfig_t, flySkyConfig);
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool flySkyInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool flySkyInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState);
void flySkySetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e flySkyDataReceived(uint8_t *payload);

View File

@ -22,7 +22,7 @@
#include "rx/rx_spi.h"
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState);
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet);
rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet);
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload);

View File

@ -418,7 +418,7 @@ void nextChannel(uint8_t skip)
}
}
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxSpiCommonIOInit(rxSpiConfig);
if (!cc2500SpiInit()) {
@ -429,7 +429,7 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntime
switch (spiProtocol) {
case RX_SPI_FRSKY_D:
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_D;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_FRSKY_D;
handlePacket = frSkyDHandlePacket;
setRcData = frSkyDSetRcData;
@ -438,7 +438,7 @@ bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntime
break;
case RX_SPI_FRSKY_X:
case RX_SPI_FRSKY_X_LBT:
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
handlePacket = frSkyXHandlePacket;
#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)

View File

@ -423,13 +423,13 @@ rx_spi_received_e sfhssSpiDataReceived(uint8_t *packet)
return ret;
}
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxSpiCommonIOInit(rxSpiConfig);
cc2500SpiInit();
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_SFHSS;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_SFHSS;
start_time = millis();
SET_STATE(STATE_INIT);

View File

@ -48,7 +48,7 @@ typedef struct rxSfhssSpiConfig_s {
PG_DECLARE(rxSfhssSpiConfig_t, rxSfhssSpiConfig);
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool sfhssSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState);
rx_spi_received_e sfhssSpiDataReceived(uint8_t *packet);
void sfhssSpiSetRcData(uint16_t *rcData, const uint8_t *payload);

View File

@ -301,9 +301,9 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
}
}
STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
#if defined(USE_CRSF_LINK_STATISTICS)
crsfCheckRssi(micros());
@ -340,9 +340,9 @@ STATIC_UNIT_TESTED uint8_t crsfFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return RX_FRAME_PENDING;
}
STATIC_UNIT_TESTED uint16_t crsfReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
STATIC_UNIT_TESTED uint16_t crsfReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
/* conversion from RC value to PWM
* RC PWM
* min 172 -> 988us
@ -370,17 +370,17 @@ void crsfRxSendTelemetryData(void)
}
}
bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
for (int ii = 0; ii < CRSF_MAX_CHANNEL; ++ii) {
crsfChannelData[ii] = (16 * rxConfig->midrc) / 10 - 1408;
}
rxRuntimeConfig->channelCount = CRSF_MAX_CHANNEL;
rxRuntimeConfig->rxRefreshRate = CRSF_TIME_BETWEEN_FRAMES_US; //!!TODO this needs checking
rxRuntimeState->channelCount = CRSF_MAX_CHANNEL;
rxRuntimeState->rxRefreshRate = CRSF_TIME_BETWEEN_FRAMES_US; //!!TODO this needs checking
rxRuntimeConfig->rcReadRawFn = crsfReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = crsfFrameStatus;
rxRuntimeState->rcReadRawFn = crsfReadRawRC;
rxRuntimeState->rcFrameStatusFn = crsfFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -44,6 +44,6 @@ void crsfRxWriteTelemetryData(const void *data, int len);
void crsfRxSendTelemetryData(void);
struct rxConfig_s;
struct rxRuntimeConfig_s;
bool crsfRxInit(const struct rxConfig_s *initialRxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool crsfRxInit(const struct rxConfig_s *initialRxConfig, struct rxRuntimeState_s *rxRuntimeState);
bool crsfRxIsActive(void);

View File

@ -372,7 +372,7 @@ static void dsmReceiverStartTransfer(void)
cyrf6936StartRecv();
}
bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig)
bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState)
{
IO_t extiPin = IOGetByTag(rxConfig->extiIoTag);
if (!extiPin) {
@ -381,7 +381,7 @@ bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeConfi
rxSpiCommonIOInit(rxConfig);
rxRuntimeConfig->channelCount = DSM_MAX_CHANNEL_COUNT;
rxRuntimeState->channelCount = DSM_MAX_CHANNEL_COUNT;
if (!cyrf6936Init(extiPin)) {
return false;

View File

@ -48,6 +48,6 @@ typedef struct spektrumConfig_s {
PG_DECLARE(spektrumConfig_t, spektrumConfig);
bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
bool spektrumSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState);
void spektrumSpiSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e spektrumSpiDataReceived(uint8_t *payload);

View File

@ -252,7 +252,7 @@ static bool checkChecksum(uint8_t *data, uint8_t length)
return checksum == FPORT_CRC_VALUE;
}
static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t fportFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
static bool hasTelemetryRequest = false;
@ -281,7 +281,7 @@ static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
if (frameLength != FPORT_FRAME_PAYLOAD_LENGTH_CONTROL) {
reportFrameError(DEBUG_FPORT_ERROR_TYPE_SIZE);
} else {
result = sbusChannelsDecode(rxRuntimeConfig, &frame->data.controlData.channels);
result = sbusChannelsDecode(rxRuntimeState, &frame->data.controlData.channels);
setRssi(scaleRange(frame->data.controlData.rssi, 0, 100, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_PROTOCOL);
@ -359,9 +359,9 @@ static uint8_t fportFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return result;
}
static bool fportProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
static bool fportProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
#if defined(USE_TELEMETRY_SMARTPORT)
static timeUs_t lastTelemetryFrameSentUs;
@ -390,17 +390,17 @@ static bool fportProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
return true;
}
bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
rxRuntimeConfig->channelData = sbusChannelData;
sbusChannelsInit(rxConfig, rxRuntimeConfig);
rxRuntimeState->channelData = sbusChannelData;
sbusChannelsInit(rxConfig, rxRuntimeState);
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
rxRuntimeConfig->rxRefreshRate = 11000;
rxRuntimeState->channelCount = SBUS_MAX_CHANNEL;
rxRuntimeState->rxRefreshRate = 11000;
rxRuntimeConfig->rcFrameStatusFn = fportFrameStatus;
rxRuntimeConfig->rcProcessFrameFn = fportProcessFrame;
rxRuntimeState->rcFrameStatusFn = fportFrameStatus;
rxRuntimeState->rcProcessFrameFn = fportProcessFrame;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -20,4 +20,4 @@
#pragma once
bool fportRxInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool fportRxInit(const rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -167,9 +167,9 @@ static void updateChannelData(void) {
}
}
static uint8_t ibusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t ibusFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
uint8_t frameStatus = RX_FRAME_PENDING;
@ -196,23 +196,23 @@ static uint8_t ibusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
}
static uint16_t ibusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t ibusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return ibusChannelData[chan];
}
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
ibusSyncByte = 0;
rxRuntimeConfig->channelCount = IBUS_MAX_CHANNEL;
rxRuntimeConfig->rxRefreshRate = 20000; // TODO - Verify speed
rxRuntimeState->channelCount = IBUS_MAX_CHANNEL;
rxRuntimeState->rxRefreshRate = 20000; // TODO - Verify speed
rxRuntimeConfig->rcReadRawFn = ibusReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = ibusFrameStatus;
rxRuntimeState->rcReadRawFn = ibusReadRawRC;
rxRuntimeState->rcFrameStatusFn = ibusFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -20,4 +20,4 @@
#pragma once
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -225,9 +225,9 @@ static void jetiExBusDataReceive(uint16_t c, void *data)
}
// Check if it is time to read a frame from the data...
static uint8_t jetiExBusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t jetiExBusFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (jetiExBusFrameState != EXBUS_STATE_RECEIVED)
return RX_FRAME_PENDING;
@ -242,23 +242,23 @@ static uint8_t jetiExBusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
}
}
static uint16_t jetiExBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t jetiExBusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
if (chan >= rxRuntimeConfig->channelCount)
if (chan >= rxRuntimeState->channelCount)
return 0;
return (jetiExBusChannelData[chan]);
}
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeConfig->channelCount = JETIEXBUS_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 5500;
rxRuntimeState->channelCount = JETIEXBUS_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 5500;
rxRuntimeConfig->rcReadRawFn = jetiExBusReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = jetiExBusFrameStatus;
rxRuntimeState->rcReadRawFn = jetiExBusReadRawRC;
rxRuntimeState->rcFrameStatusFn = jetiExBusFrameStatus;
jetiExBusFrameReset();

View File

@ -52,4 +52,4 @@ struct serialPort_s;
extern struct serialPort_s *jetiExBusPort;
uint16_t jetiExBusCalcCRC16(uint8_t *pt, uint8_t msgLen);
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -36,9 +36,9 @@
static uint16_t mspFrame[MAX_SUPPORTED_RC_CHANNEL_COUNT];
static bool rxMspFrameDone = false;
static uint16_t rxMspReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t rxMspReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return mspFrame[chan];
}
@ -59,9 +59,9 @@ void rxMspFrameReceive(uint16_t *frame, int channelCount)
rxMspFrameDone = true;
}
static uint8_t rxMspFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t rxMspFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (!rxMspFrameDone) {
return RX_FRAME_PENDING;
@ -71,14 +71,14 @@ static uint8_t rxMspFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return RX_FRAME_COMPLETE;
}
void rxMspInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
void rxMspInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 20000;
rxRuntimeState->channelCount = MAX_SUPPORTED_RC_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 20000;
rxRuntimeConfig->rcReadRawFn = rxMspReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = rxMspFrameStatus;
rxRuntimeState->rcReadRawFn = rxMspReadRawRC;
rxRuntimeState->rcFrameStatusFn = rxMspFrameStatus;
}
#endif

View File

@ -21,6 +21,6 @@
#pragma once
struct rxConfig_s;
struct rxRuntimeConfig_s;
void rxMspInit(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
void rxMspInit(const struct rxConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState);
void rxMspFrameReceive(uint16_t *frame, int channelCount);

View File

@ -299,9 +299,9 @@ static void cx10Nrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
}
bool cx10Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool cx10Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT;
cx10Nrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
return true;

View File

@ -24,7 +24,7 @@
#include <stdint.h>
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool cx10Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool cx10Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState);
void cx10Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e cx10Nrf24DataReceived(uint8_t *payload);

View File

@ -283,9 +283,9 @@ static void h8_3dNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId)
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
}
bool h8_3dNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool h8_3dNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT;
h8_3dNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol, &rxSpiConfig->rx_spi_id);
return true;

View File

@ -24,7 +24,7 @@
#include <stdint.h>
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool h8_3dNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool h8_3dNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState);
void h8_3dNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e h8_3dNrf24DataReceived(uint8_t *payload);

View File

@ -424,9 +424,9 @@ static void inavNrf24Setup(rx_spi_protocol_e protocol, const uint32_t *rxSpiId,
writeAckPayload(ackPayload, payloadSize);
}
bool inavNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool inavNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_MAX;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT_MAX;
inavNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol, &rxSpiConfig->rx_spi_id, rxSpiConfig->rx_spi_rf_channel_count);
return true;

View File

@ -24,8 +24,8 @@
#include <stdint.h>
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool inavNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool inavNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState);
void inavNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e inavNrf24DataReceived(uint8_t *payload);

View File

@ -204,9 +204,9 @@ static void knNrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
}
bool knNrf24Init(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool knNrf24Init(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = KN_RC_CHANNEL_COUNT;
rxRuntimeState->channelCount = KN_RC_CHANNEL_COUNT;
knNrf24Setup((rx_spi_protocol_e)rxConfig->rx_spi_protocol);
return true;

View File

@ -24,7 +24,7 @@
#include <stdint.h>
struct rxConfig_s;
struct rxRuntimeConfig_s;
bool knNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool knNrf24Init(const struct rxConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState);
void knNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e knNrf24DataReceived(uint8_t *payload);

View File

@ -299,9 +299,9 @@ static void symaNrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
}
bool symaNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool symaNrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT;
rxRuntimeState->channelCount = RC_CHANNEL_COUNT;
symaNrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
return true;

View File

@ -24,8 +24,8 @@
#include <stdint.h>
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool symaNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool symaNrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState);
void symaNrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e symaNrf24DataReceived(uint8_t *payload);

View File

@ -259,9 +259,9 @@ static void v202Nrf24Setup(rx_spi_protocol_e protocol)
NRF24L01_SetRxMode(); // enter receive mode to start listening for packets
}
bool v202Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool v202Nrf24Init(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->channelCount = V2X2_RC_CHANNEL_COUNT;
rxRuntimeState->channelCount = V2X2_RC_CHANNEL_COUNT;
v202Nrf24Setup((rx_spi_protocol_e)rxSpiConfig->rx_spi_protocol);
return true;

View File

@ -24,7 +24,7 @@
#include <stdint.h>
struct rxSpiConfig_s;
struct rxRuntimeConfig_s;
bool v202Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
bool v202Nrf24Init(const struct rxSpiConfig_s *rxSpiConfig, struct rxRuntimeState_s *rxRuntimeState);
void v202Nrf24SetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload);
rx_spi_received_e v202Nrf24DataReceived(uint8_t *payload);

View File

@ -41,37 +41,37 @@
#include "rx/rx.h"
#include "rx/pwm.h"
static uint16_t pwmReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
static uint16_t pwmReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t channel)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return pwmRead(channel);
}
static uint16_t ppmReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
static uint16_t ppmReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t channel)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return ppmRead(channel);
}
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeConfig->rxRefreshRate = 20000;
rxRuntimeState->rxRefreshRate = 20000;
// configure PWM/CPPM read function and max number of channels. serial rx below will override both of these, if enabled
switch (rxRuntimeConfig->rxProvider) {
switch (rxRuntimeState->rxProvider) {
default:
break;
case RX_PROVIDER_PARALLEL_PWM:
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
rxRuntimeConfig->rcReadRawFn = pwmReadRawRC;
rxRuntimeState->channelCount = MAX_SUPPORTED_RC_PARALLEL_PWM_CHANNEL_COUNT;
rxRuntimeState->rcReadRawFn = pwmReadRawRC;
break;
case RX_PROVIDER_PPM:
rxRuntimeConfig->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
rxRuntimeConfig->rcReadRawFn = ppmReadRawRC;
rxRuntimeState->channelCount = MAX_SUPPORTED_RC_PPM_CHANNEL_COUNT;
rxRuntimeState->rcReadRawFn = ppmReadRawRC;
break;
}

View File

@ -20,4 +20,4 @@
#pragma once
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
void rxPwmInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -118,7 +118,7 @@ uint32_t rcInvalidPulsPeriod[MAX_SUPPORTED_RC_CHANNEL_COUNT];
#define SKIP_RC_ON_SUSPEND_PERIOD 1500000 // 1.5 second period in usec (call frequency independent)
#define SKIP_RC_SAMPLES_ON_RESUME 2 // flush 2 samples to drop wrong measurements (timing independent)
rxRuntimeConfig_t rxRuntimeConfig;
rxRuntimeState_t rxRuntimeState;
static uint8_t rcSampleIndex = 0;
PG_REGISTER_ARRAY_WITH_RESET_FN(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs, PG_RX_CHANNEL_RANGE_CONFIG, 0);
@ -151,24 +151,24 @@ void resetAllRxChannelRangeConfigurations(rxChannelRangeConfig_t *rxChannelRange
}
}
static uint16_t nullReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
static uint16_t nullReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t channel)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
UNUSED(channel);
return PPM_RCVR_TIMEOUT;
}
static uint8_t nullFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t nullFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return RX_FRAME_PENDING;
}
static bool nullProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
static bool nullProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return true;
}
@ -180,66 +180,66 @@ STATIC_UNIT_TESTED bool isPulseValid(uint16_t pulseDuration)
}
#ifdef USE_SERIAL_RX
static bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
static bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
bool enabled = false;
switch (rxRuntimeConfig->serialrxProvider) {
switch (rxRuntimeState->serialrxProvider) {
#ifdef USE_SERIALRX_SRXL2
case SERIALRX_SRXL2:
enabled = srxl2RxInit(rxConfig, rxRuntimeConfig);
enabled = srxl2RxInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_SPEKTRUM
case SERIALRX_SRXL:
case SERIALRX_SPEKTRUM1024:
case SERIALRX_SPEKTRUM2048:
enabled = spektrumInit(rxConfig, rxRuntimeConfig);
enabled = spektrumInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_SBUS
case SERIALRX_SBUS:
enabled = sbusInit(rxConfig, rxRuntimeConfig);
enabled = sbusInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_SUMD
case SERIALRX_SUMD:
enabled = sumdInit(rxConfig, rxRuntimeConfig);
enabled = sumdInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_SUMH
case SERIALRX_SUMH:
enabled = sumhInit(rxConfig, rxRuntimeConfig);
enabled = sumhInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_XBUS
case SERIALRX_XBUS_MODE_B:
case SERIALRX_XBUS_MODE_B_RJ01:
enabled = xBusInit(rxConfig, rxRuntimeConfig);
enabled = xBusInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_IBUS
case SERIALRX_IBUS:
enabled = ibusInit(rxConfig, rxRuntimeConfig);
enabled = ibusInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_JETIEXBUS
case SERIALRX_JETIEXBUS:
enabled = jetiExBusInit(rxConfig, rxRuntimeConfig);
enabled = jetiExBusInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_CRSF
case SERIALRX_CRSF:
enabled = crsfRxInit(rxConfig, rxRuntimeConfig);
enabled = crsfRxInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_TARGET_CUSTOM
case SERIALRX_TARGET_CUSTOM:
enabled = targetCustomSerialRxInit(rxConfig, rxRuntimeConfig);
enabled = targetCustomSerialRxInit(rxConfig, rxRuntimeState);
break;
#endif
#ifdef USE_SERIALRX_FPORT
case SERIALRX_FPORT:
enabled = fportRxInit(rxConfig, rxRuntimeConfig);
enabled = fportRxInit(rxConfig, rxRuntimeState);
break;
#endif
default:
@ -253,22 +253,22 @@ static bool serialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntim
void rxInit(void)
{
if (featureIsEnabled(FEATURE_RX_PARALLEL_PWM)) {
rxRuntimeConfig.rxProvider = RX_PROVIDER_PARALLEL_PWM;
rxRuntimeState.rxProvider = RX_PROVIDER_PARALLEL_PWM;
} else if (featureIsEnabled(FEATURE_RX_PPM)) {
rxRuntimeConfig.rxProvider = RX_PROVIDER_PPM;
rxRuntimeState.rxProvider = RX_PROVIDER_PPM;
} else if (featureIsEnabled(FEATURE_RX_SERIAL)) {
rxRuntimeConfig.rxProvider = RX_PROVIDER_SERIAL;
rxRuntimeState.rxProvider = RX_PROVIDER_SERIAL;
} else if (featureIsEnabled(FEATURE_RX_MSP)) {
rxRuntimeConfig.rxProvider = RX_PROVIDER_MSP;
rxRuntimeState.rxProvider = RX_PROVIDER_MSP;
} else if (featureIsEnabled(FEATURE_RX_SPI)) {
rxRuntimeConfig.rxProvider = RX_PROVIDER_SPI;
rxRuntimeState.rxProvider = RX_PROVIDER_SPI;
} else {
rxRuntimeConfig.rxProvider = RX_PROVIDER_NONE;
rxRuntimeState.rxProvider = RX_PROVIDER_NONE;
}
rxRuntimeConfig.serialrxProvider = rxConfig()->serialrx_provider;
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rxRuntimeConfig.rcProcessFrameFn = nullProcessFrame;
rxRuntimeState.serialrxProvider = rxConfig()->serialrx_provider;
rxRuntimeState.rcReadRawFn = nullReadRawRC;
rxRuntimeState.rcFrameStatusFn = nullFrameStatus;
rxRuntimeState.rcProcessFrameFn = nullProcessFrame;
rcSampleIndex = 0;
needRxSignalMaxDelayUs = DELAY_10_HZ;
@ -296,17 +296,17 @@ void rxInit(void)
}
}
switch (rxRuntimeConfig.rxProvider) {
switch (rxRuntimeState.rxProvider) {
default:
break;
#ifdef USE_SERIAL_RX
case RX_PROVIDER_SERIAL:
{
const bool enabled = serialRxInit(rxConfig(), &rxRuntimeConfig);
const bool enabled = serialRxInit(rxConfig(), &rxRuntimeState);
if (!enabled) {
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rxRuntimeState.rcReadRawFn = nullReadRawRC;
rxRuntimeState.rcFrameStatusFn = nullFrameStatus;
}
}
@ -315,7 +315,7 @@ void rxInit(void)
#ifdef USE_RX_MSP
case RX_PROVIDER_MSP:
rxMspInit(rxConfig(), &rxRuntimeConfig);
rxMspInit(rxConfig(), &rxRuntimeState);
needRxSignalMaxDelayUs = DELAY_5_HZ;
break;
@ -324,10 +324,10 @@ void rxInit(void)
#ifdef USE_RX_SPI
case RX_PROVIDER_SPI:
{
const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeConfig);
const bool enabled = rxSpiInit(rxSpiConfig(), &rxRuntimeState);
if (!enabled) {
rxRuntimeConfig.rcReadRawFn = nullReadRawRC;
rxRuntimeConfig.rcFrameStatusFn = nullFrameStatus;
rxRuntimeState.rcReadRawFn = nullReadRawRC;
rxRuntimeState.rcFrameStatusFn = nullFrameStatus;
}
}
@ -337,7 +337,7 @@ void rxInit(void)
#if defined(USE_PWM) || defined(USE_PPM)
case RX_PROVIDER_PPM:
case RX_PROVIDER_PARALLEL_PWM:
rxPwmInit(rxConfig(), &rxRuntimeConfig);
rxPwmInit(rxConfig(), &rxRuntimeState);
break;
#endif
@ -355,7 +355,7 @@ void rxInit(void)
// Setup source frame RSSI filtering to take averaged values every FRAME_ERR_RESAMPLE_US
pt1FilterInit(&frameErrFilter, pt1FilterGain(GET_FRAME_ERR_LPF_FREQUENCY(rxConfig()->rssi_src_frame_lpf_period), FRAME_ERR_RESAMPLE_US/1000000.0));
rxChannelCount = MIN(rxConfig()->max_aux_channel + NON_AUX_CHANNEL_COUNT, rxRuntimeConfig.channelCount);
rxChannelCount = MIN(rxConfig()->max_aux_channel + NON_AUX_CHANNEL_COUNT, rxRuntimeState.channelCount);
}
bool rxIsReceivingSignal(void)
@ -371,7 +371,7 @@ bool rxAreFlightChannelsValid(void)
void suspendRxPwmPpmSignal(void)
{
#if defined(USE_PWM) || defined(USE_PPM)
if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) {
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
suspendRxSignalUntil = micros() + SKIP_RC_ON_SUSPEND_PERIOD;
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
failsafeOnRxSuspend(SKIP_RC_ON_SUSPEND_PERIOD);
@ -382,7 +382,7 @@ void suspendRxPwmPpmSignal(void)
void resumeRxPwmPpmSignal(void)
{
#if defined(USE_PWM) || defined(USE_PPM)
if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) {
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
suspendRxSignalUntil = micros();
skipRxSamples = SKIP_RC_SAMPLES_ON_RESUME;
failsafeOnRxResume();
@ -447,7 +447,7 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
bool signalReceived = false;
bool useDataDrivenProcessing = true;
switch (rxRuntimeConfig.rxProvider) {
switch (rxRuntimeState.rxProvider) {
default:
break;
@ -475,7 +475,7 @@ bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTime)
case RX_PROVIDER_MSP:
case RX_PROVIDER_SPI:
{
const uint8_t frameStatus = rxRuntimeConfig.rcFrameStatusFn(&rxRuntimeConfig);
const uint8_t frameStatus = rxRuntimeState.rcFrameStatusFn(&rxRuntimeState);
if (frameStatus & RX_FRAME_COMPLETE) {
rxIsInFailsafeMode = (frameStatus & RX_FRAME_FAILSAFE) != 0;
bool rxFrameDropped = (frameStatus & RX_FRAME_DROPPED) != 0;
@ -586,7 +586,7 @@ static void readRxChannelsApplyRanges(void)
const uint8_t rawChannel = channel < RX_MAPPABLE_CHANNEL_COUNT ? rxConfig()->rcmap[channel] : channel;
// sample the channel
uint16_t sample = rxRuntimeConfig.rcReadRawFn(&rxRuntimeConfig, rawChannel);
uint16_t sample = rxRuntimeState.rcReadRawFn(&rxRuntimeState, rawChannel);
// apply the rx calibration
if (channel < NON_AUX_CHANNEL_COUNT) {
@ -625,7 +625,7 @@ static void detectAndApplySignalLossBehaviour(void)
}
}
#if defined(USE_PWM) || defined(USE_PPM)
if (rxRuntimeConfig.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeConfig.rxProvider == RX_PROVIDER_PPM) {
if (rxRuntimeState.rxProvider == RX_PROVIDER_PARALLEL_PWM || rxRuntimeState.rxProvider == RX_PROVIDER_PPM) {
// smooth output for PWM and PPM
rcData[channel] = calculateChannelMovingAverage(channel, sample);
} else
@ -650,7 +650,7 @@ static void detectAndApplySignalLossBehaviour(void)
bool calculateRxChannelsAndUpdateFailsafe(timeUs_t currentTimeUs)
{
if (auxiliaryProcessingRequired) {
auxiliaryProcessingRequired = !rxRuntimeConfig.rcProcessFrameFn(&rxRuntimeConfig);
auxiliaryProcessingRequired = !rxRuntimeState.rcProcessFrameFn(&rxRuntimeState);
}
if (!rxDataProcessingRequired) {
@ -855,7 +855,7 @@ uint16_t rxGetLinkQualityPercent(void)
uint16_t rxGetRefreshRate(void)
{
return rxRuntimeConfig.rxRefreshRate;
return rxRuntimeState.rxRefreshRate;
}
bool isRssiConfigured(void)

View File

@ -121,10 +121,10 @@ typedef struct rxChannelRangeConfig_s {
PG_DECLARE_ARRAY(rxChannelRangeConfig_t, NON_AUX_CHANNEL_COUNT, rxChannelRangeConfigs);
struct rxRuntimeConfig_s;
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig, uint8_t chan); // used by receiver driver to return channel data
typedef uint8_t (*rcFrameStatusFnPtr)(struct rxRuntimeConfig_s *rxRuntimeConfig);
typedef bool (*rcProcessFrameFnPtr)(const struct rxRuntimeConfig_s *rxRuntimeConfig);
struct rxRuntimeState_s;
typedef uint16_t (*rcReadRawDataFnPtr)(const struct rxRuntimeState_s *rxRuntimeState, uint8_t chan); // used by receiver driver to return channel data
typedef uint8_t (*rcFrameStatusFnPtr)(struct rxRuntimeState_s *rxRuntimeState);
typedef bool (*rcProcessFrameFnPtr)(const struct rxRuntimeState_s *rxRuntimeState);
typedef enum {
RX_PROVIDER_NONE = 0,
@ -135,7 +135,7 @@ typedef enum {
RX_PROVIDER_SPI,
} rxProvider_t;
typedef struct rxRuntimeConfig_s {
typedef struct rxRuntimeState_s {
rxProvider_t rxProvider;
SerialRXType serialrxProvider;
uint8_t channelCount; // number of RC channels as reported by current input driver
@ -145,7 +145,7 @@ typedef struct rxRuntimeConfig_s {
rcProcessFrameFnPtr rcProcessFrameFn;
uint16_t *channelData;
void *frameData;
} rxRuntimeConfig_t;
} rxRuntimeState_t;
typedef enum {
RSSI_SOURCE_NONE = 0,
@ -166,7 +166,7 @@ typedef enum {
extern linkQualitySource_e linkQualitySource;
extern rxRuntimeConfig_t rxRuntimeConfig; //!!TODO remove this extern, only needed once for channelCount
extern rxRuntimeState_t rxRuntimeState; //!!TODO remove this extern, only needed once for channelCount
void rxInit(void);
bool rxUpdateCheck(timeUs_t currentTimeUs, timeDelta_t currentDeltaTimeUs);

View File

@ -55,7 +55,7 @@ uint16_t rxSpiRcData[MAX_SUPPORTED_RC_CHANNEL_COUNT];
STATIC_UNIT_TESTED uint8_t rxSpiPayload[RX_SPI_MAX_PAYLOAD_SIZE];
STATIC_UNIT_TESTED uint8_t rxSpiNewPacketAvailable; // set true when a new packet is received
typedef bool (*protocolInitFnPtr)(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
typedef bool (*protocolInitFnPtr)(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState);
typedef rx_spi_received_e (*protocolDataReceivedFnPtr)(uint8_t *payload);
typedef rx_spi_received_e (*protocolProcessFrameFnPtr)(uint8_t *payload);
typedef void (*protocolSetRcDataFromPayloadFnPtr)(uint16_t *rcData, const uint8_t *payload);
@ -65,11 +65,11 @@ static protocolDataReceivedFnPtr protocolDataReceived;
static protocolProcessFrameFnPtr protocolProcessFrame;
static protocolSetRcDataFromPayloadFnPtr protocolSetRcDataFromPayload;
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channel)
STATIC_UNIT_TESTED uint16_t rxSpiReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t channel)
{
STATIC_ASSERT(NRF24L01_MAX_PAYLOAD_SIZE <= RX_SPI_MAX_PAYLOAD_SIZE, NRF24L01_MAX_PAYLOAD_SIZE_larger_than_RX_SPI_MAX_PAYLOAD_SIZE);
if (channel >= rxRuntimeConfig->channelCount) {
if (channel >= rxRuntimeState->channelCount) {
return 0;
}
if (rxSpiNewPacketAvailable) {
@ -174,9 +174,9 @@ STATIC_UNIT_TESTED bool rxSpiSetProtocol(rx_spi_protocol_e protocol)
* Called from updateRx in rx.c, updateRx called from taskUpdateRxCheck.
* If taskUpdateRxCheck returns true, then taskUpdateRxMain will shortly be called.
*/
static uint8_t rxSpiFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t rxSpiFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
uint8_t status = RX_FRAME_PENDING;
@ -194,9 +194,9 @@ static uint8_t rxSpiFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return status;
}
static bool rxSpiProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
static bool rxSpiProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (protocolProcessFrame) {
rx_spi_received_e result = protocolProcessFrame(rxSpiPayload);
@ -216,7 +216,7 @@ static bool rxSpiProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
/*
* Set and initialize the RX protocol
*/
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState)
{
bool ret = false;
@ -225,14 +225,14 @@ bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeCon
}
if (rxSpiSetProtocol(rxSpiConfig->rx_spi_protocol)) {
ret = protocolInit(rxSpiConfig, rxRuntimeConfig);
ret = protocolInit(rxSpiConfig, rxRuntimeState);
}
rxSpiNewPacketAvailable = false;
rxRuntimeConfig->rxRefreshRate = 20000;
rxRuntimeState->rxRefreshRate = 20000;
rxRuntimeConfig->rcReadRawFn = rxSpiReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = rxSpiFrameStatus;
rxRuntimeConfig->rcProcessFrameFn = rxSpiProcessFrame;
rxRuntimeState->rcReadRawFn = rxSpiReadRawRC;
rxRuntimeState->rcFrameStatusFn = rxSpiFrameStatus;
rxRuntimeState->rcProcessFrameFn = rxSpiProcessFrame;
return ret;
}

View File

@ -82,4 +82,4 @@ typedef enum {
#define RC_CHANNEL_HEADLESS RC_SPI_AUX5
#define RC_CHANNEL_RTH RC_SPI_AUX6 // return to home
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool rxSpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -140,9 +140,9 @@ static void sbusDataReceive(uint16_t c, void *data)
}
}
static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t sbusFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
sbusFrameData_t *sbusFrameData = rxRuntimeConfig->frameData;
sbusFrameData_t *sbusFrameData = rxRuntimeState->frameData;
if (!sbusFrameData->done) {
return RX_FRAME_PENDING;
}
@ -150,30 +150,30 @@ static uint8_t sbusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
DEBUG_SET(DEBUG_SBUS, DEBUG_SBUS_FRAME_FLAGS, sbusFrameData->frame.frame.channels.flags);
return sbusChannelsDecode(rxRuntimeConfig, &sbusFrameData->frame.frame.channels);
return sbusChannelsDecode(rxRuntimeState, &sbusFrameData->frame.frame.channels);
}
bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
static sbusFrameData_t sbusFrameData;
static uint32_t sbusBaudRate;
rxRuntimeConfig->channelData = sbusChannelData;
rxRuntimeConfig->frameData = &sbusFrameData;
sbusChannelsInit(rxConfig, rxRuntimeConfig);
rxRuntimeState->channelData = sbusChannelData;
rxRuntimeState->frameData = &sbusFrameData;
sbusChannelsInit(rxConfig, rxRuntimeState);
rxRuntimeConfig->channelCount = SBUS_MAX_CHANNEL;
rxRuntimeState->channelCount = SBUS_MAX_CHANNEL;
if (rxConfig->sbus_baud_fast) {
rxRuntimeConfig->rxRefreshRate = SBUS_FAST_RX_REFRESH_RATE;
rxRuntimeState->rxRefreshRate = SBUS_FAST_RX_REFRESH_RATE;
sbusBaudRate = SBUS_FAST_BAUDRATE;
} else {
rxRuntimeConfig->rxRefreshRate = SBUS_RX_REFRESH_RATE;
rxRuntimeState->rxRefreshRate = SBUS_RX_REFRESH_RATE;
sbusBaudRate = SBUS_BAUDRATE;
}
rxRuntimeConfig->rcFrameStatusFn = sbusFrameStatus;
rxRuntimeState->rcFrameStatusFn = sbusFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -181,7 +181,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
}
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeConfig->serialrxProvider);
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif

View File

@ -20,4 +20,4 @@
#pragma once
bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool sbusInit(const rxConfig_t *initialRxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -41,9 +41,9 @@
#define SBUS_DIGITAL_CHANNEL_MIN 173
#define SBUS_DIGITAL_CHANNEL_MAX 1812
uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels)
uint8_t sbusChannelsDecode(rxRuntimeState_t *rxRuntimeState, const sbusChannels_t *channels)
{
uint16_t *sbusChannelData = rxRuntimeConfig->channelData;
uint16_t *sbusChannelData = rxRuntimeState->channelData;
sbusChannelData[0] = channels->chan0;
sbusChannelData[1] = channels->chan1;
sbusChannelData[2] = channels->chan2;
@ -87,18 +87,18 @@ uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannel
return RX_FRAME_COMPLETE;
}
static uint16_t sbusChannelsReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sbusChannelsReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
// Linear fitting values read from OpenTX-ppmus and comparing with values received by X4R
// http://www.wolframalpha.com/input/?i=linear+fit+%7B173%2C+988%7D%2C+%7B1812%2C+2012%7D%2C+%7B993%2C+1500%7D
return (5 * rxRuntimeConfig->channelData[chan] / 8) + 880;
return (5 * rxRuntimeState->channelData[chan] / 8) + 880;
}
void sbusChannelsInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
void sbusChannelsInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfig->rcReadRawFn = sbusChannelsReadRawRC;
rxRuntimeState->rcReadRawFn = sbusChannelsReadRawRC;
for (int b = 0; b < SBUS_MAX_CHANNEL; b++) {
rxRuntimeConfig->channelData[b] = (16 * rxConfig->midrc) / 10 - 1408;
rxRuntimeState->channelData[b] = (16 * rxConfig->midrc) / 10 - 1408;
}
}
#endif

View File

@ -50,7 +50,7 @@ typedef struct sbusChannels_s {
#define SBUS_CHANNEL_DATA_LENGTH sizeof(sbusChannels_t)
uint8_t sbusChannelsDecode(rxRuntimeConfig_t *rxRuntimeConfig, const sbusChannels_t *channels);
uint8_t sbusChannelsDecode(rxRuntimeState_t *rxRuntimeState, const sbusChannels_t *channels);
void sbusChannelsInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
void sbusChannelsInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -68,7 +68,7 @@ static bool spekHiRes = false;
static volatile uint8_t spekFrame[SPEK_FRAME_SIZE];
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
static rxRuntimeState_t *rxRuntimeStatePtr;
static serialPort_t *serialPort;
#if defined(USE_TELEMETRY_SRXL)
@ -106,9 +106,9 @@ static void spektrumDataReceive(uint16_t c, void *data)
uint32_t spekChannelData[SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT];
static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t spektrumFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
#if defined(USE_TELEMETRY_SRXL)
static timeUs_t telemetryFrameRequestedUs = 0;
@ -146,7 +146,7 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
// Get the RC control channel inputs
for (int b = 3; b < spektrumRcDataSize; b += 2) {
const uint8_t spekChannel = 0x0F & (spekFrame[b - 1] >> spek_chan_shift);
if (spekChannel < rxRuntimeConfigPtr->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT) {
if (spekChannel < rxRuntimeStatePtr->channelCount && spekChannel < SPEKTRUM_MAX_SUPPORTED_CHANNEL_COUNT) {
if (rssi_channel == 0 || spekChannel != rssi_channel) {
spekChannelData[spekChannel] = ((uint32_t)(spekFrame[b - 1] & spek_chan_mask) << 8) + spekFrame[b];
}
@ -172,11 +172,11 @@ static uint8_t spektrumFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return result;
}
static uint16_t spektrumReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t spektrumReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
uint16_t data;
if (chan >= rxRuntimeConfig->channelCount) {
if (chan >= rxRuntimeState->channelCount) {
return 0;
}
@ -242,10 +242,10 @@ void spektrumBind(rxConfig_t *rxConfig)
ioTag_t rxPin = serialPinConfig()->ioTagRx[index];
// Take care half-duplex case
switch (rxRuntimeConfig.serialrxProvider) {
switch (rxRuntimeState.serialrxProvider) {
case SERIALRX_SRXL:
#if defined(USE_TELEMETRY_SRXL)
if (featureIsEnabled(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig, rxRuntimeConfig.serialrxProvider)) {
if (featureIsEnabled(FEATURE_TELEMETRY) && !telemetryCheckRxPortShared(portConfig, rxRuntimeState.serialrxProvider)) {
bindPin = txPin;
}
break;
@ -311,9 +311,9 @@ void spektrumBind(rxConfig_t *rxConfig)
#endif // USE_SPEKTRUM_BIND
#if defined(USE_TELEMETRY_SRXL)
static bool spektrumProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
static bool spektrumProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
// if there is telemetry data to write
if (telemetryBufLen > 0) {
@ -341,9 +341,9 @@ void srxlRxWriteTelemetryData(const void *data, int len)
}
#endif
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfigPtr = rxRuntimeConfig;
rxRuntimeStatePtr = rxRuntimeState;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -352,12 +352,12 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
srxlEnabled = false;
#if defined(USE_TELEMETRY_SRXL)
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeConfig->serialrxProvider);
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif
switch (rxRuntimeConfig->serialrxProvider) {
switch (rxRuntimeState->serialrxProvider) {
default:
break;
@ -372,8 +372,8 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
spek_chan_mask = 0x07;
spekHiRes = true;
resolution = 2048;
rxRuntimeConfig->channelCount = SPEKTRUM_2048_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 11000;
rxRuntimeState->channelCount = SPEKTRUM_2048_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 11000;
break;
case SERIALRX_SPEKTRUM1024:
// 10 bit frames
@ -381,15 +381,15 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
spek_chan_mask = 0x03;
spekHiRes = false;
resolution = 1024;
rxRuntimeConfig->channelCount = SPEKTRUM_1024_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 22000;
rxRuntimeState->channelCount = SPEKTRUM_1024_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 22000;
break;
}
rxRuntimeConfig->rcReadRawFn = spektrumReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = spektrumFrameStatus;
rxRuntimeState->rcReadRawFn = spektrumReadRawRC;
rxRuntimeState->rcFrameStatusFn = spektrumFrameStatus;
#if defined(USE_TELEMETRY_SRXL)
rxRuntimeConfig->rcProcessFrameFn = spektrumProcessFrame;
rxRuntimeState->rcProcessFrameFn = spektrumProcessFrame;
#endif
serialPort = openSerialPort(portConfig->identifier,
@ -409,7 +409,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig
#endif
rssi_channel = rxConfig->rssi_channel - 1; // -1 because rxConfig->rssi_channel is 1-based and rssi_channel is 0-based.
if (rssi_channel >= rxRuntimeConfig->channelCount) {
if (rssi_channel >= rxRuntimeState->channelCount) {
rssi_channel = 0;
}

View File

@ -49,7 +49,7 @@ extern int32_t resolution;
extern uint8_t rssi_channel; // Stores the RX RSSI channel.
void spektrumBind(rxConfig_t *rxConfig);
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);
bool srxlTelemetryBufferEmpty();
void srxlRxWriteTelemetryData(const void *data, int len);

View File

@ -167,7 +167,7 @@ bool srxl2ProcessHandshake(const Srxl2Header* header)
return true;
}
void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeConfig_t *rxRuntimeConfig) {
void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntimeState_t *rxRuntimeState) {
if (channelData->rssi >= 0) {
const int rssiPercent = channelData->rssi;
setRssi(scaleRange(rssiPercent, 0, 100, 0, RSSI_MAX_VALUE), RSSI_SOURCE_RX_PROTOCOL);
@ -187,14 +187,14 @@ void srxl2ProcessChannelData(const Srxl2ChannelDataHeader* channelData, rxRuntim
while (channelMask) {
unsigned idx = __builtin_ctz (channelMask);
uint32_t mask = 1 << idx;
rxRuntimeConfig->channelData[idx] = *frameChannels++;
rxRuntimeState->channelData[idx] = *frameChannels++;
channelMask &= ~mask;
}
DEBUG_PRINTF("channel data: %d %d %x\r\n", channelData_header->rssi, channelData_header->frameLosses, channelData_header->channelMask.u32);
}
bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeConfig_t *rxRuntimeConfig)
bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState)
{
const Srxl2ControlDataSubHeader* controlData = (Srxl2ControlDataSubHeader*)(header + 1);
const uint8_t ownId = (FlightController << 4) | unitId;
@ -205,11 +205,11 @@ bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeConfig_t *rxRun
switch (controlData->command) {
case ChannelData:
srxl2ProcessChannelData((const Srxl2ChannelDataHeader *) (controlData + 1), rxRuntimeConfig);
srxl2ProcessChannelData((const Srxl2ChannelDataHeader *) (controlData + 1), rxRuntimeState);
break;
case FailsafeChannelData: {
srxl2ProcessChannelData((const Srxl2ChannelDataHeader *) (controlData + 1), rxRuntimeConfig);
srxl2ProcessChannelData((const Srxl2ChannelDataHeader *) (controlData + 1), rxRuntimeState);
setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
// DEBUG_PRINTF("fs channel data\r\n");
} break;
@ -240,13 +240,13 @@ bool srxl2ProcessControlData(const Srxl2Header* header, rxRuntimeConfig_t *rxRun
return true;
}
bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeConfig_t *rxRuntimeConfig)
bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeState_t *rxRuntimeState)
{
switch (header->packetType) {
case Handshake:
return srxl2ProcessHandshake(header);
case ControlData:
return srxl2ProcessControlData(header, rxRuntimeConfig);
return srxl2ProcessControlData(header, rxRuntimeState);
default:
DEBUG_PRINTF("Other packet type, ID: %x \r\n", header->packetType);
break;
@ -256,7 +256,7 @@ bool srxl2ProcessPacket(const Srxl2Header* header, rxRuntimeConfig_t *rxRuntimeC
}
// @note assumes packet is fully there
void srxl2Process(rxRuntimeConfig_t *rxRuntimeConfig)
void srxl2Process(rxRuntimeState_t *rxRuntimeState)
{
if (processBufferPtr->packet.header.id != SRXL2_ID || processBufferPtr->len != processBufferPtr->packet.header.length) {
DEBUG_PRINTF("invalid header id: %x, or length: %x received vs %x expected \r\n", processBufferPtr->packet.header.id, processBufferPtr->len, processBufferPtr->packet.header.length);
@ -276,7 +276,7 @@ void srxl2Process(rxRuntimeConfig_t *rxRuntimeConfig)
//Packet is valid only after ID and CRC check out
lastValidPacketTimestamp = micros();
if (srxl2ProcessPacket(&processBufferPtr->packet.header, rxRuntimeConfig)) {
if (srxl2ProcessPacket(&processBufferPtr->packet.header, rxRuntimeState)) {
return;
}
@ -326,15 +326,15 @@ static void srxl2Idle()
readBufferIdx = 0;
}
static uint8_t srxl2FrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t srxl2FrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
globalResult = RX_FRAME_PENDING;
// len should only be set after an idle interrupt (packet reception complete)
if (processBufferPtr != NULL && processBufferPtr->len) {
srxl2Process(rxRuntimeConfig);
srxl2Process(rxRuntimeState);
processBufferPtr->len = 0;
}
@ -427,9 +427,9 @@ static uint8_t srxl2FrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return result;
}
static bool srxl2ProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
static bool srxl2ProcessFrame(const rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (writeBufferIdx == 0) {
return true;
@ -453,13 +453,13 @@ static bool srxl2ProcessFrame(const rxRuntimeConfig_t *rxRuntimeConfig)
return true;
}
static uint16_t srxl2ReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t channelIdx)
static uint16_t srxl2ReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t channelIdx)
{
if (channelIdx >= rxRuntimeConfig->channelCount) {
if (channelIdx >= rxRuntimeState->channelCount) {
return 0;
}
return SPEKTRUM_PULSE_OFFSET + ((rxRuntimeConfig->channelData[channelIdx] >> SRXL2_CHANNEL_SHIFT) >> 1);
return SPEKTRUM_PULSE_OFFSET + ((rxRuntimeState->channelData[channelIdx] >> SRXL2_CHANNEL_SHIFT) >> 1);
}
void srxl2RxWriteData(const void *data, int len)
@ -473,7 +473,7 @@ void srxl2RxWriteData(const void *data, int len)
writeBufferIdx = len;
}
bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t channelData[SRXL2_MAX_CHANNELS];
for (size_t i = 0; i < SRXL2_MAX_CHANNELS; ++i) {
@ -483,13 +483,13 @@ bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
unitId = rxConfig->srxl2_unit_id;
baudRate = rxConfig->srxl2_baud_fast;
rxRuntimeConfig->channelData = channelData;
rxRuntimeConfig->channelCount = SRXL2_MAX_CHANNELS;
rxRuntimeConfig->rxRefreshRate = SRXL2_FRAME_PERIOD_US;
rxRuntimeState->channelData = channelData;
rxRuntimeState->channelCount = SRXL2_MAX_CHANNELS;
rxRuntimeState->rxRefreshRate = SRXL2_FRAME_PERIOD_US;
rxRuntimeConfig->rcReadRawFn = srxl2ReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = srxl2FrameStatus;
rxRuntimeConfig->rcProcessFrameFn = srxl2ProcessFrame;
rxRuntimeState->rcReadRawFn = srxl2ReadRawRC;
rxRuntimeState->rcFrameStatusFn = srxl2FrameStatus;
rxRuntimeState->rcProcessFrameFn = srxl2ProcessFrame;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -8,7 +8,7 @@
struct sbuf_s;
bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);
bool srxl2RxIsActive(void);
void srxl2RxWriteData(const void *data, int len);
bool srxl2TelemetryRequested(void);

View File

@ -108,9 +108,9 @@ static void sumdDataReceive(uint16_t c, void *data)
#define SUMDV3_FRAME_STATE_OK 0x03
#define SUMD_FRAME_STATE_FAILSAFE 0x81
static uint8_t sumdFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t sumdFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
uint8_t frameStatus = RX_FRAME_PENDING;
@ -148,21 +148,21 @@ static uint8_t sumdFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return frameStatus;
}
static uint16_t sumdReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sumdReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
return sumdChannels[chan] / 8;
}
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeConfig->channelCount = MIN(SUMD_MAX_CHANNEL, MAX_SUPPORTED_RC_CHANNEL_COUNT);
rxRuntimeConfig->rxRefreshRate = 11000;
rxRuntimeState->channelCount = MIN(SUMD_MAX_CHANNEL, MAX_SUPPORTED_RC_CHANNEL_COUNT);
rxRuntimeState->rxRefreshRate = 11000;
rxRuntimeConfig->rcReadRawFn = sumdReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = sumdFrameStatus;
rxRuntimeState->rcReadRawFn = sumdReadRawRC;
rxRuntimeState->rcFrameStatusFn = sumdFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -170,7 +170,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
}
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeConfig->serialrxProvider);
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif

View File

@ -20,4 +20,4 @@
#pragma once
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -85,9 +85,9 @@ static void sumhDataReceive(uint16_t c, void *data)
}
}
static uint8_t sumhFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t sumhFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
uint8_t channelIndex;
@ -108,9 +108,9 @@ static uint8_t sumhFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return RX_FRAME_COMPLETE;
}
static uint16_t sumhReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t sumhReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (chan >= SUMH_MAX_CHANNEL_COUNT) {
return 0;
@ -119,15 +119,15 @@ static uint16_t sumhReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t
return sumhChannels[chan];
}
bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
rxRuntimeConfig->channelCount = SUMH_MAX_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 11000;
rxRuntimeState->channelCount = SUMH_MAX_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 11000;
rxRuntimeConfig->rcReadRawFn = sumhReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = sumhFrameStatus;
rxRuntimeState->rcReadRawFn = sumhReadRawRC;
rxRuntimeState->rcFrameStatusFn = sumhFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -135,7 +135,7 @@ bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
}
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeConfig->serialrxProvider);
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif

View File

@ -20,4 +20,4 @@
#pragma once
bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool sumhInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -21,4 +21,4 @@
#pragma once
// Function to be implemented on a per-target basis under src/main/target/<TARGET>/serialrx.c
bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -235,9 +235,9 @@ static void xBusDataReceive(uint16_t c, void *data)
}
// Indicate time to read a frame from the data...
static uint8_t xBusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t xBusFrameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (!xBusFrameReceived) {
return RX_FRAME_PENDING;
@ -248,12 +248,12 @@ static uint8_t xBusFrameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return RX_FRAME_COMPLETE;
}
static uint16_t xBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t xBusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
uint16_t data;
// Deliver the data wanted
if (chan >= rxRuntimeConfig->channelCount) {
if (chan >= rxRuntimeState->channelCount) {
return 0;
}
@ -262,13 +262,13 @@ static uint16_t xBusReadRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t
return data;
}
bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
uint32_t baudRate;
switch (rxRuntimeConfig->serialrxProvider) {
switch (rxRuntimeState->serialrxProvider) {
case SERIALRX_XBUS_MODE_B:
rxRuntimeConfig->channelCount = XBUS_CHANNEL_COUNT;
rxRuntimeState->channelCount = XBUS_CHANNEL_COUNT;
xBusFrameReceived = false;
xBusDataIncoming = false;
xBusFramePosition = 0;
@ -278,7 +278,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
xBusProvider = SERIALRX_XBUS_MODE_B;
break;
case SERIALRX_XBUS_MODE_B_RJ01:
rxRuntimeConfig->channelCount = XBUS_RJ01_CHANNEL_COUNT;
rxRuntimeState->channelCount = XBUS_RJ01_CHANNEL_COUNT;
xBusFrameReceived = false;
xBusDataIncoming = false;
xBusFramePosition = 0;
@ -292,10 +292,10 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
break;
}
rxRuntimeConfig->rxRefreshRate = 11000;
rxRuntimeState->rxRefreshRate = 11000;
rxRuntimeConfig->rcReadRawFn = xBusReadRawRC;
rxRuntimeConfig->rcFrameStatusFn = xBusFrameStatus;
rxRuntimeState->rcReadRawFn = xBusReadRawRC;
rxRuntimeState->rcFrameStatusFn = xBusFrameStatus;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -303,7 +303,7 @@ bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
}
#ifdef USE_TELEMETRY
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeConfig->serialrxProvider);
bool portShared = telemetryCheckRxPortShared(portConfig, rxRuntimeState->serialrxProvider);
#else
bool portShared = false;
#endif

View File

@ -20,4 +20,4 @@
#pragma once
bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig);
bool xBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState);

View File

@ -63,7 +63,7 @@ static uint8_t dataIndex = 0;
static uint8_t cksum[2] = {0};
static uint8_t counter = 0;
static rxRuntimeConfig_t *rxRuntimeConfigPtr;
static rxRuntimeState_t *rxRuntimeStatePtr;
static serialPort_t *serialPort;
#define SUPPORTED_CHANNEL_COUNT (4 + CRTP_CPPM_EMU_MAX_AUX_CHANNELS)
@ -187,9 +187,9 @@ static void dataReceive(uint16_t c, void *data)
}
}
static uint8_t frameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
static uint8_t frameStatus(rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxRuntimeConfig);
UNUSED(rxRuntimeState);
if (!rcFrameComplete) {
return RX_FRAME_PENDING;
@ -201,18 +201,18 @@ static uint8_t frameStatus(rxRuntimeConfig_t *rxRuntimeConfig)
return RX_FRAME_COMPLETE;
}
static uint16_t readRawRC(const rxRuntimeConfig_t *rxRuntimeConfig, uint8_t chan)
static uint16_t readRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
{
if (chan >= rxRuntimeConfig->channelCount) {
if (chan >= rxRuntimeState->channelCount) {
return 0;
}
return channelData[chan];
}
bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeConfigPtr = rxRuntimeConfig;
rxRuntimeStatePtr = rxRuntimeState;
if (rxConfig->serialrx_provider != SERIALRX_TARGET_CUSTOM)
{
@ -224,10 +224,10 @@ bool targetCustomSerialRxInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxR
return false;
}
rxRuntimeConfig->channelCount = SUPPORTED_CHANNEL_COUNT;
rxRuntimeConfig->rxRefreshRate = 20000; // Value taken from rx_spi.c (NRF24 is being used downstream)
rxRuntimeConfig->rcReadRawFn = readRawRC;
rxRuntimeConfig->rcFrameStatusFn = frameStatus;
rxRuntimeState->channelCount = SUPPORTED_CHANNEL_COUNT;
rxRuntimeState->rxRefreshRate = 20000; // Value taken from rx_spi.c (NRF24 is being used downstream)
rxRuntimeState->rcReadRawFn = readRawRC;
rxRuntimeState->rcFrameStatusFn = frameStatus;
serialPort = openSerialPort(portConfig->identifier,
FUNCTION_RX_SERIAL,

View File

@ -494,7 +494,7 @@ static void configureFrSkyHubTelemetryPort(void)
void checkFrSkyHubTelemetryState(void)
{
if (telemetryState == TELEMETRY_STATE_INITIALIZED_SERIAL) {
if (telemetryCheckRxPortShared(portConfig, rxRuntimeConfig.serialrxProvider)) {
if (telemetryCheckRxPortShared(portConfig, rxRuntimeState.serialrxProvider)) {
if (frSkyHubPort == NULL && telemetrySharedPort != NULL) {
frSkyHubPort = telemetrySharedPort;
}

View File

@ -289,7 +289,7 @@ void configureLtmTelemetryPort(void)
void checkLtmTelemetryState(void)
{
if (portConfig && telemetryCheckRxPortShared(portConfig, rxRuntimeConfig.serialrxProvider)) {
if (portConfig && telemetryCheckRxPortShared(portConfig, rxRuntimeState.serialrxProvider)) {
if (!ltmEnabled && telemetrySharedPort != NULL) {
ltmPort = telemetrySharedPort;
ltmEnabled = true;

View File

@ -183,7 +183,7 @@ void configureMAVLinkTelemetryPort(void)
void checkMAVLinkTelemetryState(void)
{
if (portConfig && telemetryCheckRxPortShared(portConfig, rxRuntimeConfig.serialrxProvider)) {
if (portConfig && telemetryCheckRxPortShared(portConfig, rxRuntimeState.serialrxProvider)) {
if (!mavlinkTelemetryEnabled && telemetrySharedPort != NULL) {
mavlinkPort = telemetrySharedPort;
mavlinkTelemetryEnabled = true;
@ -276,21 +276,21 @@ void mavlinkSendRCChannelsAndRSSI(void)
// port Servo output port (set of 8 outputs = 1 port). Most MAVs will just use one, but this allows to encode more than 8 servos.
0,
// chan1_raw RC channel 1 value, in microseconds
(rxRuntimeConfig.channelCount >= 1) ? rcData[0] : 0,
(rxRuntimeState.channelCount >= 1) ? rcData[0] : 0,
// chan2_raw RC channel 2 value, in microseconds
(rxRuntimeConfig.channelCount >= 2) ? rcData[1] : 0,
(rxRuntimeState.channelCount >= 2) ? rcData[1] : 0,
// chan3_raw RC channel 3 value, in microseconds
(rxRuntimeConfig.channelCount >= 3) ? rcData[2] : 0,
(rxRuntimeState.channelCount >= 3) ? rcData[2] : 0,
// chan4_raw RC channel 4 value, in microseconds
(rxRuntimeConfig.channelCount >= 4) ? rcData[3] : 0,
(rxRuntimeState.channelCount >= 4) ? rcData[3] : 0,
// chan5_raw RC channel 5 value, in microseconds
(rxRuntimeConfig.channelCount >= 5) ? rcData[4] : 0,
(rxRuntimeState.channelCount >= 5) ? rcData[4] : 0,
// chan6_raw RC channel 6 value, in microseconds
(rxRuntimeConfig.channelCount >= 6) ? rcData[5] : 0,
(rxRuntimeState.channelCount >= 6) ? rcData[5] : 0,
// chan7_raw RC channel 7 value, in microseconds
(rxRuntimeConfig.channelCount >= 7) ? rcData[6] : 0,
(rxRuntimeState.channelCount >= 7) ? rcData[6] : 0,
// chan8_raw RC channel 8 value, in microseconds
(rxRuntimeConfig.channelCount >= 8) ? rcData[7] : 0,
(rxRuntimeState.channelCount >= 8) ? rcData[7] : 0,
// rssi Receive signal strength indicator, 0: 0%, 255: 100%
constrain(scaleRange(getRssi(), 0, RSSI_MAX_VALUE, 0, 255), 0, 255));
msgLength = mavlink_msg_to_send_buffer(mavBuffer, &mavMsg);

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;