Refactoring of rxFrameTimeUs

This commit is contained in:
Štěpán Dalecký 2021-09-27 21:08:42 +02:00
parent 1ceff68a00
commit fcd41eb28b
16 changed files with 35 additions and 82 deletions

View File

@ -71,8 +71,6 @@ static uint8_t telemetryBuf[CRSF_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
static float channelScale = CRSF_RC_CHANNEL_SCALE_LEGACY;
static timeUs_t lastRcFrameTimeUs = 0;
#ifdef USE_RX_LINK_UPLINK_POWER
#define CRSF_UPLINK_POWER_LEVEL_MW_ITEMS_COUNT 8
// Uplink power levels by uplinkTXPower expressed in mW (250 mW is from ver >=4.00)
@ -351,7 +349,7 @@ STATIC_UNIT_TESTED uint8_t crsfFrameCmdCRC(void)
// Receive ISR callback, called back from serial port
STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
{
UNUSED(data);
rxRuntimeState_t *const rxRuntimeState = (rxRuntimeState_t *const)data;
static uint8_t crsfFramePosition = 0;
#if defined(USE_CRSF_V3)
@ -389,7 +387,7 @@ STATIC_UNIT_TESTED void crsfDataReceive(uint16_t c, void *data)
case CRSF_FRAMETYPE_RC_CHANNELS_PACKED:
case CRSF_FRAMETYPE_SUBSET_RC_CHANNELS_PACKED:
if (crsfFrame.frame.deviceAddress == CRSF_ADDRESS_FLIGHT_CONTROLLER) {
lastRcFrameTimeUs = currentTimeUs;
rxRuntimeState->lastRcFrameTimeUs = currentTimeUs;
crsfFrameDone = true;
memcpy(&crsfChannelDataFrame, &crsfFrame, sizeof(crsfFrame));
}
@ -610,11 +608,6 @@ void crsfRxSendTelemetryData(void)
}
}
static timeUs_t crsfFrameTimeUs(void)
{
return lastRcFrameTimeUs;
}
bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
for (int ii = 0; ii < CRSF_MAX_CHANNEL; ++ii) {
@ -626,7 +619,7 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = crsfReadRawRC;
rxRuntimeState->rcFrameStatusFn = crsfFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = crsfFrameTimeUs;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {
@ -636,7 +629,7 @@ bool crsfRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
serialPort = openSerialPort(portConfig->identifier,
FUNCTION_RX_SERIAL,
crsfDataReceive,
NULL,
rxRuntimeState,
CRSF_BAUDRATE,
CRSF_PORT_MODE,
CRSF_PORT_OPTIONS | (rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0)

View File

@ -150,8 +150,6 @@ static serialPort_t *fportPort;
static bool telemetryEnabled = false;
#endif
static timeUs_t lastRcFrameTimeUs = 0;
static void reportFrameError(uint8_t errorReason) {
static volatile uint16_t frameErrors = 0;
@ -280,7 +278,7 @@ static uint8_t fportFrameStatus(rxRuntimeState_t *rxRuntimeState)
lastRcFrameReceivedMs = millis();
if (!(result & (RX_FRAME_FAILSAFE | RX_FRAME_DROPPED))) {
lastRcFrameTimeUs = rxBuffer[rxBufferReadIndex].frameStartTimeUs;
rxRuntimeState->lastRcFrameTimeUs = rxBuffer[rxBufferReadIndex].frameStartTimeUs;
}
}
@ -386,11 +384,6 @@ static bool fportProcessFrame(const rxRuntimeState_t *rxRuntimeState)
return true;
}
static timeUs_t fportFrameTimeUs(void)
{
return lastRcFrameTimeUs;
}
bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
@ -402,7 +395,7 @@ bool fportRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcFrameStatusFn = fportFrameStatus;
rxRuntimeState->rcProcessFrameFn = fportProcessFrame;
rxRuntimeState->rcFrameTimeUsFn = fportFrameTimeUs;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -87,8 +87,6 @@ static timeUs_t ghstRxFrameEndAtUs = 0;
static uint8_t telemetryBuf[GHST_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
static timeUs_t lastRcFrameTimeUs = 0;
/* GHST Protocol
* Ghost uses 420k baud single-wire, half duplex connection, connected to a FC UART 'Tx' pin
* Each control packet is interleaved with one or more corresponding downlink packets
@ -305,11 +303,6 @@ STATIC_UNIT_TESTED float ghstReadRawRC(const rxRuntimeState_t *rxRuntimeState, u
return (5 * ((float)ghstChannelData[chan] + 1) / 8) + 880;
}
static timeUs_t ghstFrameTimeUs(void)
{
return lastRcFrameTimeUs;
}
// UART idle detected (inter-packet)
static void ghstIdle()
{
@ -329,7 +322,7 @@ bool ghstRxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = ghstReadRawRC;
rxRuntimeState->rcFrameStatusFn = ghstFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = ghstFrameTimeUs;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
rxRuntimeState->rcProcessFrameFn = ghstProcessFrame;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);

View File

@ -76,7 +76,6 @@ static uint32_t ibusChannelData[IBUS_MAX_CHANNEL];
static uint8_t ibus[IBUS_BUFFSIZE] = { 0, };
static timeUs_t lastFrameTimeUs = 0;
static timeUs_t lastRcFrameTimeUs = 0;
static bool isValidIa6bIbusPacketLength(uint8_t length)
{
@ -184,7 +183,7 @@ static uint8_t ibusFrameStatus(rxRuntimeState_t *rxRuntimeState)
if (ibusModel == IBUS_MODEL_IA6 || ibusSyncByte == IBUS_SERIAL_RX_PACKET_LENGTH) {
updateChannelData();
frameStatus = RX_FRAME_COMPLETE;
lastRcFrameTimeUs = lastFrameTimeUs;
rxRuntimeState->lastRcFrameTimeUs = lastFrameTimeUs;
#if defined(USE_TELEMETRY) && defined(USE_TELEMETRY_IBUS)
} else {
rxBytesToIgnore = respondToIbusRequest(ibus);
@ -202,11 +201,6 @@ static float ibusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
return ibusChannelData[chan];
}
static timeUs_t ibusFrameTimeUsFn(void)
{
return lastRcFrameTimeUs;
}
bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
@ -217,7 +211,7 @@ bool ibusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = ibusReadRawRC;
rxRuntimeState->rcFrameStatusFn = ibusFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = ibusFrameTimeUsFn;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -91,7 +91,6 @@ static uint8_t jetiExBusChannelFrame[EXBUS_MAX_CHANNEL_FRAME_SIZE];
uint8_t jetiExBusRequestFrame[EXBUS_MAX_REQUEST_FRAME_SIZE];
static uint16_t jetiExBusChannelData[JETIEXBUS_CHANNEL_COUNT];
static timeUs_t lastRcFrameTimeUs = 0;
// Jeti Ex Bus CRC calculations for a frame
uint16_t jetiExBusCalcCRC16(uint8_t *pt, uint8_t msgLen)
@ -229,7 +228,7 @@ static uint8_t jetiExBusFrameStatus(rxRuntimeState_t *rxRuntimeState)
if (jetiExBusCalcCRC16(jetiExBusChannelFrame, jetiExBusChannelFrame[EXBUS_HEADER_MSG_LEN]) == 0) {
jetiExBusDecodeChannelFrame(jetiExBusChannelFrame);
frameStatus = RX_FRAME_COMPLETE;
lastRcFrameTimeUs = jetiTimeStampRequest;
rxRuntimeState->lastRcFrameTimeUs = jetiTimeStampRequest;
}
jetiExBusFrameState = EXBUS_STATE_ZERO;
}
@ -245,11 +244,6 @@ static float jetiExBusReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t
return (jetiExBusChannelData[chan]);
}
static timeUs_t jetiExBusFrameTimeUsFn(void)
{
return lastRcFrameTimeUs;
}
bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
@ -259,7 +253,7 @@ bool jetiExBusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = jetiExBusReadRawRC;
rxRuntimeState->rcFrameStatusFn = jetiExBusFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = jetiExBusFrameTimeUsFn;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
jetiExBusFrameReset();

View File

@ -282,6 +282,7 @@ void rxInit(void)
rxRuntimeState.rcReadRawFn = nullReadRawRC;
rxRuntimeState.rcFrameStatusFn = nullFrameStatus;
rxRuntimeState.rcProcessFrameFn = nullProcessFrame;
rxRuntimeState.lastRcFrameTimeUs = 0;
rcSampleIndex = 0;
needRxSignalMaxDelayUs = DELAY_10_HZ;
@ -929,3 +930,8 @@ timeDelta_t rxGetFrameDelta(timeDelta_t *frameAgeUs)
return frameTimeDeltaUs;
}
timeUs_t rxFrameTimeUs(void)
{
return rxRuntimeState.lastRcFrameTimeUs;
}

View File

@ -149,6 +149,7 @@ typedef struct rxRuntimeState_s {
rcGetFrameTimeUsFn *rcFrameTimeUsFn;
uint16_t *channelData;
void *frameData;
timeUs_t lastRcFrameTimeUs;
} rxRuntimeState_t;
typedef enum {
@ -218,3 +219,5 @@ void resumeRxPwmPpmSignal(void);
uint16_t rxGetRefreshRate(void);
timeDelta_t rxGetFrameDelta(timeDelta_t *frameAgeUs);
timeUs_t rxFrameTimeUs(void);

View File

@ -108,8 +108,6 @@ typedef struct sbusFrameData_s {
bool done;
} sbusFrameData_t;
static timeUs_t lastRcFrameTimeUs = 0;
// Receive ISR callback
static void sbusDataReceive(uint16_t c, void *data)
{
@ -154,17 +152,12 @@ static uint8_t sbusFrameStatus(rxRuntimeState_t *rxRuntimeState)
const uint8_t frameStatus = sbusChannelsDecode(rxRuntimeState, &sbusFrameData->frame.frame.channels);
if (!(frameStatus & (RX_FRAME_FAILSAFE | RX_FRAME_DROPPED))) {
lastRcFrameTimeUs = sbusFrameData->startAtUs;
rxRuntimeState->lastRcFrameTimeUs = sbusFrameData->startAtUs;
}
return frameStatus;
}
static timeUs_t sbusFrameTimeUs(void)
{
return lastRcFrameTimeUs;
}
bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t sbusChannelData[SBUS_MAX_CHANNEL];
@ -186,7 +179,7 @@ bool sbusInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
}
rxRuntimeState->rcFrameStatusFn = sbusFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = sbusFrameTimeUs;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -76,12 +76,10 @@ static uint8_t telemetryBuf[SRXL_FRAME_SIZE_MAX];
static uint8_t telemetryBufLen = 0;
#endif
static timeUs_t lastRcFrameTimeUs = 0;
// Receive ISR callback
static void spektrumDataReceive(uint16_t c, void *data)
{
UNUSED(data);
rxRuntimeState_t *const rxRuntimeState = (rxRuntimeState_t *const)data;
static timeUs_t spekTimeLast = 0;
static uint8_t spekFramePosition = 0;
@ -99,7 +97,7 @@ static void spektrumDataReceive(uint16_t c, void *data)
if (spekFramePosition < SPEK_FRAME_SIZE) {
rcFrameComplete = false;
} else {
lastRcFrameTimeUs = now;
rxRuntimeState->lastRcFrameTimeUs = now;
rcFrameComplete = true;
}
}
@ -344,11 +342,6 @@ void srxlRxWriteTelemetryData(const void *data, int len)
}
#endif
static timeUs_t spektrumFrameTimeUsFn(void)
{
return lastRcFrameTimeUs;
}
bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
rxRuntimeStatePtr = rxRuntimeState;
@ -396,7 +389,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = spektrumReadRawRC;
rxRuntimeState->rcFrameStatusFn = spektrumFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = spektrumFrameTimeUsFn;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
#if defined(USE_TELEMETRY_SRXL)
rxRuntimeState->rcProcessFrameFn = spektrumProcessFrame;
#endif
@ -404,7 +397,7 @@ bool spektrumInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
serialPort = openSerialPort(portConfig->identifier,
FUNCTION_RX_SERIAL,
spektrumDataReceive,
NULL,
rxRuntimeState,
SPEKTRUM_BAUDRATE,
portShared || srxlEnabled ? MODE_RXTX : MODE_RX,
(rxConfig->serialrx_inverted ? SERIAL_INVERTED : 0) |

View File

@ -112,8 +112,6 @@ static bool telemetryRequested = false;
static uint8_t telemetryFrame[22];
static timeUs_t lastRcFrameTimeUs = 0;
uint8_t globalResult = 0;
/* handshake protocol
@ -426,7 +424,7 @@ static uint8_t srxl2FrameStatus(rxRuntimeState_t *rxRuntimeState)
}
if (!(result & (RX_FRAME_FAILSAFE | RX_FRAME_DROPPED))) {
lastRcFrameTimeUs = lastIdleTimestamp;
rxRuntimeState->lastRcFrameTimeUs = lastIdleTimestamp;
}
return result;
@ -478,11 +476,6 @@ void srxl2RxWriteData(const void *data, int len)
writeBufferIdx = len;
}
static timeUs_t srxl2FrameTimeUsFn(void)
{
return lastRcFrameTimeUs;
}
bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
static uint16_t channelData[SRXL2_MAX_CHANNELS];
@ -499,7 +492,7 @@ bool srxl2RxInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = srxl2ReadRawRC;
rxRuntimeState->rcFrameStatusFn = srxl2FrameStatus;
rxRuntimeState->rcFrameTimeUsFn = srxl2FrameTimeUsFn;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
rxRuntimeState->rcProcessFrameFn = srxl2ProcessFrame;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);

View File

@ -76,7 +76,6 @@ static uint16_t crc;
static uint8_t sumd[SUMD_BUFFSIZE] = { 0, };
static uint8_t sumdChannelCount;
static timeUs_t lastFrameTimeUs = 0;
static timeUs_t lastRcFrameTimeUs = 0;
// Receive ISR callback
static void sumdDataReceive(uint16_t c, void *data)
@ -156,7 +155,7 @@ static uint8_t sumdFrameStatus(rxRuntimeState_t *rxRuntimeState)
}
if (!(frameStatus & (RX_FRAME_FAILSAFE | RX_FRAME_DROPPED))) {
lastRcFrameTimeUs = lastFrameTimeUs;
rxRuntimeState->lastRcFrameTimeUs = lastFrameTimeUs;
}
return frameStatus;
@ -168,11 +167,6 @@ static float sumdReadRawRC(const rxRuntimeState_t *rxRuntimeState, uint8_t chan)
return (float)sumdChannels[chan] / 8;
}
static timeUs_t sumdFrameTimeUsFn(void)
{
return lastRcFrameTimeUs;
}
bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
{
UNUSED(rxConfig);
@ -182,7 +176,7 @@ bool sumdInit(const rxConfig_t *rxConfig, rxRuntimeState_t *rxRuntimeState)
rxRuntimeState->rcReadRawFn = sumdReadRawRC;
rxRuntimeState->rcFrameStatusFn = sumdFrameStatus;
rxRuntimeState->rcFrameTimeUsFn = sumdFrameTimeUsFn;
rxRuntimeState->rcFrameTimeUsFn = rxFrameTimeUs;
const serialPortConfig_t *portConfig = findSerialPortConfig(FUNCTION_RX_SERIAL);
if (!portConfig) {

View File

@ -361,4 +361,5 @@ void crsfScheduleMspResponse(void) {};
bool bufferMspFrame(uint8_t *, int) {return true;}
bool isBatteryVoltageAvailable(void) { return true; }
bool isAmperageAvailable(void) { return true; }
timeUs_t rxFrameTimeUs(void) { return 0; }
}

View File

@ -44,6 +44,7 @@ extern "C" {
int16_t telemTemperature1 = 0;
baro_t baro = { .baroTemperature = 50 };
telemetryConfig_t telemetryConfig_System;
timeUs_t rxFrameTimeUs(void) { return 0; }
}

View File

@ -43,6 +43,7 @@ extern "C" {
int16_t telemTemperature1 = 0;
baro_t baro = { .baroTemperature = 50 };
telemetryConfig_t telemetryConfig_System;
timeUs_t rxFrameTimeUs(void) { return 0; }
}

View File

@ -317,4 +317,5 @@ extern "C" {
return true;
}
timeUs_t rxFrameTimeUs(void) { return 0; }
}

View File

@ -377,5 +377,5 @@ bool handleMspFrame(uint8_t *, int, uint8_t *) { return false; }
void crsfScheduleMspResponse(void) {};
bool isBatteryVoltageConfigured(void) { return true; }
bool isAmperageConfigured(void) { return true; }
timeUs_t rxFrameTimeUs(void) { return 0; }
}