Updated and Validated
[betaflight.git] / src / main / rx / expresslrs.c
blob93815353e64aa35b461b41ec3cc5f5a938351331
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 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 volatile DMA_DATA uint8_t dmaBuffer[ELRS_RX_TX_BUFF_SIZE];
83 static volatile DMA_DATA uint8_t telemetryPacket[ELRS_RX_TX_BUFF_SIZE];
84 static volatile rx_spi_received_e rfPacketStatus = RX_SPI_RECEIVED_NONE;
85 static volatile uint8_t *payload;
87 static void rssiFilterReset(void)
89 simpleLPFilterInit(&rssiFilter, 2, 5);
92 #define PACKET_HANDLING_TO_TOCK_ISR_DELAY_US 250
95 // Event pair recorder
98 typedef enum {
99 EPR_FIRST,
100 EPR_SECOND,
101 } eprEvent_e;
103 #define EPR_EVENT_COUNT 2
105 typedef struct eprState_s {
106 uint32_t eventAtUs[EPR_EVENT_COUNT];
107 bool eventRecorded[EPR_EVENT_COUNT];
108 } eprState_t;
110 eprState_t eprState = {
111 .eventAtUs = {0},
112 .eventRecorded = {0},
115 static void phaseLockEprEvent(eprEvent_e event, uint32_t currentTimeUs)
117 eprState.eventAtUs[event] = currentTimeUs;
118 eprState.eventRecorded[event] = true;
121 static bool phaseLockEprHaveBothEvents(void)
123 bool bothEventsRecorded = eprState.eventRecorded[EPR_SECOND] && eprState.eventRecorded[EPR_FIRST];
124 return bothEventsRecorded;
127 static int32_t phaseLockEprResult(void)
129 if (!phaseLockEprHaveBothEvents()) {
130 return 0;
133 return (int32_t)(eprState.eventAtUs[EPR_SECOND] - eprState.eventAtUs[EPR_FIRST]);
136 static void phaseLockEprReset(void)
138 memset(&eprState, 0, sizeof(eprState_t));
143 // Phase Lock
147 #define EPR_INTERNAL EPR_FIRST
148 #define EPR_EXTERNAL EPR_SECOND
150 typedef struct phaseLockState_s {
151 simpleLowpassFilter_t offsetFilter;
152 simpleLowpassFilter_t offsetDxFilter;
154 int32_t rawOffsetUs;
155 int32_t previousRawOffsetUs;
157 int32_t offsetUs;
158 int32_t offsetDeltaUs;
159 int32_t previousOffsetUs;
160 } phaseLockState_t;
162 static phaseLockState_t pl;
164 static void expressLrsPhaseLockReset(void)
166 simpleLPFilterInit(&pl.offsetFilter, 2, 5);
167 simpleLPFilterInit(&pl.offsetDxFilter, 4, 5);
169 phaseLockEprReset();
172 static uint8_t nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
174 static uint8_t telemetryBurstCount = 1;
175 static uint8_t telemetryBurstMax = 1;
176 static bool telemBurstValid = false;
178 // Maximum ms between LINK_STATISTICS packets for determining burst max
179 #define TELEM_MIN_LINK_INTERVAL 512U
181 #ifdef USE_MSP_OVER_TELEMETRY
182 static uint8_t mspBuffer[ELRS_MSP_BUFFER_SIZE];
183 #endif
186 // Stick unpacking
189 static void setRssiChannelData(uint16_t *rcData)
191 rcData[ELRS_LQ_CHANNEL] = scaleRange(receiver.uplinkLQ, 0, 100, 988, 2011);
192 rcData[ELRS_RSSI_CHANNEL] = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 988, 2011);
195 static void unpackAnalogChannelData(uint16_t *rcData, const uint8_t *payload)
197 rcData[0] = convertAnalog((payload[0] << 3) | ((payload[4] & 0xC0) >> 5));
198 rcData[1] = convertAnalog((payload[1] << 3) | ((payload[4] & 0x30) >> 3));
199 rcData[2] = convertAnalog((payload[2] << 3) | ((payload[4] & 0x0C) >> 1));
200 rcData[3] = convertAnalog((payload[3] << 3) | ((payload[4] & 0x03) << 1));
204 * Hybrid switches uses 10 bits for each analog channel,
205 * 2 bits for the low latency switch[0]
206 * 3 bits for the round-robin switch index and 2 bits for the value
207 * 4 analog channels, 1 low latency switch and round robin switch data = 47 bits (1 free)
209 * sets telemetry status bit
211 static void unpackChannelDataHybridSwitch8(uint16_t *rcData, const uint8_t *payload)
213 unpackAnalogChannelData(rcData, payload);
215 const uint8_t switchByte = payload[5];
217 // The low latency switch
218 rcData[4] = convertSwitch1b((switchByte & 0x40) >> 6);
220 // The round-robin switch, switchIndex is actually index-1
221 // to leave the low bit open for switch 7 (sent as 0b11x)
222 // where x is the high bit of switch 7
223 uint8_t switchIndex = (switchByte & 0x38) >> 3;
224 uint16_t switchValue = convertSwitch3b(switchByte & 0x07);
226 switch (switchIndex) {
227 case 0:
228 rcData[5] = switchValue;
229 break;
230 case 1:
231 rcData[6] = switchValue;
232 break;
233 case 2:
234 rcData[7] = switchValue;
235 break;
236 case 3:
237 rcData[8] = switchValue;
238 break;
239 case 4:
240 rcData[9] = switchValue;
241 break;
242 case 5:
243 rcData[10] = switchValue;
244 break;
245 case 6:
246 FALLTHROUGH;
247 case 7:
248 rcData[11] = convertSwitchNb(switchByte & 0x0F, 15); //4-bit
249 break;
250 default:
251 break;
254 setRssiChannelData(rcData);
258 * HybridWide switches decoding of over the air data
260 * Hybrid switches uses 10 bits for each analog channel,
261 * 1 bits for the low latency switch[0]
262 * 6 or 7 bits for the round-robin switch
263 * 1 bit for the TelemetryStatus, which may be in every packet or just idx 7
264 * depending on TelemetryRatio
266 * Output: crsf.PackedRCdataOut, crsf.LinkStatistics.uplink_TX_Power
267 * Returns: TelemetryStatus bit
269 static void unpackChannelDataHybridWide(uint16_t *rcData, const uint8_t *payload)
271 unpackAnalogChannelData(rcData, payload);
272 const uint8_t switchByte = payload[5];
274 // The low latency switch
275 rcData[4] = convertSwitch1b((switchByte & 0x80) >> 7);
277 // The round-robin switch, 6-7 bits with the switch index implied by the nonce. Some logic moved to processRFPacket
278 if (wideSwitchIndex >= 7) {
279 txPower = switchByte & 0x3F;
280 } else {
281 uint8_t bins;
282 uint16_t switchValue;
283 if (tlmRatioEnumToValue(receiver.modParams->tlmInterval) < 8) {
284 bins = 63;
285 switchValue = switchByte & 0x3F; // 6-bit
286 } else {
287 bins = 127;
288 switchValue = switchByte & 0x7F; // 7-bit
291 switchValue = convertSwitchNb(switchValue, bins);
292 rcData[5 + wideSwitchIndex] = switchValue;
295 setRssiChannelData(rcData);
298 static uint8_t minLqForChaos(void)
300 // Determine the most number of CRC-passing packets we could receive on
301 // a single channel out of 100 packets that fill the LQcalc span.
302 // The LQ must be GREATER THAN this value, not >=
303 // The amount of time we coexist on the same channel is
304 // 100 divided by the total number of packets in a FHSS loop (rounded up)
305 // and there would be 4x packets received each time it passes by so
306 // FHSShopInterval * ceil(100 / FHSShopInterval * numfhss) or
307 // FHSShopInterval * trunc((100 + (FHSShopInterval * numfhss) - 1) / (FHSShopInterval * numfhss))
308 // With a interval of 4 this works out to: 2.4=4, FCC915=4, AU915=8, EU868=8, EU/AU433=36
309 const uint32_t numfhss = fhssGetNumEntries();
310 const uint8_t interval = receiver.modParams->fhssHopInterval;
311 return interval * ((interval * numfhss + 99) / (interval * numfhss));
314 static void setRfLinkRate(const uint8_t index)
316 #if defined(USE_RX_SX1280) && defined(USE_RX_SX127X)
317 receiver.modParams = (rxExpressLrsSpiConfig()->domain == ISM2400) ? &airRateConfig[1][index] : &airRateConfig[0][index];
318 receiver.rfPerfParams = (rxExpressLrsSpiConfig()->domain == ISM2400) ? &rfPerfConfig[1][index] : &rfPerfConfig[0][index];
319 #else
320 receiver.modParams = &airRateConfig[0][index];
321 receiver.rfPerfParams = &rfPerfConfig[0][index];
322 #endif
323 receiver.currentFreq = fhssGetInitialFreq(receiver.freqOffset);
324 // Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
325 receiver.cycleIntervalMs = ((uint32_t)11U * fhssGetNumEntries() * receiver.modParams->fhssHopInterval * receiver.modParams->interval) / (10U * 1000U);
327 receiver.config(receiver.modParams->bw, receiver.modParams->sf, receiver.modParams->cr, receiver.currentFreq, receiver.modParams->preambleLen, receiver.UID[5] & 0x01);
329 expressLrsUpdateTimerInterval(receiver.modParams->interval);
331 rssiFilterReset();
332 receiver.nextRateIndex = index; // presumably we just handled this
333 telemBurstValid = false;
335 #ifdef USE_RX_LINK_QUALITY_INFO
336 rxSetRfMode((uint8_t)RATE_4HZ - (uint8_t)receiver.modParams->enumRate);
337 #endif
340 uint32_t expressLrsGetCurrentFreq(void)
342 return receiver.currentFreq;
345 void expressLrsSetRfPacketStatus(rx_spi_received_e status)
347 rfPacketStatus = status;
350 volatile uint8_t *expressLrsGetRxBuffer(void) {
351 return dmaBuffer;
354 volatile uint8_t *expressLrsGetTelemetryBuffer(void)
356 return telemetryPacket;
359 volatile uint8_t *expressLrsGetPayloadBuffer(void)
361 return payload;
364 bool expressLrsIsFhssReq(void)
366 uint8_t modresultFHSS = (receiver.nonceRX + 1) % receiver.modParams->fhssHopInterval;
368 if ((receiver.modParams->fhssHopInterval == 0) || receiver.alreadyFhss == true || receiver.inBindingMode || (modresultFHSS != 0) || (receiver.connectionState == ELRS_DISCONNECTED)) {
369 return false;
372 receiver.alreadyFhss = true;
373 receiver.currentFreq = fhssGetNextFreq(receiver.freqOffset);
375 return true;
378 bool expressLrsTelemRespReq(void)
380 uint8_t modresult = (receiver.nonceRX + 1) % tlmRatioEnumToValue(receiver.modParams->tlmInterval);
381 if (receiver.inBindingMode || (receiver.connectionState == ELRS_DISCONNECTED) || (receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM) || (modresult != 0)) {
382 return false; // don't bother sending tlm if disconnected or TLM is off
383 } else {
384 return true;
388 static void expressLrsSendTelemResp(void)
390 uint8_t *data;
391 uint8_t maxLength;
392 uint8_t packageIndex;
394 receiver.alreadyTelemResp = true;
395 telemetryPacket[0] = ELRS_TLM_PACKET;
397 if (nextTelemetryType == ELRS_TELEMETRY_TYPE_LINK || !isTelemetrySenderActive()) {
398 telemetryPacket[1] = ELRS_TELEMETRY_TYPE_LINK;
399 telemetryPacket[2] = receiver.rssiFiltered > 0 ? 0 : -receiver.rssiFiltered; //diversity not supported
400 telemetryPacket[3] = connectionHasModelMatch << 7;
401 telemetryPacket[4] = receiver.snr;
402 telemetryPacket[5] = receiver.uplinkLQ;
403 #ifdef USE_MSP_OVER_TELEMETRY
404 telemetryPacket[6] = getCurrentMspConfirm() ? 1 : 0;
405 #else
406 telemetryPacket[6] = 0;
407 #endif
408 nextTelemetryType = ELRS_TELEMETRY_TYPE_DATA;
409 // Start the count at 1 because the next will be DATA and doing +1 before checking
410 // against Max below is for some reason 10 bytes more code
411 telemetryBurstCount = 1;
412 } else {
413 if (telemetryBurstCount < telemetryBurstMax) {
414 telemetryBurstCount++;
415 } else {
416 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
419 getCurrentTelemetryPayload(&packageIndex, &maxLength, &data);
420 telemetryPacket[1] = (packageIndex << ELRS_TELEMETRY_SHIFT) + ELRS_TELEMETRY_TYPE_DATA;
421 telemetryPacket[2] = maxLength > 0 ? *data : 0;
422 telemetryPacket[3] = maxLength >= 1 ? *(data + 1) : 0;
423 telemetryPacket[4] = maxLength >= 2 ? *(data + 2) : 0;
424 telemetryPacket[5] = maxLength >= 3 ? *(data + 3) : 0;
425 telemetryPacket[6] = maxLength >= 4 ? *(data + 4) : 0;
428 uint16_t crc = calcCrc14((uint8_t *)telemetryPacket, 7, crcInitializer);
429 telemetryPacket[0] |= (crc >> 6) & 0xFC;
430 telemetryPacket[7] = crc & 0xFF;
433 static void updatePhaseLock(void)
435 if (receiver.connectionState != ELRS_DISCONNECTED && phaseLockEprHaveBothEvents()) {
436 int32_t maxOffset = receiver.modParams->interval / 4;
437 pl.rawOffsetUs = constrain(phaseLockEprResult(), -maxOffset, maxOffset);
439 pl.offsetUs = simpleLPFilterUpdate(&pl.offsetFilter, pl.rawOffsetUs);
440 pl.offsetDeltaUs = simpleLPFilterUpdate(&pl.offsetDxFilter, pl.rawOffsetUs - pl.previousRawOffsetUs);
442 if (receiver.timerState == ELRS_TIM_LOCKED && lqPeriodIsSet()) {
443 if (receiver.nonceRX % 8 == 0) { //limit rate of freq offset adjustment slightly
444 if (pl.offsetUs > 0) {
445 expressLrsTimerIncreaseFrequencyOffset();
446 } else if (pl.offsetUs < 0) {
447 expressLrsTimerDecreaseFrequencyOffset();
452 if (receiver.connectionState != ELRS_CONNECTED) {
453 expressLrsUpdatePhaseShift(pl.rawOffsetUs >> 1);
454 } else {
455 expressLrsUpdatePhaseShift(pl.offsetUs >> 2);
458 pl.previousOffsetUs = pl.offsetUs;
459 pl.previousRawOffsetUs = pl.rawOffsetUs;
461 expressLrsTimerDebug();
463 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 0, pl.rawOffsetUs);
464 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK, 1, pl.offsetUs);
467 phaseLockEprReset();
470 //hwTimerCallbackTick
471 void expressLrsOnTimerTickISR(void) // this is 180 out of phase with the other callback, occurs mid-packet reception
473 updatePhaseLock();
474 receiver.nonceRX += 1;
476 // Save the LQ value before the inc() reduces it by 1
477 receiver.uplinkLQ = lqGet();
478 // Only advance the LQI period counter if we didn't send Telemetry this period
479 if (!receiver.alreadyTelemResp) {
480 lqNewPeriod();
483 receiver.alreadyTelemResp = false;
484 receiver.alreadyFhss = false;
486 receiver.rxHandleFromTick();
489 //hwTimerCallbackTock
490 void expressLrsOnTimerTockISR(void)
492 uint32_t currentTimeUs = micros();
494 phaseLockEprEvent(EPR_INTERNAL, currentTimeUs);
496 receiver.rxHandleFromTock();
499 static uint16_t lostConnectionCounter = 0;
501 void lostConnection(void)
503 lostConnectionCounter++;
505 receiver.rfModeCycleMultiplier = 1;
506 receiver.connectionState = ELRS_DISCONNECTED; //set lost connection
507 receiver.timerState = ELRS_TIM_DISCONNECTED;
508 expressLrsTimerResetFrequencyOffset();
509 receiver.freqOffset = 0;
510 pl.offsetUs = 0;
511 pl.offsetDeltaUs = 0;
512 pl.rawOffsetUs = 0;
513 pl.previousRawOffsetUs = 0;
514 receiver.gotConnectionMs = 0;
515 receiver.uplinkLQ = 0;
516 lqReset();
517 expressLrsPhaseLockReset();
518 receiver.alreadyTelemResp = false;
519 receiver.alreadyFhss = false;
521 if (!receiver.inBindingMode) {
522 expressLrsTimerStop();
523 setRfLinkRate(receiver.nextRateIndex); // also sets to initialFreq
524 receiver.startReceiving();
528 static void tentativeConnection(const uint32_t timeStampMs)
530 receiver.connectionState = ELRS_TENTATIVE;
531 connectionHasModelMatch = false;
532 receiver.timerState = ELRS_TIM_DISCONNECTED;
533 receiver.freqOffset = 0;
534 pl.offsetUs = 0;
535 pl.previousRawOffsetUs = 0;
536 expressLrsPhaseLockReset(); //also resets PFD
537 receiver.rfModeCycledAtMs = timeStampMs; // give another 3 sec for lock to occur
539 // The caller MUST call hwTimer.resume(). It is not done here because
540 // the timer ISR will fire immediately and preempt any other code
543 static void gotConnection(const uint32_t timeStampMs)
545 if (receiver.connectionState == ELRS_CONNECTED) {
546 return; // Already connected
549 receiver.lockRFmode = true; // currently works as if LOCK_ON_FIRST_CONNECTION was enabled
551 receiver.connectionState = ELRS_CONNECTED; //we got a packet, therefore no lost connection
552 receiver.timerState = ELRS_TIM_TENTATIVE;
553 receiver.gotConnectionMs = timeStampMs;
555 if (rxExpressLrsSpiConfig()->rateIndex != receiver.rateIndex) {
556 rxExpressLrsSpiConfigMutable()->rateIndex = receiver.rateIndex;
557 receiver.configChanged = true;
561 //setup radio
562 static void initializeReceiver(void)
564 fhssGenSequence(receiver.UID, rxExpressLrsSpiConfig()->domain);
565 lqReset();
566 receiver.nonceRX = 0;
567 receiver.freqOffset = 0;
568 receiver.configChanged = false;
569 receiver.rssi = 0;
570 receiver.rssiFiltered = 0;
571 receiver.snr = 0;
572 receiver.uplinkLQ = 0;
573 receiver.rateIndex = receiver.inBindingMode ? bindingRateIndex : rxExpressLrsSpiConfig()->rateIndex;
574 setRfLinkRate(receiver.rateIndex);
576 receiver.started = false;
577 receiver.alreadyFhss = false;
578 receiver.alreadyTelemResp = false;
579 receiver.lockRFmode = false;
580 receiver.timerState = ELRS_TIM_DISCONNECTED;
581 receiver.connectionState = ELRS_DISCONNECTED;
583 uint32_t timeStampMs = millis();
585 receiver.rfModeCycledAtMs = timeStampMs;
586 receiver.configCheckedAtMs = timeStampMs;
587 receiver.statsUpdatedAtMs = timeStampMs;
588 receiver.gotConnectionMs = timeStampMs;
589 receiver.lastSyncPacketMs = timeStampMs;
590 receiver.lastValidPacketMs = timeStampMs;
592 receiver.rfModeCycleMultiplier = 1;
595 static void unpackBindPacket(volatile uint8_t *packet)
597 rxExpressLrsSpiConfigMutable()->UID[2] = packet[3];
598 rxExpressLrsSpiConfigMutable()->UID[3] = packet[4];
599 rxExpressLrsSpiConfigMutable()->UID[4] = packet[5];
600 rxExpressLrsSpiConfigMutable()->UID[5] = packet[6];
602 receiver.UID = rxExpressLrsSpiConfigMutable()->UID;
603 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
604 receiver.inBindingMode = false;
605 receiver.configChanged = true; //after initialize as it sets it to false
609 * Process the assembled MSP packet in mspBuffer[]
611 static void processRFMspPacket(volatile uint8_t *packet)
613 // Always examine MSP packets for bind information if in bind mode
614 // [1] is the package index, first packet of the MSP
615 if (receiver.inBindingMode && packet[1] == 1 && packet[2] == ELRS_MSP_BIND) {
616 unpackBindPacket(packet); //onELRSBindMSP
617 return;
620 #ifdef USE_MSP_OVER_TELEMETRY
621 // Must be fully connected to process MSP, prevents processing MSP
622 // during sync, where packets can be received before connection
623 if (receiver.connectionState != ELRS_CONNECTED) {
624 return;
627 bool currentMspConfirmValue = getCurrentMspConfirm();
628 receiveMspData(packet[1], packet + 2);
629 if (currentMspConfirmValue != getCurrentMspConfirm()) {
630 nextTelemetryType = ELRS_TELEMETRY_TYPE_LINK;
632 if (hasFinishedMspData()) {
633 if (mspBuffer[ELRS_MSP_COMMAND_INDEX] == ELRS_MSP_SET_RX_CONFIG && mspBuffer[ELRS_MSP_COMMAND_INDEX + 1] == ELRS_MSP_MODEL_ID) { //mspReceiverComplete
634 if (rxExpressLrsSpiConfig()->modelId != mspBuffer[9]) { //UpdateModelMatch
635 rxExpressLrsSpiConfigMutable()->modelId = mspBuffer[9];
636 receiver.configChanged = true;
637 receiver.connectionState = ELRS_DISCONNECT_PENDING;
639 } else if (connectionHasModelMatch) {
640 processMspPacket(mspBuffer);
643 mspReceiverUnlock();
645 #endif
648 static bool processRFSyncPacket(volatile uint8_t *packet, const uint32_t timeStampMs)
650 // Verify the first two of three bytes of the binding ID, which should always match
651 if (packet[4] != receiver.UID[3] || packet[5] != receiver.UID[4]) {
652 return false;
655 // The third byte will be XORed with inverse of the ModelId if ModelMatch is on
656 // Only require the first 18 bits of the UID to match to establish a connection
657 // but the last 6 bits must modelmatch before sending any data to the FC
658 if ((packet[6] & ~ELRS_MODELMATCH_MASK) != (receiver.UID[5] & ~ELRS_MODELMATCH_MASK)) {
659 return false;
662 receiver.lastSyncPacketMs = timeStampMs;
664 // Will change the packet air rate in loop() if this changes
665 receiver.nextRateIndex = (packet[3] & 0xC0) >> 6;
666 uint8_t tlmRateIn = (packet[3] & 0x38) >> 3;
667 uint8_t switchEncMode = ((packet[3] & 0x06) >> 1) - 1; //spi implementation uses 0 based index for hybrid
669 // Update switch mode encoding immediately
670 if (switchEncMode != rxExpressLrsSpiConfig()->switchMode) {
671 rxExpressLrsSpiConfigMutable()->switchMode = switchEncMode;
672 receiver.configChanged = true;
675 // Update TLM ratio
676 if (receiver.modParams->tlmInterval != tlmRateIn) {
677 receiver.modParams->tlmInterval = tlmRateIn;
678 telemBurstValid = false;
681 // modelId = 0xff indicates modelMatch is disabled, the XOR does nothing in that case
682 uint8_t modelXor = (~rxExpressLrsSpiConfig()->modelId) & ELRS_MODELMATCH_MASK;
683 bool modelMatched = packet[6] == (receiver.UID[5] ^ modelXor);
685 if (receiver.connectionState == ELRS_DISCONNECTED || receiver.nonceRX != packet[2] || fhssGetCurrIndex() != packet[1] || connectionHasModelMatch != modelMatched) {
686 fhssSetCurrIndex(packet[1]);
687 receiver.nonceRX = packet[2];
689 tentativeConnection(timeStampMs);
690 connectionHasModelMatch = modelMatched;
692 if (!expressLrsTimerIsRunning()) {
693 return true;
697 return false;
700 rx_spi_received_e processRFPacket(volatile uint8_t *payload, uint32_t timeStampUs)
702 elrsPacketType_e type = dmaBuffer[0] & 0x03;
703 uint16_t inCRC = (((uint16_t)(dmaBuffer[0] & 0xFC)) << 6 ) | dmaBuffer[7];
705 // For SM_HYBRID the CRC only has the packet type in byte 0
706 // For SM_HYBRID_WIDE the FHSS slot is added to the CRC in byte 0 on RC_DATA_PACKETs
707 if (type != ELRS_RC_DATA_PACKET || rxExpressLrsSpiConfig()->switchMode != SM_HYBRID_WIDE) {
708 dmaBuffer[0] = type;
709 } else {
710 uint8_t nonceFHSSresult = receiver.nonceRX % receiver.modParams->fhssHopInterval;
711 dmaBuffer[0] = type | (nonceFHSSresult << 2);
713 uint16_t calculatedCRC = calcCrc14((uint8_t *)dmaBuffer, 7, crcInitializer);
715 if (inCRC != calculatedCRC) {
716 return RX_SPI_RECEIVED_NONE;
719 phaseLockEprEvent(EPR_EXTERNAL, timeStampUs + PACKET_HANDLING_TO_TOCK_ISR_DELAY_US);
721 bool shouldStartTimer = false;
722 uint32_t timeStampMs = millis();
724 receiver.lastValidPacketMs = timeStampMs;
726 switch(type) {
727 case ELRS_RC_DATA_PACKET:
728 // Must be fully connected to process RC packets, prevents processing RC
729 // during sync, where packets can be received before connection
730 if (receiver.connectionState == ELRS_CONNECTED && connectionHasModelMatch) {
731 if (rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE) {
732 wideSwitchIndex = hybridWideNonceToSwitchIndex(receiver.nonceRX);
733 if ((tlmRatioEnumToValue(receiver.modParams->tlmInterval) < 8) || wideSwitchIndex == 7) {
734 confirmCurrentTelemetryPayload((dmaBuffer[6] & 0x40) >> 6);
736 } else {
737 confirmCurrentTelemetryPayload(dmaBuffer[6] & (1 << 7));
739 memcpy((uint8_t *)payload, (uint8_t *)&dmaBuffer[1], 6); // stick data handling is done in expressLrsSetRcDataFromPayload
741 break;
742 case ELRS_MSP_DATA_PACKET:
743 processRFMspPacket(dmaBuffer);
744 break;
745 case ELRS_TLM_PACKET:
746 //not implemented
747 break;
748 case ELRS_SYNC_PACKET:
749 shouldStartTimer = processRFSyncPacket(dmaBuffer, timeStampMs) && !receiver.inBindingMode;
750 break;
751 default:
752 return RX_SPI_RECEIVED_NONE;
755 // Store the LQ/RSSI/Antenna
756 receiver.getRfLinkInfo(&receiver.rssi, &receiver.snr);
757 // Received a packet, that's the definition of LQ
758 lqIncrease();
760 // Extend sync duration since we've received a packet at this rate
761 // but do not extend it indefinitely
762 receiver.rfModeCycleMultiplier = ELRS_MODE_CYCLE_MULTIPLIER_SLOW; //RFModeCycleMultiplierSlow
764 if (shouldStartTimer) {
765 expressLrsTimerResume();
768 return RX_SPI_RECEIVED_DATA;
771 static void updateTelemetryBurst(void)
773 if (telemBurstValid) {
774 return;
776 telemBurstValid = true;
778 uint32_t hz = rateEnumToHz(receiver.modParams->enumRate);
779 uint32_t ratiodiv = tlmRatioEnumToValue(receiver.modParams->tlmInterval);
780 telemetryBurstMax = TELEM_MIN_LINK_INTERVAL * hz / ratiodiv / 1000U;
782 // Reserve one slot for LINK telemetry
783 if (telemetryBurstMax > 1) {
784 --telemetryBurstMax;
785 } else {
786 telemetryBurstMax = 1;
789 // Notify the sender to adjust its expected throughput
790 updateTelemetryRate(hz, ratiodiv, telemetryBurstMax);
793 /* If not connected will rotate through the RF modes looking for sync
794 * and blink LED
796 static void cycleRfMode(const uint32_t timeStampMs)
798 if (receiver.connectionState == ELRS_CONNECTED || receiver.inBindingMode) {
799 return;
801 // Actually cycle the RF mode if not LOCK_ON_FIRST_CONNECTION
802 if (receiver.lockRFmode == false && (timeStampMs - receiver.rfModeCycledAtMs) > (receiver.cycleIntervalMs * receiver.rfModeCycleMultiplier)) {
803 receiver.rfModeCycledAtMs = timeStampMs;
804 receiver.lastSyncPacketMs = timeStampMs; // reset this variable
805 receiver.rateIndex = (receiver.rateIndex + 1) % ELRS_RATE_MAX;
806 setRfLinkRate(receiver.rateIndex); // switch between rates
807 receiver.statsUpdatedAtMs = timeStampMs;
808 lqReset();
809 receiver.startReceiving();
811 // Switch to FAST_SYNC if not already in it (won't be if was just connected)
812 receiver.rfModeCycleMultiplier = 1;
813 } // if time to switch RF mode
816 #ifdef USE_RX_SX1280
817 static inline void configureReceiverForSX1280(void)
819 receiver.init = (elrsRxInitFnPtr) sx1280Init;
820 receiver.config = (elrsRxConfigFnPtr) sx1280Config;
821 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx1280StartReceiving;
822 receiver.rxISR = (elrsRxISRFnPtr) sx1280ISR;
823 receiver.rxHandleFromTock = (elrsRxHandleFromTockFnPtr) sx1280HandleFromTock;
824 receiver.rxHandleFromTick = (elrsRxBusyTimeoutFnPtr) sx1280HandleFromTick;
825 receiver.getRfLinkInfo = (elrsRxgetRfLinkInfoFnPtr) sx1280GetLastPacketStats;
826 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx1280AdjustFrequency;
828 #endif
830 #ifdef USE_RX_SX127X
831 static inline void configureReceiverForSX127x(void)
833 receiver.init = (elrsRxInitFnPtr) sx127xInit;
834 receiver.config = (elrsRxConfigFnPtr) sx127xConfig;
835 receiver.startReceiving = (elrsRxStartReceivingFnPtr) sx127xStartReceiving;
836 receiver.rxISR = (elrsRxISRFnPtr) sx127xISR;
837 receiver.getRfLinkInfo = (elrsRxgetRfLinkInfoFnPtr) sx127xGetLastPacketStats;
838 receiver.handleFreqCorrection = (elrsRxHandleFreqCorrectionFnPtr) sx127xAdjustFrequency;
840 #endif
842 //setup
843 bool expressLrsSpiInit(const struct rxSpiConfig_s *rxConfig, struct rxRuntimeState_s *rxRuntimeState, rxSpiExtiConfig_t *extiConfig)
845 if (!rxSpiExtiConfigured()) {
846 return false;
849 rxSpiCommonIOInit(rxConfig);
851 rxRuntimeState->channelCount = ELRS_MAX_CHANNELS;
853 extiConfig->ioConfig = IOCFG_IPD;
854 extiConfig->trigger = BETAFLIGHT_EXTI_TRIGGER_RISING;
856 if (rxExpressLrsSpiConfig()->resetIoTag) {
857 receiver.resetPin = IOGetByTag(rxExpressLrsSpiConfig()->resetIoTag);
858 } else {
859 receiver.resetPin = IO_NONE;
862 if (rxExpressLrsSpiConfig()->busyIoTag) {
863 receiver.busyPin = IOGetByTag(rxExpressLrsSpiConfig()->busyIoTag);
864 } else {
865 receiver.busyPin = IO_NONE;
868 switch (rxExpressLrsSpiConfig()->domain) {
869 #ifdef USE_RX_SX127X
870 case AU433:
871 FALLTHROUGH;
872 case AU915:
873 FALLTHROUGH;
874 case EU433:
875 FALLTHROUGH;
876 case EU868:
877 FALLTHROUGH;
878 case IN866:
879 FALLTHROUGH;
880 case FCC915:
881 configureReceiverForSX127x();
882 bindingRateIndex = ELRS_BINDING_RATE_900;
883 break;
884 #endif
885 #ifdef USE_RX_SX1280
886 case ISM2400:
887 configureReceiverForSX1280();
888 bindingRateIndex = ELRS_BINDING_RATE_24;
889 break;
890 #endif
891 default:
892 return false;
895 if (!receiver.init(receiver.resetPin, receiver.busyPin)) {
896 return false;
899 if (rssiSource == RSSI_SOURCE_NONE) {
900 rssiSource = RSSI_SOURCE_RX_PROTOCOL;
903 if (linkQualitySource == LQ_SOURCE_NONE) {
904 linkQualitySource = LQ_SOURCE_RX_PROTOCOL_CRSF;
907 if (rxExpressLrsSpiConfig()->UID[0] || rxExpressLrsSpiConfig()->UID[1]
908 || rxExpressLrsSpiConfig()->UID[2] || rxExpressLrsSpiConfig()->UID[3]
909 || rxExpressLrsSpiConfig()->UID[4] || rxExpressLrsSpiConfig()->UID[5]) {
910 receiver.inBindingMode = false;
911 receiver.UID = rxExpressLrsSpiConfig()->UID;
912 crcInitializer = (receiver.UID[4] << 8) | receiver.UID[5];
913 } else {
914 receiver.inBindingMode = true;
915 receiver.UID = BindingUID;
916 crcInitializer = 0;
919 expressLrsPhaseLockReset();
921 expressLrsInitialiseTimer(RX_EXPRESSLRS_TIMER_INSTANCE, &receiver.timerUpdateCb);
922 expressLrsTimerStop();
924 generateCrc14Table();
925 initializeReceiver();
927 initTelemetry();
928 #ifdef USE_MSP_OVER_TELEMETRY
929 setMspDataToReceive(ELRS_MSP_BUFFER_SIZE, mspBuffer, ELRS_MSP_BYTES_PER_CALL);
930 #endif
932 // Timer IRQs must only be enabled after the receiver is configured otherwise race conditions occur.
933 expressLrsTimerEnableIRQs();
935 return true;
938 static void handleConnectionStateUpdate(const uint32_t timeStampMs)
940 if ((receiver.connectionState != ELRS_DISCONNECTED) && (receiver.modParams->index != receiver.nextRateIndex)) { // forced change
941 lostConnection();
942 receiver.lastSyncPacketMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
943 receiver.rfModeCycledAtMs = timeStampMs; // reset this variable to stop rf mode switching and add extra time
944 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
945 #ifdef USE_RX_RSSI_DBM
946 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
947 #endif
948 #ifdef USE_RX_LINK_QUALITY_INFO
949 setLinkQualityDirect(0);
950 #endif
953 if (receiver.connectionState == ELRS_TENTATIVE && ((timeStampMs - receiver.lastSyncPacketMs) > receiver.rfPerfParams->rxLockTimeoutMs)) {
954 lostConnection();
955 receiver.rfModeCycledAtMs = timeStampMs;
956 receiver.lastSyncPacketMs = timeStampMs;
959 cycleRfMode(timeStampMs);
961 // Note that will updated from ISR and could thus be ahead of the timestamp
962 uint32_t localLastValidPacket = receiver.lastValidPacketMs;
964 // Determine the time in ms since the last valid packet was received. As this will be received under interrupt control it may be
965 // after the timeStampMs value was taken in which case treat as if it arrived at the same time to avoid a timeout
966 int32_t lastPacketDeltaMs = cmp32(timeStampMs, localLastValidPacket);
968 if (lastPacketDeltaMs < 0) {
969 lastPacketDeltaMs = 0;
972 if ((receiver.connectionState == ELRS_DISCONNECT_PENDING) || // check if we lost conn.
973 ((receiver.connectionState == ELRS_CONNECTED) && ((uint32_t)lastPacketDeltaMs > receiver.rfPerfParams->disconnectTimeoutMs))) {
974 lostConnection();
977 if ((receiver.connectionState == ELRS_TENTATIVE) && (ABS(pl.offsetDeltaUs) <= 10) && (pl.offsetUs < 100) && (lqGet() > minLqForChaos())) {
978 gotConnection(timeStampMs); // detects when we are connected
981 if ((receiver.timerState == ELRS_TIM_TENTATIVE) && ((timeStampMs - receiver.gotConnectionMs) > ELRS_CONSIDER_CONNECTION_GOOD_MS) && (ABS(pl.offsetDeltaUs) <= 5)) {
982 receiver.timerState = ELRS_TIM_LOCKED;
985 if ((receiver.connectionState == ELRS_CONNECTED) && (ABS(pl.offsetDeltaUs) > 10) && (pl.offsetUs >= 100) && (lqGet() <= minLqForChaos())) {
986 lostConnection(); // SPI: resync when we're in chaos territory
990 static void handleConfigUpdate(const uint32_t timeStampMs)
992 if ((timeStampMs - receiver.configCheckedAtMs) > ELRS_CONFIG_CHECK_MS) {
993 receiver.configCheckedAtMs = timeStampMs;
994 if (receiver.configChanged) {
995 saveConfigAndNotify();
996 receiver.initializeReceiverPending = true;
997 receiver.configChanged = false;
1002 static void handleLinkStatsUpdate(const uint32_t timeStampMs)
1004 if ((timeStampMs - receiver.statsUpdatedAtMs) > ELRS_LINK_STATS_CHECK_MS) {
1006 receiver.statsUpdatedAtMs = timeStampMs;
1008 if (receiver.connectionState == ELRS_CONNECTED) {
1009 receiver.rssiFiltered = simpleLPFilterUpdate(&rssiFilter, receiver.rssi);
1010 uint16_t rssiScaled = scaleRange(constrain(receiver.rssiFiltered, receiver.rfPerfParams->sensitivity, -50), receiver.rfPerfParams->sensitivity, -50, 0, 1023);
1011 setRssi(rssiScaled, RSSI_SOURCE_RX_PROTOCOL);
1012 #ifdef USE_RX_RSSI_DBM
1013 setRssiDbm(receiver.rssiFiltered, RSSI_SOURCE_RX_PROTOCOL);
1014 #endif
1015 #ifdef USE_RX_LINK_QUALITY_INFO
1016 setLinkQualityDirect(receiver.uplinkLQ);
1017 #endif
1018 #ifdef USE_RX_LINK_UPLINK_POWER
1019 rxSetUplinkTxPwrMw(txPowerIndexToValue(txPower));
1020 #endif
1021 } else {
1022 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
1023 #ifdef USE_RX_RSSI_DBM
1024 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL);
1025 #endif
1026 #ifdef USE_RX_LINK_QUALITY_INFO
1027 setLinkQualityDirect(0);
1028 #endif
1033 void expressLrsHandleTelemetryUpdate(void)
1035 if (receiver.connectionState != ELRS_CONNECTED || (receiver.modParams->tlmInterval == TLM_RATIO_NO_TLM)) {
1036 return;
1039 uint8_t *nextPayload = 0;
1040 uint8_t nextPlayloadSize = 0;
1041 if (!isTelemetrySenderActive() && getNextTelemetryPayload(&nextPlayloadSize, &nextPayload)) {
1042 setTelemetryDataToTransmit(nextPlayloadSize, nextPayload, ELRS_TELEMETRY_BYTES_PER_CALL);
1044 updateTelemetryBurst();
1047 void expressLrsSetRcDataFromPayload(uint16_t *rcData, const uint8_t *payload)
1049 if (rcData && payload) {
1050 rxExpressLrsSpiConfig()->switchMode == SM_HYBRID_WIDE ? unpackChannelDataHybridWide(rcData, payload) : unpackChannelDataHybridSwitch8(rcData, payload);
1054 static void enterBindingMode(void)
1056 // Set UID to special binding values
1057 receiver.UID = BindingUID;
1058 crcInitializer = 0;
1059 receiver.inBindingMode = true;
1061 setRfLinkRate(bindingRateIndex);
1062 receiver.startReceiving();
1065 void expressLrsDoTelem(void)
1067 expressLrsHandleTelemetryUpdate();
1068 expressLrsSendTelemResp();
1070 if (rxExpressLrsSpiConfig()->domain != ISM2400 && !receiver.didFhss && !expressLrsTelemRespReq() && lqPeriodIsSet()) {
1071 // TODO No need to handle this on SX1280, but will on SX127x
1072 // TODO this needs to be DMA aswell, SX127x unlikely to work right now
1073 receiver.handleFreqCorrection(receiver.freqOffset, receiver.currentFreq); //corrects for RX freq offset
1077 rx_spi_received_e expressLrsDataReceived(uint8_t *payloadBuffer)
1079 payload = payloadBuffer;
1081 rx_spi_received_e rfPacketReturnStatus = RX_SPI_RECEIVED_NONE;
1083 if (!receiver.started && (systemState & SYSTEM_STATE_READY)) {
1084 receiver.started = true;
1085 receiver.startReceiving(); // delay receiving after initialization to ensure a clean connect
1088 if (receiver.initializeReceiverPending) {
1089 initializeReceiver();
1090 receiver.initializeReceiverPending = false;
1093 if (rxSpiCheckBindRequested(true)) {
1094 enterBindingMode();
1097 const uint32_t timeStampMs = millis();
1098 handleConnectionStateUpdate(timeStampMs);
1099 handleConfigUpdate(timeStampMs);
1100 handleLinkStatsUpdate(timeStampMs);
1102 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 0, lostConnectionCounter);
1103 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 1, receiver.rssiFiltered);
1104 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 2, receiver.snr);
1105 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI, 3, receiver.uplinkLQ);
1107 receiver.inBindingMode ? rxSpiLedBlinkBind() : rxSpiLedBlinkRxLoss(rfPacketStatus);
1109 if (rfPacketStatus != RX_SPI_RECEIVED_NONE) {
1110 // A packet has been received since last time
1111 rfPacketReturnStatus = rfPacketStatus;
1112 rfPacketStatus = RX_SPI_RECEIVED_NONE;
1114 return rfPacketReturnStatus;
1117 void expressLrsStop(void)
1119 if (receiver.started) {
1120 lostConnection();
1124 void expressLrsISR(bool runAlways)
1126 if (runAlways || !expressLrsTimerIsRunning()) {
1127 receiver.rxISR();
1130 #endif /* USE_RX_EXPRESSLRS */