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)
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.
26 * Phobos- - Original port.
27 * Dominic Clifton/Hydra - Timer-based timeout implementation.
28 * Phobos- - Port of v2.0
34 #ifdef USE_RX_EXPRESSLRS
36 #include "build/debug.h"
37 #include "build/debug_pin.h"
39 #include "common/maths.h"
40 #include "common/filter.h"
42 #include "drivers/io.h"
43 #include "drivers/rx/rx_spi.h"
44 #include "drivers/system.h"
45 #include "drivers/time.h"
46 #include "drivers/timer.h"
47 #include "drivers/rx/rx_sx127x.h"
48 #include "drivers/rx/rx_sx1280.h"
49 #include "drivers/rx/expresslrs_driver.h"
51 #include "config/config.h"
52 #include "config/feature.h"
55 #include "pg/pg_ids.h"
56 #include "pg/rx_spi.h"
57 #include "pg/rx_spi_expresslrs.h"
60 #include "rx/rx_spi.h"
61 #include "rx/rx_spi_common.h"
63 #include "rx/expresslrs.h"
64 #include "rx/expresslrs_common.h"
65 #include "rx/expresslrs_impl.h"
66 #include "rx/expresslrs_telemetry.h"
68 STATIC_UNIT_TESTED elrsReceiver_t receiver
;
69 static const uint8_t BindingUID
[6] = {0,1,2,3,4,5}; // Special binding UID values
70 static uint16_t crcInitializer
= 0;
71 static uint8_t bindingRateIndex
= 0;
72 static bool connectionHasModelMatch
= false;
73 static uint8_t txPower
= 0;
74 static uint8_t wideSwitchIndex
= 0;
76 static simpleLowpassFilter_t rssiFilter
;
78 static void rssiFilterReset(void)
80 simpleLPFilterInit(&rssiFilter
, 3, 5);
83 #define PACKET_HANDLING_TO_TOCK_ISR_DELAY_US 250
86 // Event pair recorder
94 #define EPR_EVENT_COUNT 2
96 typedef struct eprState_s
{
97 uint32_t eventAtUs
[EPR_EVENT_COUNT
];
98 bool eventRecorded
[EPR_EVENT_COUNT
];
101 eprState_t eprState
= {
103 .eventRecorded
= {0},
106 static void expressLrsEPRRecordEvent(eprEvent_e event
, uint32_t currentTimeUs
)
108 eprState
.eventAtUs
[event
] = currentTimeUs
;
109 eprState
.eventRecorded
[event
] = true;
112 static bool expressLrsEPRHaveBothEvents(void)
114 bool bothEventsRecorded
= eprState
.eventRecorded
[EPR_SECOND
] && eprState
.eventRecorded
[EPR_FIRST
];
115 return bothEventsRecorded
;
118 static int32_t expressLrsEPRGetResult(void)
120 if (!expressLrsEPRHaveBothEvents()) {
124 return (int32_t)(eprState
.eventAtUs
[EPR_SECOND
] - eprState
.eventAtUs
[EPR_FIRST
]);
127 static void expressLrsEPRReset(void)
129 memset(&eprState
, 0, sizeof(eprState_t
));
138 #define EPR_INTERNAL EPR_FIRST
139 #define EPR_EXTERNAL EPR_SECOND
141 typedef struct phaseLockState_s
{
142 simpleLowpassFilter_t offsetFilter
;
143 simpleLowpassFilter_t offsetDxFilter
;
146 int32_t previousRawOffsetUs
;
149 int32_t offsetDeltaUs
;
150 int32_t previousOffsetUs
;
153 static phaseLockState_t pl
;
155 static void expressLrsPhaseLockReset(void)
157 simpleLPFilterInit(&pl
.offsetFilter
, 2, 5);
158 simpleLPFilterInit(&pl
.offsetDxFilter
, 4, 5);
160 expressLrsEPRReset();
163 static uint8_t nextTelemetryType
= ELRS_TELEMETRY_TYPE_LINK
;
165 static uint8_t telemetryBurstCount
= 1;
166 static uint8_t telemetryBurstMax
= 1;
167 static bool telemBurstValid
= false;
169 // Maximum ms between LINK_STATISTICS packets for determining burst max
170 #define TELEM_MIN_LINK_INTERVAL 512U
172 #ifdef USE_MSP_OVER_TELEMETRY
173 static uint8_t mspBuffer
[ELRS_MSP_BUFFER_SIZE
];
180 static void setRssiChannelData(uint16_t *rcData
)
182 rcData
[ELRS_LQ_CHANNEL
] = scaleRange(receiver
.uplinkLQ
, 0, 100, 988, 2011);
183 rcData
[ELRS_RSSI_CHANNEL
] = scaleRange(constrain(receiver
.rssiFiltered
, receiver
.rfPerfParams
->sensitivity
, -50), receiver
.rfPerfParams
->sensitivity
, -50, 988, 2011);
186 static void unpackAnalogChannelData(uint16_t *rcData
, const uint8_t *payload
)
188 rcData
[0] = convertAnalog((payload
[0] << 3) | ((payload
[4] & 0xC0) >> 5));
189 rcData
[1] = convertAnalog((payload
[1] << 3) | ((payload
[4] & 0x30) >> 3));
190 rcData
[2] = convertAnalog((payload
[2] << 3) | ((payload
[4] & 0x0C) >> 1));
191 rcData
[3] = convertAnalog((payload
[3] << 3) | ((payload
[4] & 0x03) << 1));
195 * Hybrid switches uses 10 bits for each analog channel,
196 * 2 bits for the low latency switch[0]
197 * 3 bits for the round-robin switch index and 2 bits for the value
198 * 4 analog channels, 1 low latency switch and round robin switch data = 47 bits (1 free)
200 * sets telemetry status bit
202 static void unpackChannelDataHybridSwitch8(uint16_t *rcData
, const uint8_t *payload
)
204 unpackAnalogChannelData(rcData
, payload
);
206 const uint8_t switchByte
= payload
[5];
208 // The low latency switch
209 rcData
[4] = convertSwitch1b((switchByte
& 0x40) >> 6);
211 // The round-robin switch, switchIndex is actually index-1
212 // to leave the low bit open for switch 7 (sent as 0b11x)
213 // where x is the high bit of switch 7
214 uint8_t switchIndex
= (switchByte
& 0x38) >> 3;
215 uint16_t switchValue
= convertSwitch3b(switchByte
& 0x07);
217 switch (switchIndex
) {
219 rcData
[5] = switchValue
;
222 rcData
[6] = switchValue
;
225 rcData
[7] = switchValue
;
228 rcData
[8] = switchValue
;
231 rcData
[9] = switchValue
;
234 rcData
[10] = switchValue
;
239 rcData
[11] = convertSwitchNb(switchByte
& 0x0F, 15); //4-bit
245 setRssiChannelData(rcData
);
249 * HybridWide switches decoding of over the air data
251 * Hybrid switches uses 10 bits for each analog channel,
252 * 1 bits for the low latency switch[0]
253 * 6 or 7 bits for the round-robin switch
254 * 1 bit for the TelemetryStatus, which may be in every packet or just idx 7
255 * depending on TelemetryRatio
257 * Output: crsf.PackedRCdataOut, crsf.LinkStatistics.uplink_TX_Power
258 * Returns: TelemetryStatus bit
260 static void unpackChannelDataHybridWide(uint16_t *rcData
, const uint8_t *payload
)
262 unpackAnalogChannelData(rcData
, payload
);
263 const uint8_t switchByte
= payload
[5];
265 // The low latency switch
266 rcData
[4] = convertSwitch1b((switchByte
& 0x80) >> 7);
268 // The round-robin switch, 6-7 bits with the switch index implied by the nonce. Some logic moved to processRFPacket
269 if (wideSwitchIndex
>= 7) {
270 txPower
= switchByte
& 0x3F;
273 uint16_t switchValue
;
274 if (tlmRatioEnumToValue(receiver
.modParams
->tlmInterval
) < 8) {
276 switchValue
= switchByte
& 0x3F; // 6-bit
279 switchValue
= switchByte
& 0x7F; // 7-bit
282 switchValue
= convertSwitchNb(switchValue
, bins
);
283 rcData
[5 + wideSwitchIndex
] = switchValue
;
286 setRssiChannelData(rcData
);
289 static void startReceiving(void)
292 receiver
.startReceiving();
295 static uint8_t minLqForChaos(void)
297 // Determine the most number of CRC-passing packets we could receive on
298 // a single channel out of 100 packets that fill the LQcalc span.
299 // The LQ must be GREATER THAN this value, not >=
300 // The amount of time we coexist on the same channel is
301 // 100 divided by the total number of packets in a FHSS loop (rounded up)
302 // and there would be 4x packets received each time it passes by so
303 // FHSShopInterval * ceil(100 / FHSShopInterval * numfhss) or
304 // FHSShopInterval * trunc((100 + (FHSShopInterval * numfhss) - 1) / (FHSShopInterval * numfhss))
305 // With a interval of 4 this works out to: 2.4=4, FCC915=4, AU915=8, EU868=8, EU/AU433=36
306 const uint32_t numfhss
= getFHSSNumEntries();
307 const uint8_t interval
= receiver
.modParams
->fhssHopInterval
;
308 return interval
* ((interval
* numfhss
+ 99) / (interval
* numfhss
));
311 static void setRFLinkRate(const uint8_t index
)
313 #if defined(USE_RX_SX1280) && defined(USE_RX_SX127X)
314 receiver
.modParams
= (rxExpressLrsSpiConfig()->domain
== ISM2400
) ? &airRateConfig
[1][index
] : &airRateConfig
[0][index
];
315 receiver
.rfPerfParams
= (rxExpressLrsSpiConfig()->domain
== ISM2400
) ? &rfPerfConfig
[1][index
] : &rfPerfConfig
[0][index
];
317 receiver
.modParams
= &airRateConfig
[0][index
];
318 receiver
.rfPerfParams
= &rfPerfConfig
[0][index
];
320 receiver
.currentFreq
= getInitialFreq(receiver
.freqOffset
);
321 // Wait for (11/10) 110% of time it takes to cycle through all freqs in FHSS table (in ms)
322 receiver
.cycleIntervalMs
= ((uint32_t)11U * getFHSSNumEntries() * receiver
.modParams
->fhssHopInterval
* receiver
.modParams
->interval
) / (10U * 1000U);
324 receiver
.config(receiver
.modParams
->bw
, receiver
.modParams
->sf
, receiver
.modParams
->cr
, receiver
.currentFreq
, receiver
.modParams
->preambleLen
, receiver
.UID
[5] & 0x01);
326 expressLrsUpdateTimerInterval(receiver
.modParams
->interval
);
329 receiver
.nextRateIndex
= index
; // presumably we just handled this
330 telemBurstValid
= false;
332 #ifdef USE_RX_LINK_QUALITY_INFO
333 rxSetRfMode((uint8_t)RATE_4HZ
- (uint8_t)receiver
.modParams
->enumRate
);
337 static bool handleFHSS(void)
339 uint8_t modresultFHSS
= (receiver
.nonceRX
+ 1) % receiver
.modParams
->fhssHopInterval
;
341 if ((receiver
.modParams
->fhssHopInterval
== 0) || receiver
.alreadyFHSS
== true || receiver
.inBindingMode
|| (modresultFHSS
!= 0) || (receiver
.connectionState
== ELRS_DISCONNECTED
)) {
345 receiver
.alreadyFHSS
= true;
346 receiver
.currentFreq
= FHSSgetNextFreq(receiver
.freqOffset
);
347 receiver
.setFrequency(receiver
.currentFreq
);
349 uint8_t modresultTLM
= (receiver
.nonceRX
+ 1) % (tlmRatioEnumToValue(receiver
.modParams
->tlmInterval
));
351 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
357 static bool handleSendTelemetryResponse(void)
363 uint8_t packageIndex
;
364 uint8_t modresult
= (receiver
.nonceRX
+ 1) % tlmRatioEnumToValue(receiver
.modParams
->tlmInterval
);
366 if ((receiver
.connectionState
== ELRS_DISCONNECTED
) || (receiver
.modParams
->tlmInterval
== TLM_RATIO_NO_TLM
)
367 || (receiver
.alreadyTLMresp
== true) || (modresult
!= 0)) {
368 return false; // don't bother sending tlm if disconnected or TLM is off
371 receiver
.alreadyTLMresp
= true;
372 packet
[0] = ELRS_TLM_PACKET
;
374 if (nextTelemetryType
== ELRS_TELEMETRY_TYPE_LINK
|| !isTelemetrySenderActive()) {
375 packet
[1] = ELRS_TELEMETRY_TYPE_LINK
;
376 packet
[2] = receiver
.rssiFiltered
> 0 ? 0 : -receiver
.rssiFiltered
; //diversity not supported
377 packet
[3] = connectionHasModelMatch
<< 7;
378 packet
[4] = receiver
.snr
;
379 packet
[5] = receiver
.uplinkLQ
;
380 #ifdef USE_MSP_OVER_TELEMETRY
381 packet
[6] = getCurrentMspConfirm() ? 1 : 0;
385 nextTelemetryType
= ELRS_TELEMETRY_TYPE_DATA
;
386 // Start the count at 1 because the next will be DATA and doing +1 before checking
387 // against Max below is for some reason 10 bytes more code
388 telemetryBurstCount
= 1;
390 if (telemetryBurstCount
< telemetryBurstMax
) {
391 telemetryBurstCount
++;
393 nextTelemetryType
= ELRS_TELEMETRY_TYPE_LINK
;
396 getCurrentTelemetryPayload(&packageIndex
, &maxLength
, &data
);
397 packet
[1] = (packageIndex
<< ELRS_TELEMETRY_SHIFT
) + ELRS_TELEMETRY_TYPE_DATA
;
398 packet
[2] = maxLength
> 0 ? *data
: 0;
399 packet
[3] = maxLength
>= 1 ? *(data
+ 1) : 0;
400 packet
[4] = maxLength
>= 2 ? *(data
+ 2) : 0;
401 packet
[5] = maxLength
>= 3 ? *(data
+ 3) : 0;
402 packet
[6] = maxLength
>= 4 ? *(data
+ 4) : 0;
405 uint16_t crc
= calcCrc14(packet
, 7, crcInitializer
);
406 packet
[0] |= (crc
>> 6) & 0xFC;
407 packet
[7] = crc
& 0xFF;
410 receiver
.transmitData(packet
, ELRS_RX_TX_BUFF_SIZE
);
414 static void updatePhaseLock(void)
416 if (receiver
.connectionState
!= ELRS_DISCONNECTED
&& expressLrsEPRHaveBothEvents()) {
417 pl
.rawOffsetUs
= expressLrsEPRGetResult();
419 pl
.offsetUs
= simpleLPFilterUpdate(&pl
.offsetFilter
, pl
.rawOffsetUs
);
420 pl
.offsetDeltaUs
= simpleLPFilterUpdate(&pl
.offsetDxFilter
, pl
.rawOffsetUs
- pl
.previousRawOffsetUs
);
422 if (receiver
.timerState
== ELRS_TIM_LOCKED
&& lqPeriodIsSet()) {
423 if (receiver
.nonceRX
% 8 == 0) { //limit rate of freq offset adjustment slightly
424 if (pl
.offsetUs
> 0) {
425 expressLrsTimerIncreaseFrequencyOffset();
426 } else if (pl
.offsetUs
< 0) {
427 expressLrsTimerDecreaseFrequencyOffset();
432 if (receiver
.connectionState
!= ELRS_CONNECTED
) {
433 expressLrsUpdatePhaseShift(pl
.rawOffsetUs
>> 1);
435 expressLrsUpdatePhaseShift(pl
.offsetUs
>> 2);
438 pl
.previousOffsetUs
= pl
.offsetUs
;
439 pl
.previousRawOffsetUs
= pl
.rawOffsetUs
;
441 expressLrsTimerDebug();
443 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK
, 0, pl
.rawOffsetUs
);
444 DEBUG_SET(DEBUG_RX_EXPRESSLRS_PHASELOCK
, 1, pl
.offsetUs
);
447 expressLrsEPRReset();
450 //hwTimerCallbackTick
451 void expressLrsOnTimerTickISR(void) // this is 180 out of phase with the other callback, occurs mid-packet reception
454 receiver
.nonceRX
+= 1;
456 // Save the LQ value before the inc() reduces it by 1
457 receiver
.uplinkLQ
= lqGet();
458 // Only advance the LQI period counter if we didn't send Telemetry this period
459 if (!receiver
.alreadyTLMresp
) {
463 receiver
.alreadyTLMresp
= false;
464 receiver
.alreadyFHSS
= false;
467 //hwTimerCallbackTock
468 void expressLrsOnTimerTockISR(void)
470 uint32_t currentTimeUs
= micros();
472 expressLrsEPRRecordEvent(EPR_INTERNAL
, currentTimeUs
);
474 receiver
.fhssRequired
= true; //Rest of the code is moved to expressLrsDataReceived to avoid race condition
477 static uint16_t lostConnectionCounter
= 0;
479 void lostConnection(void)
481 lostConnectionCounter
++;
483 receiver
.rfModeCycleMultiplier
= 1;
484 receiver
.connectionState
= ELRS_DISCONNECTED
; //set lost connection
485 receiver
.timerState
= ELRS_TIM_DISCONNECTED
;
486 expressLrsTimerResetFrequencyOffset();
487 receiver
.freqOffset
= 0;
489 pl
.offsetDeltaUs
= 0;
491 pl
.previousRawOffsetUs
= 0;
492 receiver
.gotConnectionMs
= 0;
493 receiver
.uplinkLQ
= 0;
495 expressLrsPhaseLockReset();
496 receiver
.alreadyTLMresp
= false;
497 receiver
.alreadyFHSS
= false;
499 if (!receiver
.inBindingMode
) {
500 //while (micros() - expressLrsEPRGetResult() > 250); // time it just after the tock() TODO this currently breaks and is blocking, not a fan of this.
501 expressLrsTimerStop();
502 setRFLinkRate(receiver
.nextRateIndex
); // also sets to initialFreq
507 static void tentativeConnection(const uint32_t timeStampMs
)
509 receiver
.connectionState
= ELRS_TENTATIVE
;
510 connectionHasModelMatch
= false;
511 receiver
.timerState
= ELRS_TIM_DISCONNECTED
;
512 receiver
.freqOffset
= 0;
514 pl
.previousRawOffsetUs
= 0;
515 expressLrsPhaseLockReset(); //also resets PFD
516 receiver
.rfModeCycledAtMs
= timeStampMs
; // give another 3 sec for lock to occur
518 // The caller MUST call hwTimer.resume(). It is not done here because
519 // the timer ISR will fire immediately and preempt any other code
522 static void gotConnection(const uint32_t timeStampMs
)
524 if (receiver
.connectionState
== ELRS_CONNECTED
) {
525 return; // Already connected
528 receiver
.lockRFmode
= true; // currently works as if LOCK_ON_FIRST_CONNECTION was enabled
530 receiver
.connectionState
= ELRS_CONNECTED
; //we got a packet, therefore no lost connection
531 receiver
.timerState
= ELRS_TIM_TENTATIVE
;
532 receiver
.gotConnectionMs
= timeStampMs
;
534 if (rxExpressLrsSpiConfig()->rateIndex
!= receiver
.rateIndex
) {
535 rxExpressLrsSpiConfigMutable()->rateIndex
= receiver
.rateIndex
;
536 receiver
.configChanged
= true;
541 static void initializeReceiver(void)
543 FHSSrandomiseFHSSsequence(receiver
.UID
, rxExpressLrsSpiConfig()->domain
);
545 receiver
.nonceRX
= 0;
546 receiver
.freqOffset
= 0;
547 receiver
.configChanged
= false;
549 receiver
.rssiFiltered
= 0;
551 receiver
.uplinkLQ
= 0;
552 receiver
.rateIndex
= receiver
.inBindingMode
? bindingRateIndex
: rxExpressLrsSpiConfig()->rateIndex
;
553 setRFLinkRate(receiver
.rateIndex
);
555 receiver
.alreadyFHSS
= false;
556 receiver
.alreadyTLMresp
= false;
557 receiver
.lockRFmode
= false;
558 receiver
.timerState
= ELRS_TIM_DISCONNECTED
;
559 receiver
.connectionState
= ELRS_DISCONNECTED
;
561 uint32_t timeStampMs
= millis();
563 receiver
.rfModeCycledAtMs
= timeStampMs
;
564 receiver
.configCheckedAtMs
= timeStampMs
;
565 receiver
.statsUpdatedAtMs
= timeStampMs
;
566 receiver
.gotConnectionMs
= timeStampMs
;
567 receiver
.lastSyncPacketMs
= timeStampMs
;
568 receiver
.lastValidPacketMs
= timeStampMs
;
570 receiver
.rfModeCycleMultiplier
= 1;
573 static void unpackBindPacket(uint8_t *packet
)
575 rxExpressLrsSpiConfigMutable()->UID
[2] = packet
[3];
576 rxExpressLrsSpiConfigMutable()->UID
[3] = packet
[4];
577 rxExpressLrsSpiConfigMutable()->UID
[4] = packet
[5];
578 rxExpressLrsSpiConfigMutable()->UID
[5] = packet
[6];
580 receiver
.UID
= rxExpressLrsSpiConfigMutable()->UID
;
581 crcInitializer
= (receiver
.UID
[4] << 8) | receiver
.UID
[5];
582 receiver
.inBindingMode
= false;
584 initializeReceiver();
586 receiver
.configChanged
= true; //after initialize as it sets it to false
591 * Process the assembled MSP packet in mspBuffer[]
593 static void processRFMspPacket(uint8_t *packet
)
595 // Always examine MSP packets for bind information if in bind mode
596 // [1] is the package index, first packet of the MSP
597 if (receiver
.inBindingMode
&& packet
[1] == 1 && packet
[2] == ELRS_MSP_BIND
) {
598 unpackBindPacket(packet
); //onELRSBindMSP
602 #ifdef USE_MSP_OVER_TELEMETRY
603 // Must be fully connected to process MSP, prevents processing MSP
604 // during sync, where packets can be received before connection
605 if (receiver
.connectionState
!= ELRS_CONNECTED
) {
609 bool currentMspConfirmValue
= getCurrentMspConfirm();
610 receiveMspData(packet
[1], packet
+ 2);
611 if (currentMspConfirmValue
!= getCurrentMspConfirm()) {
612 nextTelemetryType
= ELRS_TELEMETRY_TYPE_LINK
;
614 if (hasFinishedMspData()) {
615 if (mspBuffer
[ELRS_MSP_COMMAND_INDEX
] == ELRS_MSP_SET_RX_CONFIG
&& mspBuffer
[ELRS_MSP_COMMAND_INDEX
+ 1] == ELRS_MSP_MODEL_ID
) { //mspReceiverComplete
616 if (rxExpressLrsSpiConfig()->modelId
!= mspBuffer
[9]) { //UpdateModelMatch
617 rxExpressLrsSpiConfigMutable()->modelId
= mspBuffer
[9];
618 receiver
.configChanged
= true;
619 receiver
.connectionState
= ELRS_DISCONNECT_PENDING
;
621 } else if (connectionHasModelMatch
) {
622 processMspPacket(mspBuffer
);
630 static bool processRFSyncPacket(uint8_t *packet
, const uint32_t timeStampMs
)
632 // Verify the first two of three bytes of the binding ID, which should always match
633 if (packet
[4] != receiver
.UID
[3] || packet
[5] != receiver
.UID
[4]) {
637 // The third byte will be XORed with inverse of the ModelId if ModelMatch is on
638 // Only require the first 18 bits of the UID to match to establish a connection
639 // but the last 6 bits must modelmatch before sending any data to the FC
640 if ((packet
[6] & ~ELRS_MODELMATCH_MASK
) != (receiver
.UID
[5] & ~ELRS_MODELMATCH_MASK
)) {
644 receiver
.lastSyncPacketMs
= timeStampMs
;
646 // Will change the packet air rate in loop() if this changes
647 receiver
.nextRateIndex
= (packet
[3] & 0xC0) >> 6;
648 uint8_t tlmRateIn
= (packet
[3] & 0x38) >> 3;
649 uint8_t switchEncMode
= ((packet
[3] & 0x06) >> 1) - 1; //spi implementation uses 0 based index for hybrid
651 // Update switch mode encoding immediately
652 if (switchEncMode
!= rxExpressLrsSpiConfig()->switchMode
) {
653 rxExpressLrsSpiConfigMutable()->switchMode
= switchEncMode
;
654 receiver
.configChanged
= true;
658 if (receiver
.modParams
->tlmInterval
!= tlmRateIn
) {
659 receiver
.modParams
->tlmInterval
= tlmRateIn
;
660 telemBurstValid
= false;
663 // modelId = 0xff indicates modelMatch is disabled, the XOR does nothing in that case
664 uint8_t modelXor
= (~rxExpressLrsSpiConfig()->modelId
) & ELRS_MODELMATCH_MASK
;
665 bool modelMatched
= packet
[6] == (receiver
.UID
[5] ^ modelXor
);
667 if (receiver
.connectionState
== ELRS_DISCONNECTED
|| receiver
.nonceRX
!= packet
[2] || FHSSgetCurrIndex() != packet
[1] || connectionHasModelMatch
!= modelMatched
) {
668 FHSSsetCurrIndex(packet
[1]);
669 receiver
.nonceRX
= packet
[2];
671 tentativeConnection(timeStampMs
);
672 connectionHasModelMatch
= modelMatched
;
674 if (!expressLrsTimerIsRunning()) {
682 static rx_spi_received_e
processRFPacket(uint8_t *payload
)
684 uint8_t packet
[ELRS_RX_TX_BUFF_SIZE
];
686 receiver
.receiveData(packet
, ELRS_RX_TX_BUFF_SIZE
);
688 uint32_t timeStampUs
= micros();
690 elrsPacketType_e type
= packet
[0] & 0x03;
691 uint16_t inCRC
= (((uint16_t)(packet
[0] & 0xFC)) << 6 ) | packet
[7];
693 // For SM_HYBRID the CRC only has the packet type in byte 0
694 // For SM_HYBRID_WIDE the FHSS slot is added to the CRC in byte 0 on RC_DATA_PACKETs
695 if (type
!= ELRS_RC_DATA_PACKET
|| rxExpressLrsSpiConfig()->switchMode
!= SM_HYBRID_WIDE
) {
698 uint8_t nonceFHSSresult
= receiver
.nonceRX
% receiver
.modParams
->fhssHopInterval
;
699 packet
[0] = type
| (nonceFHSSresult
<< 2);
701 uint16_t calculatedCRC
= calcCrc14(packet
, 7, crcInitializer
);
703 if (inCRC
!= calculatedCRC
) {
704 return RX_SPI_RECEIVED_NONE
;
707 expressLrsEPRRecordEvent(EPR_EXTERNAL
, timeStampUs
+ PACKET_HANDLING_TO_TOCK_ISR_DELAY_US
);
709 bool shouldStartTimer
= false;
710 uint32_t timeStampMs
= millis();
712 receiver
.lastValidPacketMs
= timeStampMs
;
715 case ELRS_RC_DATA_PACKET
:
716 // Must be fully connected to process RC packets, prevents processing RC
717 // during sync, where packets can be received before connection
718 if (receiver
.connectionState
== ELRS_CONNECTED
&& connectionHasModelMatch
) {
719 if (rxExpressLrsSpiConfig()->switchMode
== SM_HYBRID_WIDE
) {
720 wideSwitchIndex
= hybridWideNonceToSwitchIndex(receiver
.nonceRX
);
721 if ((tlmRatioEnumToValue(receiver
.modParams
->tlmInterval
) < 8) || wideSwitchIndex
== 7) {
722 confirmCurrentTelemetryPayload((packet
[6] & 0x40) >> 6);
725 confirmCurrentTelemetryPayload(packet
[6] & (1 << 7));
727 memcpy(payload
, &packet
[1], 6); // stick data handling is done in expressLrsSetRcDataFromPayload
730 case ELRS_MSP_DATA_PACKET
:
731 processRFMspPacket(packet
);
733 case ELRS_TLM_PACKET
:
736 case ELRS_SYNC_PACKET
:
737 shouldStartTimer
= processRFSyncPacket(packet
, timeStampMs
) && !receiver
.inBindingMode
;
740 return RX_SPI_RECEIVED_NONE
;
743 // Store the LQ/RSSI/Antenna
744 receiver
.getRFlinkInfo(&receiver
.rssi
, &receiver
.snr
);
745 // Received a packet, that's the definition of LQ
747 // Extend sync duration since we've received a packet at this rate
748 // but do not extend it indefinitely
749 receiver
.rfModeCycleMultiplier
= ELRS_MODE_CYCLE_MULTIPLIER_SLOW
; //RFModeCycleMultiplierSlow
751 if (shouldStartTimer
) {
752 expressLrsTimerResume();
755 receiver
.fhssRequired
= true;
757 return RX_SPI_RECEIVED_DATA
;
760 static void updateTelemetryBurst(void)
762 if (telemBurstValid
) {
765 telemBurstValid
= true;
767 uint32_t hz
= rateEnumToHz(receiver
.modParams
->enumRate
);
768 uint32_t ratiodiv
= tlmRatioEnumToValue(receiver
.modParams
->tlmInterval
);
769 telemetryBurstMax
= TELEM_MIN_LINK_INTERVAL
* hz
/ ratiodiv
/ 1000U;
771 // Reserve one slot for LINK telemetry
772 if (telemetryBurstMax
> 1) {
775 telemetryBurstMax
= 1;
778 // Notify the sender to adjust its expected throughput
779 updateTelemetryRate(hz
, ratiodiv
, telemetryBurstMax
);
782 /* If not connected will rotate through the RF modes looking for sync
785 static void cycleRfMode(const uint32_t timeStampMs
)
787 if (receiver
.connectionState
== ELRS_CONNECTED
|| receiver
.inBindingMode
) {
790 // Actually cycle the RF mode if not LOCK_ON_FIRST_CONNECTION
791 if (receiver
.lockRFmode
== false && (timeStampMs
- receiver
.rfModeCycledAtMs
) > (receiver
.cycleIntervalMs
* receiver
.rfModeCycleMultiplier
)) {
792 receiver
.rfModeCycledAtMs
= timeStampMs
;
793 receiver
.lastSyncPacketMs
= timeStampMs
; // reset this variable
794 receiver
.rateIndex
= (receiver
.rateIndex
+ 1) % ELRS_RATE_MAX
;
795 setRFLinkRate(receiver
.rateIndex
); // switch between rates
796 receiver
.statsUpdatedAtMs
= timeStampMs
;
800 // Switch to FAST_SYNC if not already in it (won't be if was just connected)
801 receiver
.rfModeCycleMultiplier
= 1;
802 } // if time to switch RF mode
806 static inline void configureReceiverForSX1280(void)
808 receiver
.init
= (elrsRxInitFnPtr
) sx1280Init
;
809 receiver
.config
= (elrsRxConfigFnPtr
) sx1280Config
;
810 receiver
.startReceiving
= (elrsRxStartReceivingFnPtr
) sx1280StartReceiving
;
811 receiver
.rxISR
= (elrsRxISRFnPtr
) sx1280ISR
;
812 receiver
.transmitData
= (elrsRxTransmitDataFnPtr
) sx1280TransmitData
;
813 receiver
.receiveData
= (elrsRxReceiveDataFnPtr
) sx1280ReceiveData
;
814 receiver
.getRFlinkInfo
= (elrsRxGetRFlinkInfoFnPtr
) sx1280GetLastPacketStats
;
815 receiver
.setFrequency
= (elrsRxSetFrequencyFnPtr
) sx1280SetFrequencyReg
;
816 receiver
.handleFreqCorrection
= (elrsRxHandleFreqCorrectionFnPtr
) sx1280AdjustFrequency
;
821 static inline void configureReceiverForSX127x(void)
823 receiver
.init
= (elrsRxInitFnPtr
) sx127xInit
;
824 receiver
.config
= (elrsRxConfigFnPtr
) sx127xConfig
;
825 receiver
.startReceiving
= (elrsRxStartReceivingFnPtr
) sx127xStartReceiving
;
826 receiver
.rxISR
= (elrsRxISRFnPtr
) sx127xISR
;
827 receiver
.transmitData
= (elrsRxTransmitDataFnPtr
) sx127xTransmitData
;
828 receiver
.receiveData
= (elrsRxReceiveDataFnPtr
) sx127xReceiveData
;
829 receiver
.getRFlinkInfo
= (elrsRxGetRFlinkInfoFnPtr
) sx127xGetLastPacketStats
;
830 receiver
.setFrequency
= (elrsRxSetFrequencyFnPtr
) sx127xSetFrequencyReg
;
831 receiver
.handleFreqCorrection
= (elrsRxHandleFreqCorrectionFnPtr
) sx127xAdjustFrequency
;
836 bool expressLrsSpiInit(const struct rxSpiConfig_s
*rxConfig
, struct rxRuntimeState_s
*rxRuntimeState
, rxSpiExtiConfig_t
*extiConfig
)
838 if (!rxSpiExtiConfigured()) {
842 rxSpiCommonIOInit(rxConfig
);
844 rxRuntimeState
->channelCount
= ELRS_MAX_CHANNELS
;
846 extiConfig
->ioConfig
= IOCFG_IPD
;
847 extiConfig
->trigger
= BETAFLIGHT_EXTI_TRIGGER_RISING
;
849 if (rxExpressLrsSpiConfig()->resetIoTag
) {
850 receiver
.resetPin
= IOGetByTag(rxExpressLrsSpiConfig()->resetIoTag
);
852 receiver
.resetPin
= IO_NONE
;
855 if (rxExpressLrsSpiConfig()->busyIoTag
) {
856 receiver
.busyPin
= IOGetByTag(rxExpressLrsSpiConfig()->busyIoTag
);
858 receiver
.busyPin
= IO_NONE
;
861 switch (rxExpressLrsSpiConfig()->domain
) {
874 configureReceiverForSX127x();
875 bindingRateIndex
= ELRS_BINDING_RATE_900
;
880 configureReceiverForSX1280();
881 bindingRateIndex
= ELRS_BINDING_RATE_24
;
888 if (!receiver
.init(receiver
.resetPin
, receiver
.busyPin
)) {
892 if (rssiSource
== RSSI_SOURCE_NONE
) {
893 rssiSource
= RSSI_SOURCE_RX_PROTOCOL
;
896 if (linkQualitySource
== LQ_SOURCE_NONE
) {
897 linkQualitySource
= LQ_SOURCE_RX_PROTOCOL_CRSF
;
900 if (rxExpressLrsSpiConfig()->UID
[0] || rxExpressLrsSpiConfig()->UID
[1]
901 || rxExpressLrsSpiConfig()->UID
[2] || rxExpressLrsSpiConfig()->UID
[3]
902 || rxExpressLrsSpiConfig()->UID
[4] || rxExpressLrsSpiConfig()->UID
[5]) {
903 receiver
.inBindingMode
= false;
904 receiver
.UID
= rxExpressLrsSpiConfig()->UID
;
905 crcInitializer
= (receiver
.UID
[4] << 8) | receiver
.UID
[5];
907 receiver
.inBindingMode
= true;
908 receiver
.UID
= BindingUID
;
912 expressLrsPhaseLockReset();
914 expressLrsInitialiseTimer(RX_EXPRESSLRS_TIMER_INSTANCE
, &receiver
.timerUpdateCb
);
915 expressLrsTimerStop();
917 generateCrc14Table();
918 initializeReceiver();
921 #ifdef USE_MSP_OVER_TELEMETRY
922 setMspDataToReceive(ELRS_MSP_BUFFER_SIZE
, mspBuffer
, ELRS_MSP_BYTES_PER_CALL
);
925 // Timer IRQs must only be enabled after the receiver is configured otherwise race conditions occur.
926 expressLrsTimerEnableIRQs();
933 static void handleConnectionStateUpdate(const uint32_t timeStampMs
)
935 if ((receiver
.connectionState
!= ELRS_DISCONNECTED
) && (receiver
.modParams
->index
!= receiver
.nextRateIndex
)) { // forced change
937 receiver
.lastSyncPacketMs
= timeStampMs
; // reset this variable to stop rf mode switching and add extra time
938 receiver
.rfModeCycledAtMs
= timeStampMs
; // reset this variable to stop rf mode switching and add extra time
939 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
940 #ifdef USE_RX_RSSI_DBM
941 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL
);
943 #ifdef USE_RX_LINK_QUALITY_INFO
944 setLinkQualityDirect(0);
948 if (receiver
.connectionState
== ELRS_TENTATIVE
&& ((timeStampMs
- receiver
.lastSyncPacketMs
) > receiver
.rfPerfParams
->rxLockTimeoutMs
)) {
950 receiver
.rfModeCycledAtMs
= timeStampMs
;
951 receiver
.lastSyncPacketMs
= timeStampMs
;
954 cycleRfMode(timeStampMs
);
956 uint32_t localLastValidPacket
= receiver
.lastValidPacketMs
; // Required to prevent race condition due to LastValidPacket getting updated from ISR
957 if ((receiver
.connectionState
== ELRS_DISCONNECT_PENDING
) || // check if we lost conn.
958 ((receiver
.connectionState
== ELRS_CONNECTED
) && ((int32_t)receiver
.rfPerfParams
->disconnectTimeoutMs
< (int32_t)(timeStampMs
- localLastValidPacket
)))) {
962 if ((receiver
.connectionState
== ELRS_TENTATIVE
) && (ABS(pl
.offsetDeltaUs
) <= 10) && (pl
.offsetUs
< 100) && (lqGet() > minLqForChaos())) { //detects when we are connected
963 gotConnection(timeStampMs
);
966 if ((receiver
.timerState
== ELRS_TIM_TENTATIVE
) && ((timeStampMs
- receiver
.gotConnectionMs
) > ELRS_CONSIDER_CONNECTION_GOOD_MS
) && (ABS(pl
.offsetDeltaUs
) <= 5)) {
967 receiver
.timerState
= ELRS_TIM_LOCKED
;
971 static void handleConfigUpdate(const uint32_t timeStampMs
)
973 if ((timeStampMs
- receiver
.configCheckedAtMs
) > ELRS_CONFIG_CHECK_MS
) {
974 receiver
.configCheckedAtMs
= timeStampMs
;
975 if (receiver
.configChanged
) {
978 receiver
.configChanged
= false;
983 static void handleLinkStatsUpdate(const uint32_t timeStampMs
)
985 if ((timeStampMs
- receiver
.statsUpdatedAtMs
) > ELRS_LINK_STATS_CHECK_MS
) {
987 receiver
.statsUpdatedAtMs
= timeStampMs
;
989 if (receiver
.connectionState
!= ELRS_CONNECTED
) {
990 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
991 #ifdef USE_RX_RSSI_DBM
992 setRssiDbmDirect(-130, RSSI_SOURCE_RX_PROTOCOL
);
994 #ifdef USE_RX_LINK_QUALITY_INFO
995 setLinkQualityDirect(0);
998 receiver
.rssiFiltered
= simpleLPFilterUpdate(&rssiFilter
, receiver
.rssi
);
999 uint16_t rssiScaled
= scaleRange(constrain(receiver
.rssiFiltered
, receiver
.rfPerfParams
->sensitivity
, -50), receiver
.rfPerfParams
->sensitivity
, -50, 0, 1023);
1000 setRssi(rssiScaled
, RSSI_SOURCE_RX_PROTOCOL
);
1001 #ifdef USE_RX_RSSI_DBM
1002 setRssiDbm(receiver
.rssiFiltered
, RSSI_SOURCE_RX_PROTOCOL
);
1004 #ifdef USE_RX_LINK_QUALITY_INFO
1005 setLinkQualityDirect(receiver
.uplinkLQ
);
1007 #ifdef USE_RX_LINK_UPLINK_POWER
1008 rxSetUplinkTxPwrMw(txPowerIndexToValue(txPower
));
1014 static void handleTelemetryUpdate(void)
1016 if (receiver
.connectionState
!= ELRS_CONNECTED
|| (receiver
.modParams
->tlmInterval
== TLM_RATIO_NO_TLM
)) {
1020 uint8_t *nextPayload
= 0;
1021 uint8_t nextPlayloadSize
= 0;
1022 if (!isTelemetrySenderActive() && getNextTelemetryPayload(&nextPlayloadSize
, &nextPayload
)) {
1023 setTelemetryDataToTransmit(nextPlayloadSize
, nextPayload
, ELRS_TELEMETRY_BYTES_PER_CALL
);
1025 updateTelemetryBurst();
1028 void expressLrsSetRcDataFromPayload(uint16_t *rcData
, const uint8_t *payload
)
1030 if (rcData
&& payload
) {
1031 rxExpressLrsSpiConfig()->switchMode
== SM_HYBRID_WIDE
? unpackChannelDataHybridWide(rcData
, payload
) : unpackChannelDataHybridSwitch8(rcData
, payload
);
1035 static void enterBindingMode(void)
1037 if ((receiver
.connectionState
== ELRS_CONNECTED
) || receiver
.inBindingMode
) {
1038 // Don't enter binding if:
1039 // - we're already connected
1040 // - we're already binding
1044 // Set UID to special binding values
1045 receiver
.UID
= BindingUID
;
1047 receiver
.inBindingMode
= true;
1049 setRFLinkRate(bindingRateIndex
);
1053 rx_spi_received_e
expressLrsDataReceived(uint8_t *payload
)
1055 rx_spi_received_e result
= RX_SPI_RECEIVED_NONE
;
1056 uint32_t isrTimeStampUs
;
1058 if (rxSpiCheckBindRequested(true)) {
1062 uint8_t irqReason
= receiver
.rxISR(&isrTimeStampUs
);
1063 if (irqReason
== ELRS_DIO_TX_DONE
) {
1065 } else if (irqReason
== ELRS_DIO_RX_DONE
) {
1066 result
= processRFPacket(payload
);
1069 if (receiver
.fhssRequired
) {
1070 receiver
.fhssRequired
= false;
1071 bool didFHSS
= handleFHSS();
1072 bool tlmSent
= handleSendTelemetryResponse();
1074 if (!didFHSS
&& !tlmSent
&& lqPeriodIsSet() && rxExpressLrsSpiConfig()->domain
!= ISM2400
) {
1075 receiver
.handleFreqCorrection(receiver
.freqOffset
, receiver
.currentFreq
); //corrects for RX freq offset
1079 handleTelemetryUpdate();
1081 const uint32_t timeStampMs
= millis();
1083 handleConnectionStateUpdate(timeStampMs
);
1084 handleConfigUpdate(timeStampMs
);
1085 handleLinkStatsUpdate(timeStampMs
);
1087 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI
, 0, lostConnectionCounter
);
1088 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI
, 1, receiver
.rssiFiltered
);
1089 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI
, 2, receiver
.snr
);
1090 DEBUG_SET(DEBUG_RX_EXPRESSLRS_SPI
, 3, receiver
.uplinkLQ
);
1092 receiver
.inBindingMode
? rxSpiLedBlinkBind() : rxSpiLedBlinkRxLoss(result
);
1097 #endif /* USE_RX_EXPRESSLRS */