Add OSD_STATE_GROUP_ELEMENTS state to osdUpdate() and optimise DMA vs polled MAX7456...
[betaflight.git] / src / main / rx / expresslrs.c
blob4991b06e5aa19aed1d59cd88a0e0b6f9dae40f08
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 <string.h>
32 #include "platform.h"
34 #ifdef USE_RX_EXPRESSLRS
36 #include "build/atomic.h"
37 #include "build/debug.h"
38 #include "build/debug_pin.h"
40 #include "common/maths.h"
41 #include "common/filter.h"
43 #include "drivers/io.h"
44 #include "drivers/nvic.h"
45 #include "drivers/rx/rx_spi.h"
46 #include "drivers/system.h"
47 #include "drivers/time.h"
48 #include "drivers/timer.h"
49 #include "drivers/rx/rx_sx127x.h"
50 #include "drivers/rx/rx_sx1280.h"
51 #include "drivers/rx/expresslrs_driver.h"
53 #include "config/config.h"
54 #include "config/feature.h"
56 #include "fc/init.h"
58 #include "pg/pg.h"
59 #include "pg/pg_ids.h"
60 #include "pg/rx_spi.h"
61 #include "pg/rx_spi_expresslrs.h"
63 #include "rx/rx.h"
64 #include "rx/rx_spi.h"
65 #include "rx/rx_spi_common.h"
67 #include "rx/expresslrs.h"
68 #include "rx/expresslrs_common.h"
69 #include "rx/expresslrs_impl.h"
70 #include "rx/expresslrs_telemetry.h"
72 STATIC_UNIT_TESTED elrsReceiver_t receiver;
73 static const uint8_t BindingUID[6] = {0,1,2,3,4,5}; // Special binding UID values
74 static uint16_t crcInitializer = 0;
75 static uint8_t bindingRateIndex = 0;
76 static bool connectionHasModelMatch = false;
77 static uint8_t txPower = 0;
78 static uint8_t wideSwitchIndex = 0;
80 static simpleLowpassFilter_t rssiFilter;
82 static void rssiFilterReset(void)
84 simpleLPFilterInit(&rssiFilter, 3, 5);
87 #define PACKET_HANDLING_TO_TOCK_ISR_DELAY_US 250
90 // Event pair recorder
93 typedef enum {
94 EPR_FIRST,
95 EPR_SECOND,
96 } eprEvent_e;
98 #define EPR_EVENT_COUNT 2
100 typedef struct eprState_s {
101 uint32_t eventAtUs[EPR_EVENT_COUNT];
102 bool eventRecorded[EPR_EVENT_COUNT];
103 } eprState_t;
105 eprState_t eprState = {
106 .eventAtUs = {0},
107 .eventRecorded = {0},
110 static void expressLrsEPRRecordEvent(eprEvent_e event, uint32_t currentTimeUs)
112 eprState.eventAtUs[event] = currentTimeUs;
113 eprState.eventRecorded[event] = true;
116 static bool expressLrsEPRHaveBothEvents(void)
118 bool bothEventsRecorded = eprState.eventRecorded[EPR_SECOND] && eprState.eventRecorded[EPR_FIRST];
119 return bothEventsRecorded;
122 static int32_t expressLrsEPRGetResult(void)
124 if (!expressLrsEPRHaveBothEvents()) {
125 return 0;
128 return (int32_t)(eprState.eventAtUs[EPR_SECOND] - eprState.eventAtUs[EPR_FIRST]);
131 static void expressLrsEPRReset(void)
133 memset(&eprState, 0, sizeof(eprState_t));
138 // Phase Lock
142 #define EPR_INTERNAL EPR_FIRST
143 #define EPR_EXTERNAL EPR_SECOND
145 typedef struct phaseLockState_s {
146 simpleLowpassFilter_t offsetFilter;
147 simpleLowpassFilter_t offsetDxFilter;
149 int32_t rawOffsetUs;
150 int32_t previousRawOffsetUs;
152 int32_t offsetUs;
153 int32_t offsetDeltaUs;
154 int32_t previousOffsetUs;
155 } phaseLockState_t;
157 static phaseLockState_t pl;
159 static void expressLrsPhaseLockReset(void)
161 simpleLPFilterInit(&pl.offsetFilter, 2, 5);
162 simpleLPFilterInit(&pl.offsetDxFilter, 4, 5);
164 expressLrsEPRReset();
167 static uint8_t nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
169 static uint8_t telemetryBurstCount = 1;
170 static uint8_t telemetryBurstMax = 1;
171 static bool telemBurstValid = false;
173 // Maximum ms between LINK_STATISTICS packets for determining burst max
174 #define TELEM_MIN_LINK_INTERVAL 512U
176 #ifdef USE_MSP_OVER_TELEMETRY
177 static uint8_t mspBuffer[ELRS_MSP_BUFFER_SIZE];
178 #endif
181 // Stick unpacking
184 static void setRssiChannelData(uint16_t *rcData)
186 rcData[ELRS_LQ_CHANNEL] = scaleRange(receiver.uplinkLQ, 0, 100, 988, 2011);
187 rcData[ELRS_RSSI_CHANNEL] = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 988, 2011);
190 static void unpackAnalogChannelData(uint16_t *rcData, const uint8_t *payload)
192 rcData[0] = convertAnalog((payload[0] << 3) | ((payload[4] & 0xC0) >> 5));
193 rcData[1] = convertAnalog((payload[1] << 3) | ((payload[4] & 0x30) >> 3));
194 rcData[2] = convertAnalog((payload[2] << 3) | ((payload[4] & 0x0C) >> 1));
195 rcData[3] = convertAnalog((payload[3] << 3) | ((payload[4] & 0x03) << 1));
199 * Hybrid switches uses 10 bits for each analog channel,
200 * 2 bits for the low latency switch[0]
201 * 3 bits for the round-robin switch index and 2 bits for the value
202 * 4 analog channels, 1 low latency switch and round robin switch data = 47 bits (1 free)
204 * sets telemetry status bit
206 static void unpackChannelDataHybridSwitch8(uint16_t *rcData, const uint8_t *payload)
208 unpackAnalogChannelData(rcData, payload);
210 const uint8_t switchByte = payload[5];
212 // The low latency switch
213 rcData[4] = convertSwitch1b((switchByte & 0x40) >> 6);
215 // The round-robin switch, switchIndex is actually index-1
216 // to leave the low bit open for switch 7 (sent as 0b11x)
217 // where x is the high bit of switch 7
218 uint8_t switchIndex = (switchByte & 0x38) >> 3;
219 uint16_t switchValue = convertSwitch3b(switchByte & 0x07);
221 switch (switchIndex) {
222 case 0:
223 rcData[5] = switchValue;
224 break;
225 case 1:
226 rcData[6] = switchValue;
227 break;
228 case 2:
229 rcData[7] = switchValue;
230 break;
231 case 3:
232 rcData[8] = switchValue;
233 break;
234 case 4:
235 rcData[9] = switchValue;
236 break;
237 case 5:
238 rcData[10] = switchValue;
239 break;
240 case 6:
241 FALLTHROUGH;
242 case 7:
243 rcData[11] = convertSwitchNb(switchByte & 0x0F, 15); //4-bit
244 break;
245 default:
246 break;
249 setRssiChannelData(rcData);
253 * HybridWide switches decoding of over the air data
255 * Hybrid switches uses 10 bits for each analog channel,
256 * 1 bits for the low latency switch[0]
257 * 6 or 7 bits for the round-robin switch
258 * 1 bit for the TelemetryStatus, which may be in every packet or just idx 7
259 * depending on TelemetryRatio
261 * Output: crsf.PackedRCdataOut, crsf.LinkStatistics.uplink_TX_Power
262 * Returns: TelemetryStatus bit
264 static void unpackChannelDataHybridWide(uint16_t *rcData, const uint8_t *payload)
266 unpackAnalogChannelData(rcData, payload);
267 const uint8_t switchByte = payload[5];
269 // The low latency switch
270 rcData[4] = convertSwitch1b((switchByte & 0x80) >> 7);
272 // The round-robin switch, 6-7 bits with the switch index implied by the nonce. Some logic moved to processRFPacket
273 if (wideSwitchIndex >= 7) {
274 txPower = switchByte & 0x3F;
275 } else {
276 uint8_t bins;
277 uint16_t switchValue;
278 if (tlmRatioEnumToValue(receiver.modParams->tlmInterval) < 8) {
279 bins = 63;
280 switchValue = switchByte & 0x3F; // 6-bit
281 } else {
282 bins = 127;
283 switchValue = switchByte & 0x7F; // 7-bit
286 switchValue = convertSwitchNb(switchValue, bins);
287 rcData[5 + wideSwitchIndex] = switchValue;
290 setRssiChannelData(rcData);
293 static void startReceiving(void)
295 dbgPinLo(1);
296 receiver.startReceiving();
299 static uint8_t minLqForChaos(void)
301 // Determine the most number of CRC-passing packets we could receive on
302 // a single channel out of 100 packets that fill the LQcalc span.
303 // The LQ must be GREATER THAN this value, not >=
304 // The amount of time we coexist on the same channel is
305 // 100 divided by the total number of packets in a FHSS loop (rounded up)
306 // and there would be 4x packets received each time it passes by so
307 // FHSShopInterval * ceil(100 / FHSShopInterval * numfhss) or
308 // FHSShopInterval * trunc((100 + (FHSShopInterval * numfhss) - 1) / (FHSShopInterval * numfhss))
309 // With a interval of 4 this works out to: 2.4=4, FCC915=4, AU915=8, EU868=8, EU/AU433=36
310 const uint32_t numfhss = getFHSSNumEntries();
311 const uint8_t interval = receiver.modParams->fhssHopInterval;
312 return interval * ((interval * numfhss + 99) / (interval * numfhss));
315 static void setRFLinkRate(const uint8_t index)
317 #if defined(USE_RX_SX1280) && defined(USE_RX_SX127X)
318 receiver.modParams = (rxExpressLrsSpiConfig()->domain == ISM2400) ? &airRateConfig[1][index] : &airRateConfig[0][index];
319 receiver.rfPerfParams = (rxExpressLrsSpiConfig()->domain == ISM2400) ? &rfPerfConfig[1][index] : &rfPerfConfig[0][index];
320 #else
321 receiver.modParams = &airRateConfig[0][index];
322 receiver.rfPerfParams = &rfPerfConfig[0][index];
323 #endif
324 receiver.currentFreq = getInitialFreq(receiver.freqOffset);
325 // Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
326 receiver.cycleIntervalMs = ((uint32_t)11U * getFHSSNumEntries() * receiver.modParams->fhssHopInterval * receiver.modParams->interval) / (10U * 1000U);
328 receiver.config(receiver.modParams->bw, receiver.modParams->sf, receiver.modParams->cr, receiver.currentFreq, receiver.modParams->preambleLen, receiver.UID[5] & 0x01);
330 expressLrsUpdateTimerInterval(receiver.modParams->interval);
332 rssiFilterReset();
333 receiver.nextRateIndex = index; // presumably we just handled this
334 telemBurstValid = false;
336 #ifdef USE_RX_LINK_QUALITY_INFO
337 rxSetRfMode((uint8_t)RATE_4HZ - (uint8_t)receiver.modParams->enumRate);
338 #endif
341 static bool handleFHSS(void)
343 uint8_t modresultFHSS = (receiver.nonceRX + 1) % receiver.modParams->fhssHopInterval;
345 if ((receiver.modParams->fhssHopInterval == 0) || receiver.alreadyFHSS == true || receiver.inBindingMode || (modresultFHSS != 0) || (receiver.connectionState == ELRS_DISCONNECTED)) {
346 return false;
349 receiver.alreadyFHSS = true;
350 receiver.currentFreq = FHSSgetNextFreq(receiver.freqOffset);
351 receiver.setFrequency(receiver.currentFreq);
353 uint8_t modresultTLM = (receiver.nonceRX + 1) % (tlmRatioEnumToValue(receiver.modParams->tlmInterval));
355 if (modresultTLM != 0 || receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM) { // if we are about to send a tlm response don't bother going back to rx
356 startReceiving();
358 return true;
361 static bool shouldSendTelemetryResponse(void)
363 uint8_t modresult = (receiver.nonceRX + 1) % tlmRatioEnumToValue(receiver.modParams->tlmInterval);
364 if ((receiver.connectionState == ELRS_DISCONNECTED) || (receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM) || (receiver.alreadyTLMresp == true) || (modresult != 0)) {
365 return false; // don't bother sending tlm if disconnected or TLM is off
366 } else {
367 return true;
371 static void handleSendTelemetryResponse(void)
373 uint8_t packet[8];
375 uint8_t *data;
376 uint8_t maxLength;
377 uint8_t packageIndex;
379 receiver.alreadyTLMresp = true;
380 packet[0] = ELRS_TLM_PACKET;
382 if (nextTelemetryType == ELRS_TELEMETRY_TYPE_LINK || !isTelemetrySenderActive()) {
383 packet[1] = ELRS_TELEMETRY_TYPE_LINK;
384 packet[2] = receiver.rssiFiltered > 0 ? 0 : -receiver.rssiFiltered; //diversity not supported
385 packet[3] = connectionHasModelMatch << 7;
386 packet[4] = receiver.snr;
387 packet[5] = receiver.uplinkLQ;
388 #ifdef USE_MSP_OVER_TELEMETRY
389 packet[6] = getCurrentMspConfirm() ? 1 : 0;
390 #else
391 packet[6] = 0;
392 #endif
393 nextTelemetryType = ELRS_TELEMETRY_TYPE_DATA;
394 // Start the count at 1 because the next will be DATA and doing +1 before checking
395 // against Max below is for some reason 10 bytes more code
396 telemetryBurstCount = 1;
397 } else {
398 if (telemetryBurstCount < telemetryBurstMax) {
399 telemetryBurstCount++;
400 } else {
401 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
404 getCurrentTelemetryPayload(&packageIndex, &maxLength, &data);
405 packet[1] = (packageIndex << ELRS_TELEMETRY_SHIFT) + ELRS_TELEMETRY_TYPE_DATA;
406 packet[2] = maxLength > 0 ? *data : 0;
407 packet[3] = maxLength >= 1 ? *(data + 1) : 0;
408 packet[4] = maxLength >= 2 ? *(data + 2) : 0;
409 packet[5] = maxLength >= 3 ? *(data + 3) : 0;
410 packet[6] = maxLength >= 4 ? *(data + 4) : 0;
413 uint16_t crc = calcCrc14(packet, 7, crcInitializer);
414 packet[0] |= (crc >> 6) & 0xFC;
415 packet[7] = crc & 0xFF;
417 dbgPinHi(1);
418 receiver.transmitData(packet, ELRS_RX_TX_BUFF_SIZE);
421 static void updatePhaseLock(void)
423 if (receiver.connectionState != ELRS_DISCONNECTED && expressLrsEPRHaveBothEvents()) {
424 int32_t maxOffset = receiver.modParams->interval / 4;
425 pl.rawOffsetUs = constrain(expressLrsEPRGetResult(), -maxOffset, maxOffset);
427 pl.offsetUs = simpleLPFilterUpdate(&pl.offsetFilter, pl.rawOffsetUs);
428 pl.offsetDeltaUs = simpleLPFilterUpdate(&pl.offsetDxFilter, pl.rawOffsetUs - pl.previousRawOffsetUs);
430 if (receiver.timerState == ELRS_TIM_LOCKED && lqPeriodIsSet()) {
431 if (receiver.nonceRX % 8 == 0) { //limit rate of freq offset adjustment slightly
432 if (pl.offsetUs > 0) {
433 expressLrsTimerIncreaseFrequencyOffset();
434 } else if (pl.offsetUs < 0) {
435 expressLrsTimerDecreaseFrequencyOffset();
440 if (receiver.connectionState != ELRS_CONNECTED) {
441 expressLrsUpdatePhaseShift(pl.rawOffsetUs >> 1);
442 } else {
443 expressLrsUpdatePhaseShift(pl.offsetUs >> 2);
446 pl.previousOffsetUs = pl.offsetUs;
447 pl.previousRawOffsetUs = pl.rawOffsetUs;
449 expressLrsTimerDebug();
451 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 0, pl.rawOffsetUs);
452 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 1, pl.offsetUs);
455 expressLrsEPRReset();
458 //hwTimerCallbackTick
459 void expressLrsOnTimerTickISR(void) // this is 180 out of phase with the other callback, occurs mid-packet reception
461 updatePhaseLock();
462 receiver.nonceRX += 1;
464 // Save the LQ value before the inc() reduces it by 1
465 receiver.uplinkLQ = lqGet();
466 // Only advance the LQI period counter if we didn't send Telemetry this period
467 if (!receiver.alreadyTLMresp) {
468 lqNewPeriod();
471 receiver.alreadyTLMresp = false;
472 receiver.alreadyFHSS = false;
475 //hwTimerCallbackTock
476 void expressLrsOnTimerTockISR(void)
478 uint32_t currentTimeUs = micros();
480 expressLrsEPRRecordEvent(EPR_INTERNAL, currentTimeUs);
482 receiver.fhssRequired = true; //Rest of the code is moved to expressLrsDataReceived to avoid race condition
485 static uint16_t lostConnectionCounter = 0;
487 void lostConnection(void)
489 lostConnectionCounter++;
491 receiver.rfModeCycleMultiplier = 1;
492 receiver.connectionState = ELRS_DISCONNECTED; //set lost connection
493 receiver.timerState = ELRS_TIM_DISCONNECTED;
494 expressLrsTimerResetFrequencyOffset();
495 receiver.freqOffset = 0;
496 pl.offsetUs = 0;
497 pl.offsetDeltaUs = 0;
498 pl.rawOffsetUs = 0;
499 pl.previousRawOffsetUs = 0;
500 receiver.gotConnectionMs = 0;
501 receiver.uplinkLQ = 0;
502 lqReset();
503 expressLrsPhaseLockReset();
504 receiver.alreadyTLMresp = false;
505 receiver.alreadyFHSS = false;
507 if (!receiver.inBindingMode) {
508 //while (micros() - expressLrsEPRGetResult() > 250); // time it just after the tock() TODO this currently breaks and is blocking, not a fan of this.
509 expressLrsTimerStop();
510 setRFLinkRate(receiver.nextRateIndex); // also sets to initialFreq
511 startReceiving();
515 static void tentativeConnection(const uint32_t timeStampMs)
517 receiver.connectionState = ELRS_TENTATIVE;
518 connectionHasModelMatch = false;
519 receiver.timerState = ELRS_TIM_DISCONNECTED;
520 receiver.freqOffset = 0;
521 pl.offsetUs = 0;
522 pl.previousRawOffsetUs = 0;
523 expressLrsPhaseLockReset(); //also resets PFD
524 receiver.rfModeCycledAtMs = timeStampMs; // give another 3 sec for lock to occur
526 // The caller MUST call hwTimer.resume(). It is not done here because
527 // the timer ISR will fire immediately and preempt any other code
530 static void gotConnection(const uint32_t timeStampMs)
532 if (receiver.connectionState == ELRS_CONNECTED) {
533 return; // Already connected
536 receiver.lockRFmode = true; // currently works as if LOCK_ON_FIRST_CONNECTION was enabled
538 receiver.connectionState = ELRS_CONNECTED; //we got a packet, therefore no lost connection
539 receiver.timerState = ELRS_TIM_TENTATIVE;
540 receiver.gotConnectionMs = timeStampMs;
542 if (rxExpressLrsSpiConfig()->rateIndex != receiver.rateIndex) {
543 rxExpressLrsSpiConfigMutable()->rateIndex = receiver.rateIndex;
544 receiver.configChanged = true;
548 //setup radio
549 static void initializeReceiver(void)
551 FHSSrandomiseFHSSsequence(receiver.UID, rxExpressLrsSpiConfig()->domain);
552 lqReset();
553 receiver.nonceRX = 0;
554 receiver.freqOffset = 0;
555 receiver.configChanged = false;
556 receiver.rssi = 0;
557 receiver.rssiFiltered = 0;
558 receiver.snr = 0;
559 receiver.uplinkLQ = 0;
560 receiver.rateIndex = receiver.inBindingMode ? bindingRateIndex : rxExpressLrsSpiConfig()->rateIndex;
561 setRFLinkRate(receiver.rateIndex);
563 receiver.started = false;
564 receiver.alreadyFHSS = false;
565 receiver.alreadyTLMresp = false;
566 receiver.lockRFmode = false;
567 receiver.timerState = ELRS_TIM_DISCONNECTED;
568 receiver.connectionState = ELRS_DISCONNECTED;
570 uint32_t timeStampMs = millis();
572 receiver.rfModeCycledAtMs = timeStampMs;
573 receiver.configCheckedAtMs = timeStampMs;
574 receiver.statsUpdatedAtMs = timeStampMs;
575 receiver.gotConnectionMs = timeStampMs;
576 receiver.lastSyncPacketMs = timeStampMs;
577 receiver.lastValidPacketMs = timeStampMs;
579 receiver.rfModeCycleMultiplier = 1;
582 static void unpackBindPacket(uint8_t *packet)
584 rxExpressLrsSpiConfigMutable()->UID[2] = packet[3];
585 rxExpressLrsSpiConfigMutable()->UID[3] = packet[4];
586 rxExpressLrsSpiConfigMutable()->UID[4] = packet[5];
587 rxExpressLrsSpiConfigMutable()->UID[5] = packet[6];
589 receiver.UID = rxExpressLrsSpiConfigMutable()->UID;
590 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
591 receiver.inBindingMode = false;
593 initializeReceiver();
595 receiver.configChanged = true; //after initialize as it sets it to false
599 * Process the assembled MSP packet in mspBuffer[]
601 static void processRFMspPacket(uint8_t *packet)
603 // Always examine MSP packets for bind information if in bind mode
604 // [1] is the package index, first packet of the MSP
605 if (receiver.inBindingMode && packet[1] == 1 && packet[2] == ELRS_MSP_BIND) {
606 unpackBindPacket(packet); //onELRSBindMSP
607 return;
610 #ifdef USE_MSP_OVER_TELEMETRY
611 // Must be fully connected to process MSP, prevents processing MSP
612 // during sync, where packets can be received before connection
613 if (receiver.connectionState != ELRS_CONNECTED) {
614 return;
617 bool currentMspConfirmValue = getCurrentMspConfirm();
618 receiveMspData(packet[1], packet + 2);
619 if (currentMspConfirmValue != getCurrentMspConfirm()) {
620 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
622 if (hasFinishedMspData()) {
623 if (mspBuffer[ELRS_MSP_COMMAND_INDEX] == ELRS_MSP_SET_RX_CONFIG && mspBuffer[ELRS_MSP_COMMAND_INDEX + 1] == ELRS_MSP_MODEL_ID) { //mspReceiverComplete
624 if (rxExpressLrsSpiConfig()->modelId != mspBuffer[9]) { //UpdateModelMatch
625 rxExpressLrsSpiConfigMutable()->modelId = mspBuffer[9];
626 receiver.configChanged = true;
627 receiver.connectionState = ELRS_DISCONNECT_PENDING;
629 } else if (connectionHasModelMatch) {
630 processMspPacket(mspBuffer);
633 mspReceiverUnlock();
635 #endif
638 static bool processRFSyncPacket(uint8_t *packet, const uint32_t timeStampMs)
640 // Verify the first two of three bytes of the binding ID, which should always match
641 if (packet[4] != receiver.UID[3] || packet[5] != receiver.UID[4]) {
642 return false;
645 // The third byte will be XORed with inverse of the ModelId if ModelMatch is on
646 // Only require the first 18 bits of the UID to match to establish a connection
647 // but the last 6 bits must modelmatch before sending any data to the FC
648 if ((packet[6] & ~ELRS_MODELMATCH_MASK) != (receiver.UID[5] & ~ELRS_MODELMATCH_MASK)) {
649 return false;
652 receiver.lastSyncPacketMs = timeStampMs;
654 // Will change the packet air rate in loop() if this changes
655 receiver.nextRateIndex = (packet[3] & 0xC0) >> 6;
656 uint8_t tlmRateIn = (packet[3] & 0x38) >> 3;
657 uint8_t switchEncMode = ((packet[3] & 0x06) >> 1) - 1; //spi implementation uses 0 based index for hybrid
659 // Update switch mode encoding immediately
660 if (switchEncMode != rxExpressLrsSpiConfig()->switchMode) {
661 rxExpressLrsSpiConfigMutable()->switchMode = switchEncMode;
662 receiver.configChanged = true;
665 // Update TLM ratio
666 if (receiver.modParams->tlmInterval != tlmRateIn) {
667 receiver.modParams->tlmInterval = tlmRateIn;
668 telemBurstValid = false;
671 // modelId = 0xff indicates modelMatch is disabled, the XOR does nothing in that case
672 uint8_t modelXor = (~rxExpressLrsSpiConfig()->modelId) & ELRS_MODELMATCH_MASK;
673 bool modelMatched = packet[6] == (receiver.UID[5] ^ modelXor);
675 if (receiver.connectionState == ELRS_DISCONNECTED || receiver.nonceRX != packet[2] || FHSSgetCurrIndex() != packet[1] || connectionHasModelMatch != modelMatched) {
676 FHSSsetCurrIndex(packet[1]);
677 receiver.nonceRX = packet[2];
679 tentativeConnection(timeStampMs);
680 connectionHasModelMatch = modelMatched;
682 if (!expressLrsTimerIsRunning()) {
683 return true;
687 return false;
690 static rx_spi_received_e processRFPacket(uint8_t *payload, uint32_t timeStampUs)
692 uint8_t packet[ELRS_RX_TX_BUFF_SIZE];
694 receiver.receiveData(packet, ELRS_RX_TX_BUFF_SIZE);
696 elrsPacketType_e type = packet[0] & 0x03;
697 uint16_t inCRC = (((uint16_t)(packet[0] & 0xFC)) << 6 ) | packet[7];
699 // For SM_HYBRID the CRC only has the packet type in byte 0
700 // For SM_HYBRID_WIDE the FHSS slot is added to the CRC in byte 0 on RC_DATA_PACKETs
701 if (type != ELRS_RC_DATA_PACKET || rxExpressLrsSpiConfig()->switchMode != SM_HYBRID_WIDE) {
702 packet[0] = type;
703 } else {
704 uint8_t nonceFHSSresult = receiver.nonceRX % receiver.modParams->fhssHopInterval;
705 packet[0] = type | (nonceFHSSresult << 2);
707 uint16_t calculatedCRC = calcCrc14(packet, 7, crcInitializer);
709 if (inCRC != calculatedCRC) {
710 return RX_SPI_RECEIVED_NONE;
713 expressLrsEPRRecordEvent(EPR_EXTERNAL, timeStampUs + PACKET_HANDLING_TO_TOCK_ISR_DELAY_US);
715 bool shouldStartTimer = false;
716 uint32_t timeStampMs = millis();
718 receiver.lastValidPacketMs = timeStampMs;
720 switch(type) {
721 case ELRS_RC_DATA_PACKET:
722 // Must be fully connected to process RC packets, prevents processing RC
723 // during sync, where packets can be received before connection
724 if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
725 if (rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE) {
726 wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
727 if ((tlmRatioEnumToValue(receiver.modParams->tlmInterval) < 8) || wideSwitchIndex == 7) {
728 confirmCurrentTelemetryPayload((packet[6] & 0x40) >> 6);
730 } else {
731 confirmCurrentTelemetryPayload(packet[6] & (1 << 7));
733 memcpy(payload, &packet[1], 6); // stick data handling is done in expressLrsSetRcDataFromPayload
735 break;
736 case ELRS_MSP_DATA_PACKET:
737 processRFMspPacket(packet);
738 break;
739 case ELRS_TLM_PACKET:
740 //not implemented
741 break;
742 case ELRS_SYNC_PACKET:
743 shouldStartTimer = processRFSyncPacket(packet, timeStampMs) && !receiver.inBindingMode;
744 break;
745 default:
746 return RX_SPI_RECEIVED_NONE;
749 // Store the LQ/RSSI/Antenna
750 receiver.getRFlinkInfo(&receiver.rssi, &receiver.snr);
751 // Received a packet, that's the definition of LQ
752 lqIncrease();
753 // Extend sync duration since we've received a packet at this rate
754 // but do not extend it indefinitely
755 receiver.rfModeCycleMultiplier = ELRS_MODE_CYCLE_MULTIPLIER_SLOW; //RFModeCycleMultiplierSlow
757 if (shouldStartTimer) {
758 expressLrsTimerResume();
761 receiver.fhssRequired = true;
763 return RX_SPI_RECEIVED_DATA;
766 static void updateTelemetryBurst(void)
768 if (telemBurstValid) {
769 return;
771 telemBurstValid = true;
773 uint32_t hz = rateEnumToHz(receiver.modParams->enumRate);
774 uint32_t ratiodiv = tlmRatioEnumToValue(receiver.modParams->tlmInterval);
775 telemetryBurstMax = TELEM_MIN_LINK_INTERVAL * hz / ratiodiv / 1000U;
777 // Reserve one slot for LINK telemetry
778 if (telemetryBurstMax > 1) {
779 --telemetryBurstMax;
780 } else {
781 telemetryBurstMax = 1;
784 // Notify the sender to adjust its expected throughput
785 updateTelemetryRate(hz, ratiodiv, telemetryBurstMax);
788 /* If not connected will rotate through the RF modes looking for sync
789 * and blink LED
791 static void cycleRfMode(const uint32_t timeStampMs)
793 if (receiver.connectionState == ELRS_CONNECTED || receiver.inBindingMode) {
794 return;
796 // Actually cycle the RF mode if not LOCK_ON_FIRST_CONNECTION
797 if (receiver.lockRFmode == false && (timeStampMs - receiver.rfModeCycledAtMs) > (receiver.cycleIntervalMs * receiver.rfModeCycleMultiplier)) {
798 receiver.rfModeCycledAtMs = timeStampMs;
799 receiver.lastSyncPacketMs = timeStampMs; // reset this variable
800 receiver.rateIndex = (receiver.rateIndex + 1) % ELRS_RATE_MAX;
801 setRFLinkRate(receiver.rateIndex); // switch between rates
802 receiver.statsUpdatedAtMs = timeStampMs;
803 lqReset();
804 startReceiving();
806 // Switch to FAST_SYNC if not already in it (won't be if was just connected)
807 receiver.rfModeCycleMultiplier = 1;
808 } // if time to switch RF mode
811 #ifdef USE_RX_SX1280
812 static inline void configureReceiverForSX1280(void)
814 receiver.init = (elrsRxInitFnPtr) sx1280Init;
815 receiver.config = (elrsRxConfigFnPtr) sx1280Config;
816 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx1280StartReceiving;
817 receiver.rxISR = (elrsRxISRFnPtr) sx1280ISR;
818 receiver.transmitData = (elrsRxTransmitDataFnPtr) sx1280TransmitData;
819 receiver.receiveData = (elrsRxReceiveDataFnPtr) sx1280ReceiveData;
820 receiver.getRFlinkInfo = (elrsRxGetRFlinkInfoFnPtr) sx1280GetLastPacketStats;
821 receiver.setFrequency = (elrsRxSetFrequencyFnPtr) sx1280SetFrequencyReg;
822 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx1280AdjustFrequency;
824 #endif
826 #ifdef USE_RX_SX127X
827 static inline void configureReceiverForSX127x(void)
829 receiver.init = (elrsRxInitFnPtr) sx127xInit;
830 receiver.config = (elrsRxConfigFnPtr) sx127xConfig;
831 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx127xStartReceiving;
832 receiver.rxISR = (elrsRxISRFnPtr) sx127xISR;
833 receiver.transmitData = (elrsRxTransmitDataFnPtr) sx127xTransmitData;
834 receiver.receiveData = (elrsRxReceiveDataFnPtr) sx127xReceiveData;
835 receiver.getRFlinkInfo = (elrsRxGetRFlinkInfoFnPtr) sx127xGetLastPacketStats;
836 receiver.setFrequency = (elrsRxSetFrequencyFnPtr) sx127xSetFrequencyReg;
837 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx127xAdjustFrequency;
839 #endif
841 //setup
842 bool expressLrsSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState, rxSpiExtiConfig_t *extiConfig)
844 if (!rxSpiExtiConfigured()) {
845 return false;
848 rxSpiCommonIOInit(rxConfig);
850 rxRuntimeState->channelCount = ELRS_MAX_CHANNELS;
852 extiConfig->ioConfig = IOCFG_IPD;
853 extiConfig->trigger = BETAFLIGHT_EXTI_TRIGGER_RISING;
855 if (rxExpressLrsSpiConfig()->resetIoTag) {
856 receiver.resetPin = IOGetByTag(rxExpressLrsSpiConfig()->resetIoTag);
857 } else {
858 receiver.resetPin = IO_NONE;
861 if (rxExpressLrsSpiConfig()->busyIoTag) {
862 receiver.busyPin = IOGetByTag(rxExpressLrsSpiConfig()->busyIoTag);
863 } else {
864 receiver.busyPin = IO_NONE;
867 switch (rxExpressLrsSpiConfig()->domain) {
868 #ifdef USE_RX_SX127X
869 case AU433:
870 FALLTHROUGH;
871 case AU915:
872 FALLTHROUGH;
873 case EU433:
874 FALLTHROUGH;
875 case EU868:
876 FALLTHROUGH;
877 case IN866:
878 FALLTHROUGH;
879 case FCC915:
880 configureReceiverForSX127x();
881 bindingRateIndex = ELRS_BINDING_RATE_900;
882 break;
883 #endif
884 #ifdef USE_RX_SX1280
885 case ISM2400:
886 configureReceiverForSX1280();
887 bindingRateIndex = ELRS_BINDING_RATE_24;
888 break;
889 #endif
890 default:
891 return false;
894 if (!receiver.init(receiver.resetPin, receiver.busyPin)) {
895 return false;
898 if (rssiSource == RSSI_SOURCE_NONE) {
899 rssiSource = RSSI_SOURCE_RX_PROTOCOL;
902 if (linkQualitySource == LQ_SOURCE_NONE) {
903 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
906 if (rxExpressLrsSpiConfig()->UID[0] || rxExpressLrsSpiConfig()->UID[1]
907 || rxExpressLrsSpiConfig()->UID[2] || rxExpressLrsSpiConfig()->UID[3]
908 || rxExpressLrsSpiConfig()->UID[4] || rxExpressLrsSpiConfig()->UID[5]) {
909 receiver.inBindingMode = false;
910 receiver.UID = rxExpressLrsSpiConfig()->UID;
911 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
912 } else {
913 receiver.inBindingMode = true;
914 receiver.UID = BindingUID;
915 crcInitializer = 0;
918 expressLrsPhaseLockReset();
920 expressLrsInitialiseTimer(RX_EXPRESSLRS_TIMER_INSTANCE, &receiver.timerUpdateCb);
921 expressLrsTimerStop();
923 generateCrc14Table();
924 initializeReceiver();
926 initTelemetry();
927 #ifdef USE_MSP_OVER_TELEMETRY
928 setMspDataToReceive(ELRS_MSP_BUFFER_SIZE, mspBuffer, ELRS_MSP_BYTES_PER_CALL);
929 #endif
931 // Timer IRQs must only be enabled after the receiver is configured otherwise race conditions occur.
932 expressLrsTimerEnableIRQs();
934 return true;
937 static void handleConnectionStateUpdate(const uint32_t timeStampMs)
939 if ((receiver.connectionState != ELRS_DISCONNECTED) && (receiver.modParams->index != receiver.nextRateIndex)) { // forced change
940 lostConnection();
941 receiver.lastSyncPacketMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
942 receiver.rfModeCycledAtMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
943 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
944 #ifdef USE_RX_RSSI_DBM
945 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
946 #endif
947 #ifdef USE_RX_LINK_QUALITY_INFO
948 setLinkQualityDirect(0);
949 #endif
952 if (receiver.connectionState == ELRS_TENTATIVE && ((timeStampMs - receiver.lastSyncPacketMs) > receiver.rfPerfParams->rxLockTimeoutMs)) {
953 lostConnection();
954 receiver.rfModeCycledAtMs = timeStampMs;
955 receiver.lastSyncPacketMs = timeStampMs;
958 cycleRfMode(timeStampMs);
960 uint32_t localLastValidPacket = receiver.lastValidPacketMs; // Required to prevent race condition due to LastValidPacket getting updated from ISR
961 if ((receiver.connectionState == ELRS_DISCONNECT_PENDING) || // check if we lost conn.
962 ((receiver.connectionState == ELRS_CONNECTED) && (receiver.rfPerfParams->disconnectTimeoutMs < (timeStampMs - localLastValidPacket)))) {
963 lostConnection();
966 if ((receiver.connectionState == ELRS_TENTATIVE) && (ABS(pl.offsetDeltaUs) <= 10) && (pl.offsetUs < 100) && (lqGet() > minLqForChaos())) {
967 gotConnection(timeStampMs); // detects when we are connected
970 if ((receiver.timerState == ELRS_TIM_TENTATIVE) && ((timeStampMs - receiver.gotConnectionMs) > ELRS_CONSIDER_CONNECTION_GOOD_MS) && (ABS(pl.offsetDeltaUs) <= 5)) {
971 receiver.timerState = ELRS_TIM_LOCKED;
974 if ((receiver.connectionState == ELRS_CONNECTED) && (ABS(pl.offsetDeltaUs) > 10) && (pl.offsetUs >= 100) && (lqGet() <= minLqForChaos())) {
975 lostConnection(); // SPI: resync when we're in chaos territory
979 static void handleConfigUpdate(const uint32_t timeStampMs)
981 if ((timeStampMs - receiver.configCheckedAtMs) > ELRS_CONFIG_CHECK_MS) {
982 receiver.configCheckedAtMs = timeStampMs;
983 if (receiver.configChanged) {
984 writeEEPROM();
985 receiver.configChanged = false;
990 static void handleLinkStatsUpdate(const uint32_t timeStampMs)
992 if ((timeStampMs - receiver.statsUpdatedAtMs) > ELRS_LINK_STATS_CHECK_MS) {
994 receiver.statsUpdatedAtMs = timeStampMs;
996 if (receiver.connectionState == ELRS_CONNECTED) {
997 receiver.rssiFiltered = simpleLPFilterUpdate(&rssiFilter, receiver.rssi);
998 uint16_t rssiScaled = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 0, 1023);
999 setRssi(rssiScaled, RSSI_SOURCE_RX_PROTOCOL);
1000 #ifdef USE_RX_RSSI_DBM
1001 setRssiDbm(receiver.rssiFiltered, RSSI_SOURCE_RX_PROTOCOL);
1002 #endif
1003 #ifdef USE_RX_LINK_QUALITY_INFO
1004 setLinkQualityDirect(receiver.uplinkLQ);
1005 #endif
1006 #ifdef USE_RX_LINK_UPLINK_POWER
1007 rxSetUplinkTxPwrMw(txPowerIndexToValue(txPower));
1008 #endif
1009 } else {
1010 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
1011 #ifdef USE_RX_RSSI_DBM
1012 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
1013 #endif
1014 #ifdef USE_RX_LINK_QUALITY_INFO
1015 setLinkQualityDirect(0);
1016 #endif
1021 static void handleTelemetryUpdate(void)
1023 if (receiver.connectionState != ELRS_CONNECTED || (receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM)) {
1024 return;
1027 uint8_t *nextPayload = 0;
1028 uint8_t nextPlayloadSize = 0;
1029 if (!isTelemetrySenderActive() && getNextTelemetryPayload(&nextPlayloadSize, &nextPayload)) {
1030 setTelemetryDataToTransmit(nextPlayloadSize, nextPayload, ELRS_TELEMETRY_BYTES_PER_CALL);
1032 updateTelemetryBurst();
1035 void expressLrsSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
1037 if (rcData && payload) {
1038 rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE ? unpackChannelDataHybridWide(rcData, payload) : unpackChannelDataHybridSwitch8(rcData, payload);
1042 static void enterBindingMode(void)
1044 if ((receiver.connectionState == ELRS_CONNECTED) || receiver.inBindingMode) {
1045 // Don't enter binding if:
1046 // - we're already connected
1047 // - we're already binding
1048 return;
1051 // Set UID to special binding values
1052 receiver.UID = BindingUID;
1053 crcInitializer = 0;
1054 receiver.inBindingMode = true;
1056 setRFLinkRate(bindingRateIndex);
1057 startReceiving();
1060 static uint32_t isrTimeStampUs;
1062 rx_spi_received_e expressLrsDataReceived(uint8_t *payload)
1064 rx_spi_received_e result = RX_SPI_RECEIVED_NONE;
1066 if (!receiver.started && (systemState & SYSTEM_STATE_READY)) {
1067 receiver.started = true;
1068 startReceiving(); // delay receiving after initialization to ensure a clean connect
1071 if (rxSpiCheckBindRequested(true)) {
1072 enterBindingMode();
1075 uint8_t irqReason = receiver.rxISR(&isrTimeStampUs);
1076 if (irqReason == ELRS_DIO_TX_DONE) {
1077 startReceiving();
1078 } else if (irqReason == ELRS_DIO_RX_DONE) {
1079 result = processRFPacket(payload, isrTimeStampUs);
1082 if (receiver.fhssRequired) {
1083 receiver.fhssRequired = false;
1084 bool didFHSS = false;
1085 bool tlmReq = false;
1086 ATOMIC_BLOCK(NVIC_PRIO_TIMER) { // prevent from updating nonce in TICK
1087 didFHSS = handleFHSS();
1088 tlmReq = shouldSendTelemetryResponse();
1091 if (tlmReq) {
1092 // in case we miss a packet before TLM we still need to estimate processing time using %
1093 uint32_t processingTime = (micros() - isrTimeStampUs) % receiver.modParams->interval;
1094 if (processingTime < PACKET_HANDLING_TO_TOCK_ISR_DELAY_US && receiver.timerState == ELRS_TIM_LOCKED) {
1095 handleSendTelemetryResponse();
1096 } else {
1097 receiver.alreadyTLMresp = true;
1098 startReceiving();
1102 if (rxExpressLrsSpiConfig()->domain != ISM2400 && !didFHSS && !tlmReq && lqPeriodIsSet()) {
1103 receiver.handleFreqCorrection(receiver.freqOffset, receiver.currentFreq); //corrects for RX freq offset
1107 handleTelemetryUpdate();
1109 const uint32_t timeStampMs = millis();
1111 handleConnectionStateUpdate(timeStampMs);
1112 handleConfigUpdate(timeStampMs);
1113 handleLinkStatsUpdate(timeStampMs);
1115 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 0, lostConnectionCounter);
1116 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 1, receiver.rssiFiltered);
1117 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 2, receiver.snr);
1118 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 3, receiver.uplinkLQ);
1120 receiver.inBindingMode ? rxSpiLedBlinkBind() : rxSpiLedBlinkRxLoss(result);
1122 return result;
1125 void expressLrsStop(void)
1127 if (receiver.started) {
1128 lostConnection();
1132 #endif /* USE_RX_EXPRESSLRS */