Update cloud build defines (#14080)
[betaflight.git] / src / main / rx / expresslrs.c
blobc71a196933cbdd57d3e4a6635c01b4de043ecfb6
1 /*
2 * This file is part of Cleanflight and Betaflight.
4 * Cleanflight and Betaflight are free software. You can redistribute
5 * this software and/or modify this software under the terms of the
6 * GNU General Public License as published by the Free Software
7 * Foundation, either version 3 of the License, or (at your option)
8 * any later version.
10 * Cleanflight and Betaflight are distributed in the hope that they
11 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
12 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
13 * See the GNU General Public License for more details.
15 * You should have received a copy of the GNU General Public License
16 * along with this software.
18 * If not, see <http://www.gnu.org/licenses/>.
22 * Based on https://github.com/ExpressLRS/ExpressLRS
23 * Thanks to AlessandroAU, original creator of the ExpressLRS project.
25 * Authors:
26 * Phobos- - Original port.
27 * Dominic Clifton/Hydra - Timer-based timeout implementation.
28 * Phobos- - Port of v2.0
31 #include <stdlib.h>
32 #include <string.h>
33 #include "platform.h"
35 #ifdef USE_RX_EXPRESSLRS
37 #if !defined(RX_EXPRESSLRS_TIMER_INSTANCE)
38 #define RX_EXPRESSLRS_TIMER_INSTANCE NULL
39 #endif
41 #include "build/atomic.h"
42 #include "build/debug.h"
43 #include "build/debug_pin.h"
45 #include "common/maths.h"
46 #include "common/filter.h"
48 #include "drivers/io.h"
49 #include "drivers/nvic.h"
50 #include "drivers/rx/rx_spi.h"
51 #include "drivers/system.h"
52 #include "drivers/time.h"
53 #include "drivers/timer.h"
54 #include "drivers/rx/rx_sx127x.h"
55 #include "drivers/rx/rx_sx1280.h"
56 #include "drivers/rx/expresslrs_driver.h"
58 #include "config/config.h"
59 #include "config/feature.h"
61 #include "fc/init.h"
63 #include "pg/pg.h"
64 #include "pg/pg_ids.h"
65 #include "pg/rx_spi.h"
66 #include "pg/rx_spi_expresslrs.h"
68 #include "rx/rx.h"
69 #include "rx/rx_spi.h"
70 #include "rx/rx_spi_common.h"
72 #include "rx/expresslrs.h"
73 #include "rx/expresslrs_common.h"
74 #include "rx/expresslrs_impl.h"
75 #include "rx/expresslrs_telemetry.h"
77 UNIT_TESTED elrsReceiver_t receiver;
78 static const uint8_t BindingUID[6] = {0,1,2,3,4,5}; // Special binding UID values
79 static uint16_t crcInitializer = 0;
80 static uint8_t bindingRateIndex = 0;
81 static bool connectionHasModelMatch = false;
82 static uint8_t txPower = 0;
83 static uint8_t wideSwitchIndex = 0;
84 static uint8_t currTlmDenom = 1;
85 static simpleLowpassFilter_t rssiFilter;
86 #ifdef USE_RX_RSNR
87 static simpleLowpassFilter_t rsnrFilter;
88 #endif //USE_RX_RSNR
89 static meanAccumulator_t snrFilter; //for dyn power purposes
91 static volatile DMA_DATA uint8_t dmaBuffer[ELRS_RX_TX_BUFF_SIZE];
92 static volatile DMA_DATA uint8_t telemetryPacket[ELRS_RX_TX_BUFF_SIZE];
93 static volatile rx_spi_received_e rfPacketStatus = RX_SPI_RECEIVED_NONE;
94 static volatile uint8_t *payload;
96 static void rssiFilterReset(void)
98 simpleLPFilterInit(&rssiFilter, 2, 5);
99 #ifdef USE_RX_RSNR
100 simpleLPFilterInit(&rsnrFilter, 2, 5);
101 #endif //USE_RX_RSNR
104 #define PACKET_HANDLING_TO_TOCK_ISR_DELAY_US 250
107 // Event pair recorder
110 typedef enum {
111 EPR_FIRST,
112 EPR_SECOND,
113 } eprEvent_e;
115 #define EPR_EVENT_COUNT 2
117 typedef struct eprState_s {
118 uint32_t eventAtUs[EPR_EVENT_COUNT];
119 bool eventRecorded[EPR_EVENT_COUNT];
120 } eprState_t;
122 eprState_t eprState = {
123 .eventAtUs = {0},
124 .eventRecorded = {0},
127 static void phaseLockEprEvent(eprEvent_e event, uint32_t currentTimeUs)
129 eprState.eventAtUs[event] = currentTimeUs;
130 eprState.eventRecorded[event] = true;
133 static bool phaseLockEprHaveBothEvents(void)
135 bool bothEventsRecorded = eprState.eventRecorded[EPR_SECOND] && eprState.eventRecorded[EPR_FIRST];
136 return bothEventsRecorded;
139 static int32_t phaseLockEprResult(void)
141 if (phaseLockEprHaveBothEvents()) {
142 return (int32_t)(eprState.eventAtUs[EPR_SECOND] - eprState.eventAtUs[EPR_FIRST]);
145 return 0;
148 static void phaseLockEprReset(void)
150 memset(&eprState, 0, sizeof(eprState_t));
154 // Phase Lock
157 #define EPR_INTERNAL EPR_FIRST
158 #define EPR_EXTERNAL EPR_SECOND
160 typedef struct phaseLockState_s {
161 simpleLowpassFilter_t offsetFilter;
162 simpleLowpassFilter_t offsetDxFilter;
164 int32_t rawOffsetUs;
165 int32_t previousRawOffsetUs;
167 int32_t offsetUs;
168 int32_t offsetDeltaUs;
169 int32_t previousOffsetUs;
170 } phaseLockState_t;
172 static phaseLockState_t pl;
174 static void expressLrsPhaseLockReset(void)
176 simpleLPFilterInit(&pl.offsetFilter, 2, 5);
177 simpleLPFilterInit(&pl.offsetDxFilter, 4, 5);
179 phaseLockEprReset();
182 static uint8_t nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
184 static uint8_t telemetryBurstCount = 1;
185 static uint8_t telemetryBurstMax = 1;
186 static bool telemBurstValid = false;
188 // Maximum ms between LINK_STATISTICS packets for determining burst max
189 #define TELEM_MIN_LINK_INTERVAL 512U
191 #ifdef USE_MSP_OVER_TELEMETRY
192 static uint8_t mspBuffer[ELRS_MSP_BUFFER_SIZE];
193 #endif
196 // Stick unpacking
199 static void setRssiChannelData(uint16_t *rcData)
201 rcData[ELRS_LQ_CHANNEL] = scaleRange(receiver.uplinkLQ, 0, 100, 988, 2011);
202 rcData[ELRS_RSSI_CHANNEL] = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 988, 2011);
205 static void unpackAnalogChannelData(uint16_t *rcData, volatile elrsOtaPacket_t const * const otaPktPtr)
207 const uint8_t numOfChannels = 4;
208 const uint8_t srcBits = 10;
209 const uint16_t inputChannelMask = (1 << srcBits) - 1;
211 uint8_t bitsMerged = 0;
212 uint32_t readValue = 0;
213 uint8_t readByteIndex = 0;
214 for (uint8_t n = 0; n < numOfChannels; n++) {
215 while (bitsMerged < srcBits) {
216 uint8_t readByte = otaPktPtr->rc.ch[readByteIndex++];
217 readValue |= ((uint32_t) readByte) << bitsMerged;
218 bitsMerged += 8;
220 rcData[n] = 988 + (readValue & inputChannelMask);
221 readValue >>= srcBits;
222 bitsMerged -= srcBits;
225 // The low latency switch
226 rcData[4] = convertSwitch1b(otaPktPtr->rc.ch4);
230 * Hybrid switches uses 10 bits for each analog channel,
231 * 2 bits for the low latency switch[0]
232 * 3 bits for the round-robin switch index and 2 bits for the value
233 * 4 analog channels, 1 low latency switch and round robin switch data = 47 bits (1 free)
235 * sets telemetry status bit
237 static void unpackChannelDataHybridSwitch8(uint16_t *rcData, volatile elrsOtaPacket_t const * const otaPktPtr)
239 unpackAnalogChannelData(rcData, otaPktPtr);
241 const uint8_t switchByte = otaPktPtr->rc.switches;
243 // The round-robin switch, switchIndex is actually index-1
244 // to leave the low bit open for switch 7 (sent as 0b11x)
245 // where x is the high bit of switch 7
246 uint8_t switchIndex = (switchByte & 0x38) >> 3;
248 if (switchIndex >= 6) {
249 // Because AUX1 (index 0) is the low latency switch, the low bit
250 // of the switchIndex can be used as data, and arrives as index "6"
251 rcData[11] = convertSwitchNb(switchByte & 0x0F, 15); //4-bit
252 } else {
253 rcData[5 + switchIndex] = convertSwitch3b(switchByte & 0x07);
256 setRssiChannelData(rcData);
260 * HybridWide switches decoding of over the air data
262 * Hybrid switches uses 10 bits for each analog channel,
263 * 1 bits for the low latency switch[0]
264 * 6 or 7 bits for the round-robin switch
265 * 1 bit for the TelemetryStatus, which may be in every packet or just idx 7
266 * depending on TelemetryRatio
268 * Output: crsf.PackedRCdataOut, crsf.LinkStatistics.uplink_TX_Power
269 * Returns: TelemetryStatus bit
271 static void unpackChannelDataHybridWide(uint16_t *rcData, volatile elrsOtaPacket_t const * const otaPktPtr)
273 unpackAnalogChannelData(rcData, otaPktPtr);
274 const uint8_t switchByte = otaPktPtr->rc.switches;
276 // The round-robin switch, 6-7 bits with the switch index implied by the nonce. Some logic moved to processRFPacket
277 if (wideSwitchIndex >= 7) {
278 txPower = switchByte & 0x3F;
279 } else {
280 uint8_t bins;
281 uint16_t switchValue;
282 if (currTlmDenom > 1 && currTlmDenom < 8) {
283 bins = 63;
284 switchValue = switchByte & 0x3F; // 6-bit
285 } else {
286 bins = 127;
287 switchValue = switchByte & 0x7F; // 7-bit
290 rcData[5 + wideSwitchIndex] = convertSwitchNb(switchValue, bins);
293 setRssiChannelData(rcData);
296 static uint8_t minLqForChaos(void)
298 // Determine the most number of CRC-passing packets we could receive on
299 // a single channel out of 100 packets that fill the LQcalc span.
300 // The LQ must be GREATER THAN this value, not >=
301 // The amount of time we coexist on the same channel is
302 // 100 divided by the total number of packets in a FHSS loop (rounded up)
303 // and there would be 4x packets received each time it passes by so
304 // FHSShopInterval * ceil(100 / FHSShopInterval * numfhss) or
305 // FHSShopInterval * trunc((100 + (FHSShopInterval * numfhss) - 1) / (FHSShopInterval * numfhss))
306 // With a interval of 4 this works out to: 2.4=4, FCC915=4, AU915=8, EU868=8, EU/AU433=36
307 const uint32_t numfhss = fhssGetNumEntries();
308 const uint8_t interval = receiver.modParams->fhssHopInterval;
309 return interval * ((interval * numfhss + 99) / (interval * numfhss));
312 static bool domainIsTeam24(void)
314 #ifdef USE_RX_SX1280
315 const elrsFreqDomain_e domain = rxExpressLrsSpiConfig()->domain;
316 return (domain == ISM2400) || (domain == CE2400);
317 #else
318 return false;
319 #endif
322 static void setRfLinkRate(const uint8_t index)
324 #if defined(USE_RX_SX1280) && defined(USE_RX_SX127X)
325 const uint8_t domainIdx = domainIsTeam24() ? 1 : 0;
326 receiver.modParams = &airRateConfig[domainIdx][index];
327 receiver.rfPerfParams = &rfPerfConfig[domainIdx][index];
328 #else
329 receiver.modParams = &airRateConfig[0][index];
330 receiver.rfPerfParams = &rfPerfConfig[0][index];
331 #endif
332 receiver.currentFreq = fhssGetInitialFreq(receiver.freqOffset);
334 // Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
335 receiver.cycleIntervalMs = ((uint32_t)11U * fhssGetNumEntries() * receiver.modParams->fhssHopInterval * receiver.modParams->interval) / (10U * 1000U);
337 receiver.config(
338 receiver.modParams->bw,
339 receiver.modParams->sf,
340 receiver.modParams->cr,
341 receiver.currentFreq,
342 receiver.modParams->preambleLen,
343 receiver.UID[5] & 0x01,
344 elrsUidToSeed(receiver.UID),
345 crcInitializer,
346 receiver.modParams->radioType == RADIO_TYPE_SX128x_FLRC
348 #if defined(USE_RX_SX1280)
349 if (rxExpressLrsSpiConfig()->domain == CE2400)
350 sx1280SetOutputPower(10);
351 #endif
353 expressLrsUpdateTimerInterval(receiver.modParams->interval);
355 rssiFilterReset();
356 receiver.nextRateIndex = index; // presumably we just handled this
357 telemBurstValid = false;
359 #ifdef USE_RX_LINK_QUALITY_INFO
360 rxSetRfMode((uint8_t)receiver.modParams->enumRate);
361 #endif
364 uint32_t expressLrsGetCurrentFreq(void)
366 return receiver.currentFreq;
369 void expressLrsSetRfPacketStatus(rx_spi_received_e status)
371 rfPacketStatus = status;
374 volatile uint8_t *expressLrsGetRxBuffer(void) {
375 return dmaBuffer;
378 volatile uint8_t *expressLrsGetTelemetryBuffer(void)
380 return telemetryPacket;
383 volatile uint8_t *expressLrsGetPayloadBuffer(void)
385 return payload;
388 bool expressLrsIsFhssReq(void)
390 uint8_t modresultFHSS = (receiver.nonceRX + 1) % receiver.modParams->fhssHopInterval;
392 if ((receiver.modParams->fhssHopInterval == 0) || receiver.alreadyFhss == true || receiver.inBindingMode || (modresultFHSS != 0) || (receiver.connectionState == ELRS_DISCONNECTED)) {
393 return false;
396 receiver.alreadyFhss = true;
397 receiver.currentFreq = fhssGetNextFreq(receiver.freqOffset);
399 return true;
402 bool expressLrsTelemRespReq(void)
404 uint8_t modresult = (receiver.nonceRX + 1) % currTlmDenom;
405 if (receiver.inBindingMode || (receiver.connectionState == ELRS_DISCONNECTED) || (currTlmDenom == 1) || (modresult != 0)) {
406 return false; // don't bother sending tlm if disconnected or TLM is off
407 } else {
408 return true;
412 static void expressLrsSendTelemResp(void)
414 elrsOtaPacket_t otaPkt = {0};
416 receiver.alreadyTelemResp = true;
417 otaPkt.type = ELRS_TLM_PACKET;
419 if (nextTelemetryType == ELRS_TELEMETRY_TYPE_LINK || !isTelemetrySenderActive()) {
420 otaPkt.tlm_dl.type = ELRS_TELEMETRY_TYPE_LINK;
421 otaPkt.tlm_dl.ul_link_stats.uplink_RSSI_1 = receiver.rssiFiltered > 0 ? 0 : -receiver.rssiFiltered;
422 otaPkt.tlm_dl.ul_link_stats.uplink_RSSI_2 = 0; //diversity not supported
423 otaPkt.tlm_dl.ul_link_stats.antenna = 0;
424 otaPkt.tlm_dl.ul_link_stats.modelMatch = connectionHasModelMatch;
425 otaPkt.tlm_dl.ul_link_stats.lq = receiver.uplinkLQ;
426 otaPkt.tlm_dl.ul_link_stats.SNR = meanAccumulatorCalc(&snrFilter, -16);
427 #ifdef USE_MSP_OVER_TELEMETRY
428 otaPkt.tlm_dl.ul_link_stats.mspConfirm = getCurrentMspConfirm() ? 1 : 0;
429 #else
430 otaPkt.tlm_dl.ul_link_stats.mspConfirm = 0;
431 #endif
432 nextTelemetryType = ELRS_TELEMETRY_TYPE_DATA;
433 // Start the count at 1 because the next will be DATA and doing +1 before checking
434 // against Max below is for some reason 10 bytes more code
435 telemetryBurstCount = 1;
436 } else {
437 if (telemetryBurstCount < telemetryBurstMax) {
438 telemetryBurstCount++;
439 } else {
440 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
443 otaPkt.tlm_dl.type = ELRS_TELEMETRY_TYPE_DATA;
444 otaPkt.tlm_dl.packageIndex = getCurrentTelemetryPayload(otaPkt.tlm_dl.payload);
447 uint16_t crc = calcCrc14((uint8_t *) &otaPkt, 7, crcInitializer);
448 otaPkt.crcHigh = (crc >> 8);
449 otaPkt.crcLow = crc;
450 memcpy((uint8_t *) telemetryPacket, (uint8_t *) &otaPkt, ELRS_RX_TX_BUFF_SIZE);
453 static void updatePhaseLock(void)
455 if (receiver.connectionState != ELRS_DISCONNECTED && phaseLockEprHaveBothEvents()) {
456 int32_t maxOffset = receiver.modParams->interval / 4;
457 pl.rawOffsetUs = constrain(phaseLockEprResult(), -maxOffset, maxOffset);
459 pl.offsetUs = simpleLPFilterUpdate(&pl.offsetFilter, pl.rawOffsetUs);
460 pl.offsetDeltaUs = simpleLPFilterUpdate(&pl.offsetDxFilter, pl.rawOffsetUs - pl.previousRawOffsetUs);
462 if (receiver.timerState == ELRS_TIM_LOCKED) {
463 // limit rate of freq offset adjustment, use slot 1 because
464 // telemetry can fall on slot 1 and will never get here
465 if (receiver.nonceRX % 8 == 1) {
466 if (pl.offsetUs > 0) {
467 expressLrsTimerIncreaseFrequencyOffset();
468 } else if (pl.offsetUs < 0) {
469 expressLrsTimerDecreaseFrequencyOffset();
474 if (receiver.connectionState != ELRS_CONNECTED) {
475 expressLrsUpdatePhaseShift(pl.rawOffsetUs >> 1);
476 } else {
477 expressLrsUpdatePhaseShift(pl.offsetUs >> 2);
480 pl.previousOffsetUs = pl.offsetUs;
481 pl.previousRawOffsetUs = pl.rawOffsetUs;
483 expressLrsTimerDebug();
485 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 0, pl.rawOffsetUs);
486 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 1, pl.offsetUs);
489 phaseLockEprReset();
492 //hwTimerCallbackTick
493 void expressLrsOnTimerTickISR(void) // this is 180 out of phase with the other callback, occurs mid-packet reception
495 updatePhaseLock();
496 receiver.nonceRX += 1;
498 // Save the LQ value before the inc() reduces it by 1
499 receiver.uplinkLQ = lqGet();
500 // Only advance the LQI period counter if we didn't send Telemetry this period
501 if (!receiver.alreadyTelemResp) {
502 lqNewPeriod();
505 receiver.alreadyTelemResp = false;
506 receiver.alreadyFhss = false;
508 receiver.rxHandleFromTick();
511 //hwTimerCallbackTock
512 void expressLrsOnTimerTockISR(void)
514 uint32_t currentTimeUs = micros();
516 phaseLockEprEvent(EPR_INTERNAL, currentTimeUs);
518 receiver.rxHandleFromTock();
521 static uint16_t lostConnectionCounter = 0;
523 void lostConnection(void)
525 lostConnectionCounter++;
527 receiver.rfModeCycleMultiplier = 1;
528 receiver.connectionState = ELRS_DISCONNECTED; //set lost connection
529 receiver.timerState = ELRS_TIM_DISCONNECTED;
530 expressLrsTimerResetFrequencyOffset();
531 receiver.freqOffset = 0;
532 pl.offsetUs = 0;
533 pl.offsetDeltaUs = 0;
534 pl.rawOffsetUs = 0;
535 pl.previousRawOffsetUs = 0;
536 receiver.gotConnectionMs = 0;
537 receiver.uplinkLQ = 0;
538 lqReset();
539 expressLrsPhaseLockReset();
540 receiver.alreadyTelemResp = false;
541 receiver.alreadyFhss = false;
543 if (!receiver.inBindingMode) {
544 expressLrsTimerStop();
545 setRfLinkRate(receiver.nextRateIndex); // also sets to initialFreq
546 receiver.startReceiving();
550 static void tentativeConnection(const uint32_t timeStampMs)
552 receiver.connectionState = ELRS_TENTATIVE;
553 connectionHasModelMatch = false;
554 receiver.timerState = ELRS_TIM_DISCONNECTED;
555 receiver.freqOffset = 0;
556 pl.offsetUs = 0;
557 pl.previousRawOffsetUs = 0;
558 expressLrsPhaseLockReset(); //also resets PFD
559 meanAccumulatorInit(&snrFilter);
560 receiver.rfModeCycledAtMs = timeStampMs; // give another 3 sec for lock to occur
562 // The caller MUST call hwTimer.resume(). It is not done here because
563 // the timer ISR will fire immediately and preempt any other code
566 static void gotConnection(const uint32_t timeStampMs)
568 if (receiver.connectionState == ELRS_CONNECTED) {
569 return; // Already connected
572 receiver.lockRFmode = true; // currently works as if LOCK_ON_FIRST_CONNECTION was enabled
574 receiver.connectionState = ELRS_CONNECTED; //we got a packet, therefore no lost connection
575 receiver.timerState = ELRS_TIM_TENTATIVE;
576 receiver.gotConnectionMs = timeStampMs;
578 if (rxExpressLrsSpiConfig()->rateIndex != receiver.nextRateIndex) {
579 rxExpressLrsSpiConfigMutable()->rateIndex = receiver.nextRateIndex;
580 receiver.configChanged = true;
584 //setup radio
585 static void initializeReceiver(void)
587 fhssGenSequence(elrsUidToSeed(receiver.UID), rxExpressLrsSpiConfig()->domain);
588 lqReset();
589 receiver.nonceRX = 0;
590 receiver.freqOffset = 0;
591 receiver.configChanged = false;
592 receiver.rssi = 0;
593 receiver.rssiFiltered = 0;
594 #ifdef USE_RX_RSNR
595 receiver.rsnrFiltered = 0;
596 #endif //USE_RX_RSNR
597 receiver.snr = 0;
598 receiver.uplinkLQ = 0;
599 receiver.switchMode = 0;
600 receiver.rateIndex = receiver.inBindingMode ? bindingRateIndex : rxExpressLrsSpiConfig()->rateIndex;
601 setRfLinkRate(receiver.rateIndex);
603 receiver.started = false;
604 receiver.alreadyFhss = false;
605 receiver.alreadyTelemResp = false;
606 receiver.lockRFmode = false;
607 receiver.timerState = ELRS_TIM_DISCONNECTED;
608 receiver.connectionState = ELRS_DISCONNECTED;
610 uint32_t timeStampMs = millis();
612 receiver.rfModeCycledAtMs = timeStampMs;
613 receiver.configCheckedAtMs = timeStampMs;
614 receiver.statsUpdatedAtMs = timeStampMs;
615 receiver.gotConnectionMs = timeStampMs;
616 receiver.lastSyncPacketMs = timeStampMs;
617 receiver.lastValidPacketMs = timeStampMs;
619 receiver.rfModeCycleMultiplier = ELRS_MODE_CYCLE_MULTIPLIER_SLOW / 2;
622 static void unpackBindPacket(volatile uint8_t *packet)
624 rxExpressLrsSpiConfigMutable()->UID[2] = packet[0];
625 rxExpressLrsSpiConfigMutable()->UID[3] = packet[1];
626 rxExpressLrsSpiConfigMutable()->UID[4] = packet[2];
627 rxExpressLrsSpiConfigMutable()->UID[5] = packet[3];
629 receiver.UID = rxExpressLrsSpiConfigMutable()->UID;
630 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
631 crcInitializer ^= ELRS_OTA_VERSION_ID;
632 receiver.inBindingMode = false;
633 receiver.configChanged = true; //after initialize as it sets it to false
637 * Process the assembled MSP packet in mspBuffer[]
639 static void processRFMspPacket(volatile elrsOtaPacket_t const * const otaPktPtr)
641 // Always examine MSP packets for bind information if in bind mode
642 // [1] is the package index, first packet of the MSP
643 if (receiver.inBindingMode && otaPktPtr->msp_ul.packageIndex == 1 && otaPktPtr->msp_ul.payload[0] == ELRS_MSP_BIND) {
644 unpackBindPacket((uint8_t *) &otaPktPtr->msp_ul.payload[1]); //onELRSBindMSP
645 return;
648 #ifdef USE_MSP_OVER_TELEMETRY
649 // Must be fully connected to process MSP, prevents processing MSP
650 // during sync, where packets can be received before connection
651 if (receiver.connectionState != ELRS_CONNECTED) {
652 return;
655 bool currentMspConfirmValue = getCurrentMspConfirm();
656 receiveMspData(otaPktPtr->msp_ul.packageIndex, otaPktPtr->msp_ul.payload);
657 if (currentMspConfirmValue != getCurrentMspConfirm()) {
658 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
660 if (hasFinishedMspData()) {
661 if (mspBuffer[ELRS_MSP_COMMAND_INDEX] == ELRS_MSP_SET_RX_CONFIG && mspBuffer[ELRS_MSP_COMMAND_INDEX + 1] == ELRS_MSP_MODEL_ID) { //mspReceiverComplete
662 if (rxExpressLrsSpiConfig()->modelId != mspBuffer[9]) { //UpdateModelMatch
663 rxExpressLrsSpiConfigMutable()->modelId = mspBuffer[9];
664 receiver.configChanged = true;
665 receiver.connectionState = ELRS_DISCONNECT_PENDING;
667 } else if (connectionHasModelMatch) {
668 processMspPacket(mspBuffer);
671 mspReceiverUnlock();
673 #endif
676 static bool processRFSyncPacket(volatile elrsOtaPacket_t const * const otaPktPtr, const uint32_t timeStampMs)
678 // Verify the first two of three bytes of the binding ID, which should always match
679 if (otaPktPtr->sync.UID3 != receiver.UID[3] || otaPktPtr->sync.UID4 != receiver.UID[4]) {
680 return false;
683 // The third byte will be XORed with inverse of the ModelId if ModelMatch is on
684 // Only require the first 18 bits of the UID to match to establish a connection
685 // but the last 6 bits must modelmatch before sending any data to the FC
686 if ((otaPktPtr->sync.UID5 & ~ELRS_MODELMATCH_MASK) != (receiver.UID[5] & ~ELRS_MODELMATCH_MASK)) {
687 return false;
690 receiver.lastSyncPacketMs = timeStampMs;
692 // Will change the packet air rate in loop() if this changes
693 receiver.nextRateIndex = domainIsTeam24() ? airRateIndexToIndex24(otaPktPtr->sync.rateIndex, receiver.rateIndex) : airRateIndexToIndex900(otaPktPtr->sync.rateIndex, receiver.rateIndex);
694 // Update switch mode encoding immediately
695 receiver.switchMode = otaPktPtr->sync.switchEncMode;
697 // Update TLM ratio
698 uint8_t tlmRateIn = otaPktPtr->sync.newTlmRatio + TLM_RATIO_NO_TLM;
699 uint8_t tlmDenom = tlmRatioEnumToValue(tlmRateIn);
700 if (currTlmDenom != tlmDenom) {
701 currTlmDenom = tlmDenom;
702 telemBurstValid = false;
705 // modelId = 0xff indicates modelMatch is disabled, the XOR does nothing in that case
706 uint8_t modelXor = (~rxExpressLrsSpiConfig()->modelId) & ELRS_MODELMATCH_MASK;
707 bool modelMatched = otaPktPtr->sync.UID5 == (receiver.UID[5] ^ modelXor);
709 if (receiver.connectionState == ELRS_DISCONNECTED || receiver.nonceRX != otaPktPtr->sync.nonce || fhssGetCurrIndex() != otaPktPtr->sync.fhssIndex || connectionHasModelMatch != modelMatched) {
710 fhssSetCurrIndex(otaPktPtr->sync.fhssIndex);
711 receiver.nonceRX = otaPktPtr->sync.nonce;
713 tentativeConnection(timeStampMs);
714 connectionHasModelMatch = modelMatched;
716 if (!expressLrsTimerIsRunning()) {
717 return true;
721 return false;
724 static bool validatePacketCrcStd(volatile elrsOtaPacket_t * const otaPktPtr)
726 uint16_t const inCRC = ((uint16_t) otaPktPtr->crcHigh << 8) + otaPktPtr->crcLow;
727 // For smHybrid the CRC only has the packet type in byte 0
728 // For smWide the FHSS slot is added to the CRC in byte 0 on PACKET_TYPE_RCDATAs
729 if (otaPktPtr->type == ELRS_RC_DATA_PACKET && receiver.switchMode == SM_WIDE) {
730 otaPktPtr->crcHigh = (receiver.nonceRX % receiver.modParams->fhssHopInterval) + 1;
731 } else {
732 otaPktPtr->crcHigh = 0;
734 uint16_t const calculatedCRC = calcCrc14((uint8_t *) otaPktPtr, 7, crcInitializer);
735 return inCRC == calculatedCRC;
738 rx_spi_received_e processRFPacket(volatile uint8_t *payload, uint32_t timeStampUs)
740 volatile elrsOtaPacket_t * const otaPktPtr = (elrsOtaPacket_t * const) dmaBuffer;
742 if (!validatePacketCrcStd(otaPktPtr)) {
743 return RX_SPI_RECEIVED_NONE;
746 phaseLockEprEvent(EPR_EXTERNAL, timeStampUs + PACKET_HANDLING_TO_TOCK_ISR_DELAY_US);
748 bool shouldStartTimer = false;
749 uint32_t timeStampMs = millis();
751 receiver.lastValidPacketMs = timeStampMs;
753 switch(otaPktPtr->type) {
754 case ELRS_RC_DATA_PACKET:
755 // Must be fully connected to process RC packets, prevents processing RC
756 // during sync, where packets can be received before connection
757 if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
758 if (receiver.switchMode == SM_WIDE) {
759 wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
760 if ((currTlmDenom < 8) || wideSwitchIndex == 7) {
761 confirmCurrentTelemetryPayload((otaPktPtr->rc.switches & 0x40) >> 6);
763 } else {
764 confirmCurrentTelemetryPayload(otaPktPtr->rc.switches & (1 << 6));
766 memcpy((uint8_t *) payload, (uint8_t *) dmaBuffer, ELRS_RX_TX_BUFF_SIZE); // stick data handling is done in expressLrsSetRcDataFromPayload
768 break;
769 case ELRS_MSP_DATA_PACKET:
770 processRFMspPacket(otaPktPtr);
771 break;
772 case ELRS_TLM_PACKET:
773 //not implemented
774 break;
775 case ELRS_SYNC_PACKET:
776 shouldStartTimer = processRFSyncPacket(otaPktPtr, timeStampMs) && !receiver.inBindingMode;
777 break;
778 default:
779 return RX_SPI_RECEIVED_NONE;
782 // Store the LQ/RSSI/Antenna
783 receiver.getRfLinkInfo(&receiver.rssi, &receiver.snr);
784 receiver.handleFreqCorrection(&receiver.freqOffset, receiver.currentFreq);
786 meanAccumulatorAdd(&snrFilter, receiver.snr);
787 // Received a packet, that's the definition of LQ
788 lqIncrease();
790 // Extend sync duration since we've received a packet at this rate
791 // but do not extend it indefinitely
792 receiver.rfModeCycleMultiplier = ELRS_MODE_CYCLE_MULTIPLIER_SLOW; //RFModeCycleMultiplierSlow
794 if (shouldStartTimer) {
795 expressLrsTimerResume();
798 return RX_SPI_RECEIVED_DATA;
801 static void updateTelemetryBurst(void)
803 if (telemBurstValid) {
804 return;
806 telemBurstValid = true;
808 uint32_t hz = rateEnumToHz(receiver.modParams->enumRate);
809 telemetryBurstMax = TELEM_MIN_LINK_INTERVAL * hz / currTlmDenom / 1000U;
811 // Reserve one slot for LINK telemetry
812 if (telemetryBurstMax > 1) {
813 --telemetryBurstMax;
814 } else {
815 telemetryBurstMax = 1;
818 // Notify the sender to adjust its expected throughput
819 updateTelemetryRate(hz, currTlmDenom, telemetryBurstMax);
822 /* If not connected will rotate through the RF modes looking for sync
823 * and blink LED
825 static void cycleRfMode(const uint32_t timeStampMs)
827 if (receiver.connectionState == ELRS_CONNECTED || receiver.inBindingMode) {
828 return;
830 // Actually cycle the RF mode if not LOCK_ON_FIRST_CONNECTION
831 if (receiver.lockRFmode == false && (timeStampMs - receiver.rfModeCycledAtMs) > (receiver.cycleIntervalMs * receiver.rfModeCycleMultiplier)) {
832 receiver.rfModeCycledAtMs = timeStampMs;
833 receiver.lastSyncPacketMs = timeStampMs; // reset this variable
834 receiver.rateIndex = (receiver.rateIndex + 1) % ELRS_RATE_MAX;
835 setRfLinkRate(receiver.rateIndex); // switch between rates
836 receiver.statsUpdatedAtMs = timeStampMs;
837 lqReset();
838 receiver.startReceiving();
840 // Switch to FAST_SYNC if not already in it (won't be if was just connected)
841 receiver.rfModeCycleMultiplier = 1;
842 } // if time to switch RF mode
845 #ifdef USE_RX_SX1280
846 static inline void configureReceiverForSX1280(void)
848 receiver.init = (elrsRxInitFnPtr) sx1280Init;
849 receiver.config = (elrsRxConfigFnPtr) sx1280Config;
850 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx1280StartReceiving;
851 receiver.rxISR = (elrsRxISRFnPtr) sx1280ISR;
852 receiver.rxHandleFromTock = (elrsRxHandleFromTockFnPtr) sx1280HandleFromTock;
853 receiver.rxHandleFromTick = (elrsRxBusyTimeoutFnPtr) sx1280HandleFromTick;
854 receiver.getRfLinkInfo = (elrsRxgetRfLinkInfoFnPtr) sx1280GetLastPacketStats;
855 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx1280AdjustFrequency;
857 #endif
859 #ifdef USE_RX_SX127X
860 static inline void configureReceiverForSX127x(void)
862 receiver.init = (elrsRxInitFnPtr) sx127xInit;
863 receiver.config = (elrsRxConfigFnPtr) sx127xConfig;
864 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx127xStartReceiving;
865 receiver.rxISR = (elrsRxISRFnPtr) sx127xISR;
866 receiver.getRfLinkInfo = (elrsRxgetRfLinkInfoFnPtr) sx127xGetLastPacketStats;
867 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx127xAdjustFrequency;
869 #endif
871 //setup
872 bool expressLrsSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState, rxSpiExtiConfig_t *extiConfig)
874 if (!rxSpiExtiConfigured()) {
875 return false;
878 rxSpiCommonIOInit(rxConfig);
880 rxRuntimeState->channelCount = ELRS_MAX_CHANNELS;
882 extiConfig->ioConfig = IOCFG_IPD;
883 extiConfig->trigger = BETAFLIGHT_EXTI_TRIGGER_RISING;
885 if (rxExpressLrsSpiConfig()->resetIoTag) {
886 receiver.resetPin = IOGetByTag(rxExpressLrsSpiConfig()->resetIoTag);
887 } else {
888 receiver.resetPin = IO_NONE;
891 if (rxExpressLrsSpiConfig()->busyIoTag) {
892 receiver.busyPin = IOGetByTag(rxExpressLrsSpiConfig()->busyIoTag);
893 } else {
894 receiver.busyPin = IO_NONE;
897 switch (rxExpressLrsSpiConfig()->domain) {
898 #ifdef USE_RX_SX127X
899 case AU433:
900 case AU915:
901 case EU433:
902 case EU868:
903 case IN866:
904 case FCC915:
905 configureReceiverForSX127x();
906 bindingRateIndex = ELRS_BINDING_RATE_900;
907 break;
908 #endif
909 #ifdef USE_RX_SX1280
910 case ISM2400:
911 FALLTHROUGH;
912 case CE2400:
913 configureReceiverForSX1280();
914 bindingRateIndex = ELRS_BINDING_RATE_24;
915 break;
916 #endif
917 default:
918 return false;
921 if (!receiver.init(receiver.resetPin, receiver.busyPin)) {
922 return false;
925 if (rssiSource == RSSI_SOURCE_NONE) {
926 rssiSource = RSSI_SOURCE_RX_PROTOCOL;
929 if (linkQualitySource == LQ_SOURCE_NONE) {
930 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
933 if (rxExpressLrsSpiConfig()->UID[0] || rxExpressLrsSpiConfig()->UID[1]
934 || rxExpressLrsSpiConfig()->UID[2] || rxExpressLrsSpiConfig()->UID[3]
935 || rxExpressLrsSpiConfig()->UID[4] || rxExpressLrsSpiConfig()->UID[5]) {
936 receiver.inBindingMode = false;
937 receiver.UID = rxExpressLrsSpiConfig()->UID;
938 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
939 crcInitializer ^= ELRS_OTA_VERSION_ID;
940 } else {
941 receiver.inBindingMode = true;
942 receiver.UID = BindingUID;
943 crcInitializer = 0;
946 expressLrsPhaseLockReset();
948 expressLrsInitialiseTimer(RX_EXPRESSLRS_TIMER_INSTANCE, &receiver.timerUpdateCb);
949 expressLrsTimerStop();
951 generateCrc14Table();
952 initializeReceiver();
954 initTelemetry();
955 #ifdef USE_MSP_OVER_TELEMETRY
956 setMspDataToReceive(ELRS_MSP_BUFFER_SIZE, mspBuffer);
957 #endif
959 // Timer IRQs must only be enabled after the receiver is configured otherwise race conditions occur.
960 expressLrsTimerEnableIRQs();
962 return true;
965 static void handleConnectionStateUpdate(const uint32_t timeStampMs)
967 if ((receiver.connectionState != ELRS_DISCONNECTED) && (receiver.modParams->index != receiver.nextRateIndex)) { // forced change
968 lostConnection();
969 receiver.lastSyncPacketMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
970 receiver.rfModeCycledAtMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
971 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
972 #ifdef USE_RX_RSSI_DBM
973 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
974 #endif
975 #ifdef USE_RX_RSNR
976 setRsnrDirect(-30);
977 #endif
978 #ifdef USE_RX_LINK_QUALITY_INFO
979 setLinkQualityDirect(0);
980 #endif
983 if (receiver.connectionState == ELRS_TENTATIVE && ((timeStampMs - receiver.lastSyncPacketMs) > receiver.rfPerfParams->rxLockTimeoutMs)) {
984 lostConnection();
985 receiver.rfModeCycledAtMs = timeStampMs;
986 receiver.lastSyncPacketMs = timeStampMs;
989 cycleRfMode(timeStampMs);
991 // Note that will updated from ISR and could thus be ahead of the timestamp
992 uint32_t localLastValidPacket = receiver.lastValidPacketMs;
994 // Determine the time in ms since the last valid packet was received. As this will be received under interrupt control it may be
995 // after the timeStampMs value was taken in which case treat as if it arrived at the same time to avoid a timeout
996 int32_t lastPacketDeltaMs = cmp32(timeStampMs, localLastValidPacket);
998 if (lastPacketDeltaMs < 0) {
999 lastPacketDeltaMs = 0;
1002 if ((receiver.connectionState == ELRS_DISCONNECT_PENDING) || // check if we lost conn.
1003 ((receiver.connectionState == ELRS_CONNECTED) && ((uint32_t)lastPacketDeltaMs > receiver.rfPerfParams->disconnectTimeoutMs))) {
1004 lostConnection();
1007 if ((receiver.connectionState == ELRS_TENTATIVE) && (abs(pl.offsetDeltaUs) <= 10) && (pl.offsetUs < 100) && (lqGet() > minLqForChaos())) {
1008 gotConnection(timeStampMs); // detects when we are connected
1011 if ((receiver.timerState == ELRS_TIM_TENTATIVE) && ((timeStampMs - receiver.gotConnectionMs) > ELRS_CONSIDER_CONNECTION_GOOD_MS) && (abs(pl.offsetDeltaUs) <= 5)) {
1012 receiver.timerState = ELRS_TIM_LOCKED;
1015 if ((receiver.connectionState == ELRS_CONNECTED) && (abs(pl.offsetDeltaUs) > 10) && (pl.offsetUs >= 100) && (lqGet() <= minLqForChaos())) {
1016 lostConnection(); // SPI: resync when we're in chaos territory
1020 static void handleConfigUpdate(const uint32_t timeStampMs)
1022 if ((timeStampMs - receiver.configCheckedAtMs) > ELRS_CONFIG_CHECK_MS) {
1023 receiver.configCheckedAtMs = timeStampMs;
1024 if (receiver.configChanged) {
1025 saveConfigAndNotify();
1026 receiver.initializeReceiverPending = true;
1027 receiver.configChanged = false;
1032 static void handleLinkStatsUpdate(const uint32_t timeStampMs)
1034 if ((timeStampMs - receiver.statsUpdatedAtMs) > ELRS_LINK_STATS_CHECK_MS) {
1036 receiver.statsUpdatedAtMs = timeStampMs;
1038 if (receiver.connectionState == ELRS_CONNECTED) {
1039 receiver.rssiFiltered = simpleLPFilterUpdate(&rssiFilter, receiver.rssi);
1040 uint16_t rssiScaled = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 0, 1023);
1041 setRssi(rssiScaled, RSSI_SOURCE_RX_PROTOCOL);
1042 #ifdef USE_RX_RSSI_DBM
1043 setRssiDbm(receiver.rssiFiltered, RSSI_SOURCE_RX_PROTOCOL);
1044 #endif
1045 #ifdef USE_RX_RSNR
1046 receiver.rsnrFiltered = simpleLPFilterUpdate(&rsnrFilter, receiver.snr/4);
1047 setRsnr(receiver.rsnrFiltered);
1048 #endif
1049 #ifdef USE_RX_LINK_QUALITY_INFO
1050 setLinkQualityDirect(receiver.uplinkLQ);
1051 #endif
1052 #ifdef USE_RX_LINK_UPLINK_POWER
1053 rxSetUplinkTxPwrMw(txPowerIndexToValue(txPower));
1054 #endif
1055 } else {
1056 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
1057 #ifdef USE_RX_RSSI_DBM
1058 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
1059 #endif
1060 #ifdef USE_RX_RSNR
1061 setRsnrDirect(-30);
1062 #endif
1063 #ifdef USE_RX_LINK_QUALITY_INFO
1064 setLinkQualityDirect(0);
1065 #endif
1070 void expressLrsHandleTelemetryUpdate(void)
1072 if (receiver.connectionState != ELRS_CONNECTED || (receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM)) {
1073 return;
1076 uint8_t *nextPayload = 0;
1077 uint8_t nextPlayloadSize = 0;
1078 if (!isTelemetrySenderActive() && getNextTelemetryPayload(&nextPlayloadSize, &nextPayload)) {
1079 setTelemetryDataToTransmit(nextPlayloadSize, nextPayload);
1081 updateTelemetryBurst();
1084 void expressLrsSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
1086 if (rcData && payload) {
1087 volatile elrsOtaPacket_t * const otaPktPtr = (elrsOtaPacket_t * const) payload;
1088 receiver.switchMode == SM_WIDE ? unpackChannelDataHybridWide(rcData, otaPktPtr) : unpackChannelDataHybridSwitch8(rcData, otaPktPtr);
1092 static void enterBindingMode(void)
1094 // Set UID to special binding values
1095 receiver.UID = BindingUID;
1096 crcInitializer = 0;
1097 receiver.inBindingMode = true;
1099 setRfLinkRate(bindingRateIndex);
1100 receiver.startReceiving();
1103 void expressLrsDoTelem(void)
1105 expressLrsHandleTelemetryUpdate();
1106 expressLrsSendTelemResp();
1108 if (!expressLrsTelemRespReq() && lqPeriodIsSet()) {
1109 // TODO No need to handle this on SX1280, but will on SX127x
1110 // TODO this needs to be DMA aswell, SX127x unlikely to work right now
1111 receiver.handleFreqCorrection(&receiver.freqOffset, receiver.currentFreq); //corrects for RX freq offset
1115 rx_spi_received_e expressLrsDataReceived(uint8_t *payloadBuffer)
1117 payload = payloadBuffer;
1119 rx_spi_received_e rfPacketReturnStatus = RX_SPI_RECEIVED_NONE;
1121 if (!receiver.started && (systemState & SYSTEM_STATE_READY)) {
1122 receiver.started = true;
1123 receiver.startReceiving(); // delay receiving after initialization to ensure a clean connect
1126 if (receiver.initializeReceiverPending) {
1127 initializeReceiver();
1128 receiver.initializeReceiverPending = false;
1131 if (rxSpiCheckBindRequested(true)) {
1132 enterBindingMode();
1135 const uint32_t timeStampMs = millis();
1136 handleConnectionStateUpdate(timeStampMs);
1137 handleConfigUpdate(timeStampMs);
1138 handleLinkStatsUpdate(timeStampMs);
1140 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 0, lostConnectionCounter);
1141 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 1, receiver.rssiFiltered);
1142 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 2, receiver.snr / 4);
1143 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 3, receiver.uplinkLQ);
1145 receiver.inBindingMode ? rxSpiLedBlinkBind() : rxSpiLedBlinkRxLoss(rfPacketStatus);
1147 if (rfPacketStatus != RX_SPI_RECEIVED_NONE) {
1148 // A packet has been received since last time
1149 rfPacketReturnStatus = rfPacketStatus;
1150 rfPacketStatus = RX_SPI_RECEIVED_NONE;
1152 return rfPacketReturnStatus;
1155 void expressLrsStop(void)
1157 if (receiver.started) {
1158 lostConnection();
1162 void expressLrsISR(bool runAlways)
1164 if (runAlways || !expressLrsTimerIsRunning()) {
1165 receiver.rxISR();
1168 #endif /* USE_RX_EXPRESSLRS */