Unify rx spi exti handling (#9268)
[betaflight.git] / src / main / rx / cc2500_frsky_x.c
blob449f01ae8852e3315bcc31339b216e826920da2d
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/>.
21 #include <string.h>
23 #include "platform.h"
25 #ifdef USE_RX_FRSKY_SPI_X
27 #include "build/build_config.h"
28 #include "build/debug.h"
30 #include "common/maths.h"
31 #include "common/utils.h"
33 #include "config/feature.h"
35 #include "drivers/adc.h"
36 #include "drivers/io.h"
37 #include "drivers/io_def.h"
38 #include "drivers/io_types.h"
39 #include "drivers/resource.h"
40 #include "drivers/rx/rx_cc2500.h"
41 #include "drivers/rx/rx_spi.h"
42 #include "drivers/system.h"
43 #include "drivers/time.h"
45 #include "config/config.h"
47 #include "pg/rx.h"
48 #include "pg/rx_spi.h"
49 #include "pg/rx_spi_cc2500.h"
51 #include "rx/rx_spi_common.h"
52 #include "rx/cc2500_common.h"
53 #include "rx/cc2500_frsky_common.h"
54 #include "rx/cc2500_frsky_shared.h"
56 #include "sensors/battery.h"
58 #include "telemetry/smartport.h"
60 #include "cc2500_frsky_x.h"
62 const uint16_t crcTable[] = {
63 0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
64 0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
65 0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
66 0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
67 0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
68 0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
69 0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
70 0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
71 0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
72 0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
73 0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
74 0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
75 0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
76 0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
77 0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
78 0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
79 0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
80 0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
81 0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
82 0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
83 0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
84 0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
85 0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
86 0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
87 0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
88 0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
89 0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
90 0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
91 0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
92 0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
93 0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
94 0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
97 #define TELEMETRY_OUT_BUFFER_SIZE 64
99 #define TELEMETRY_SEQUENCE_LENGTH 4
101 #define A1_CONST_X 50
103 typedef struct telemetrySequenceMarkerData_s {
104 unsigned int packetSequenceId: 2;
105 unsigned int unused: 1;
106 unsigned int initRequest: 1;
107 unsigned int ackSequenceId: 2;
108 unsigned int retransmissionRequested: 1;
109 unsigned int initResponse: 1;
110 } __attribute__ ((__packed__)) telemetrySequenceMarkerData_t;
112 typedef union telemetrySequenceMarker_s {
113 uint8_t raw;
114 telemetrySequenceMarkerData_t data;
115 } __attribute__ ((__packed__)) telemetrySequenceMarker_t;
117 #define SEQUENCE_MARKER_REMOTE_PART 0xf0
119 #define TELEMETRY_DATA_SIZE 5
121 typedef struct telemetryData_s {
122 uint8_t dataLength;
123 uint8_t data[TELEMETRY_DATA_SIZE];
124 } __attribute__ ((__packed__)) telemetryData_t;
126 typedef struct telemetryBuffer_s {
127 telemetryData_t data;
128 uint8_t needsProcessing;
129 } telemetryBuffer_t;
131 #define TELEMETRY_FRAME_SIZE sizeof(telemetryData_t)
133 typedef struct telemetryPayload_s {
134 uint8_t packetConst;
135 uint8_t rssiA1;
136 telemetrySequenceMarker_t sequence;
137 telemetryData_t data;
138 uint8_t crc[2];
139 } __attribute__ ((__packed__)) telemetryPayload_t;
141 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
142 static telemetryData_t telemetryTxBuffer[TELEMETRY_SEQUENCE_LENGTH];
143 #endif
145 static telemetryBuffer_t telemetryRxBuffer[TELEMETRY_SEQUENCE_LENGTH];
147 static telemetrySequenceMarker_t responseToSend;
149 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
150 static uint8_t frame[20];
152 #if defined(USE_TELEMETRY_SMARTPORT)
153 static uint8_t telemetryOutWriter;
155 static uint8_t telemetryOutBuffer[TELEMETRY_OUT_BUFFER_SIZE];
157 static bool telemetryEnabled = false;
159 static uint8_t remoteToProcessId = 0;
160 static uint8_t remoteToProcessIndex = 0;
161 #endif
162 #endif // USE_RX_FRSKY_SPI_TELEMETRY
164 static uint8_t packetLength;
165 static uint16_t telemetryDelayUs;
167 static uint16_t calculateCrc(const uint8_t *data, uint8_t len) {
168 uint16_t crc = 0;
169 for (unsigned i = 0; i < len; i++) {
170 crc = (crc << 8) ^ (crcTable[((uint8_t)(crc >> 8) ^ *data++) & 0xFF]);
172 return crc;
175 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
176 #if defined(USE_TELEMETRY_SMARTPORT)
177 static uint8_t appendSmartPortData(uint8_t *buf)
179 static uint8_t telemetryOutReader = 0;
181 uint8_t index;
182 for (index = 0; index < TELEMETRY_DATA_SIZE; index++) { // max 5 bytes in a frame
183 if (telemetryOutReader == telemetryOutWriter){ // no new data
184 break;
186 buf[index] = telemetryOutBuffer[telemetryOutReader];
187 telemetryOutReader = (telemetryOutReader + 1) % TELEMETRY_OUT_BUFFER_SIZE;
190 return index;
192 #endif
194 static void buildTelemetryFrame(uint8_t *packet)
196 static uint8_t localPacketId;
198 static bool evenRun = false;
200 frame[0] = 0x0E;//length
201 frame[1] = rxCc2500SpiConfig()->bindTxId[0];
202 frame[2] = rxCc2500SpiConfig()->bindTxId[1];
203 frame[3] = packet[3];
205 if (evenRun) {
206 frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
207 } else {
208 uint8_t a1Value;
209 switch (rxCc2500SpiConfig()->a1Source) {
210 case FRSKY_SPI_A1_SOURCE_EXTADC:
211 a1Value = (uint8_t)((adcGetChannel(ADC_EXTERNAL1) & 0xfe0) >> 5);
212 break;
213 case FRSKY_SPI_A1_SOURCE_CONST:
214 a1Value = A1_CONST_X & 0x7f;
215 break;
216 case FRSKY_SPI_A1_SOURCE_VBAT:
217 default:
218 a1Value = getLegacyBatteryVoltage() & 0x7f;
219 break;
221 frame[4] = a1Value;
223 evenRun = !evenRun;
225 telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
226 telemetrySequenceMarker_t *outFrameMarker = (telemetrySequenceMarker_t *)&frame[5];
227 if (inFrameMarker->data.initRequest) { // check syncronization at startup ok if not no sport telemetry
228 outFrameMarker-> raw = 0;
229 outFrameMarker->data.initRequest = 1;
230 outFrameMarker->data.initResponse = 1;
232 localPacketId = 0;
233 } else {
234 if (inFrameMarker->data.retransmissionRequested) {
235 uint8_t retransmissionFrameId = inFrameMarker->data.ackSequenceId;
236 outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART;
237 outFrameMarker->data.packetSequenceId = retransmissionFrameId;
239 memcpy(&frame[6], &telemetryTxBuffer[retransmissionFrameId], TELEMETRY_FRAME_SIZE);
240 } else {
241 uint8_t localAckId = inFrameMarker->data.ackSequenceId;
242 if (localPacketId != (localAckId + 1) % TELEMETRY_SEQUENCE_LENGTH) {
243 outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART;
244 outFrameMarker->data.packetSequenceId = localPacketId;
246 frame[6] = appendSmartPortData(&frame[7]);
247 memcpy(&telemetryTxBuffer[localPacketId], &frame[6], TELEMETRY_FRAME_SIZE);
249 localPacketId = (localPacketId + 1) % TELEMETRY_SEQUENCE_LENGTH;
254 uint16_t lcrc = calculateCrc(&frame[3], 10);
255 frame[13]=lcrc>>8;
256 frame[14]=lcrc;
259 static bool frSkyXReadyToSend(void)
261 return true;
264 #if defined(USE_TELEMETRY_SMARTPORT)
265 static void frSkyXTelemetrySendByte(uint8_t c) {
266 if (c == FSSP_DLE || c == FSSP_START_STOP) {
267 telemetryOutBuffer[telemetryOutWriter] = FSSP_DLE;
268 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
269 telemetryOutBuffer[telemetryOutWriter] = c ^ FSSP_DLE_XOR;
270 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
271 } else {
272 telemetryOutBuffer[telemetryOutWriter] = c;
273 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
277 static void frSkyXTelemetryWriteFrame(const smartPortPayload_t *payload)
279 telemetryOutBuffer[telemetryOutWriter] = FSSP_START_STOP;
280 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
281 telemetryOutBuffer[telemetryOutWriter] = FSSP_SENSOR_ID1 & 0x1f;
282 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
283 uint8_t *data = (uint8_t *)payload;
284 for (unsigned i = 0; i < sizeof(smartPortPayload_t); i++) {
285 frSkyXTelemetrySendByte(*data++);
288 #endif
289 #endif // USE_RX_FRSKY_SPI_TELEMETRY
292 void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet)
294 uint16_t c[8];
295 // ignore failsafe packet
296 if (packet[7] != 0) {
297 return;
299 c[0] = (uint16_t)((packet[10] << 8) & 0xF00) | packet[9];
300 c[1] = (uint16_t)((packet[11] << 4) & 0xFF0) | (packet[10] >> 4);
301 c[2] = (uint16_t)((packet[13] << 8) & 0xF00) | packet[12];
302 c[3] = (uint16_t)((packet[14] << 4) & 0xFF0) | (packet[13] >> 4);
303 c[4] = (uint16_t)((packet[16] << 8) & 0xF00) | packet[15];
304 c[5] = (uint16_t)((packet[17] << 4) & 0xFF0) | (packet[16] >> 4);
305 c[6] = (uint16_t)((packet[19] << 8) & 0xF00) | packet[18];
306 c[7] = (uint16_t)((packet[20] << 4) & 0xFF0) | (packet[19] >> 4);
308 for (unsigned i = 0; i < 8; i++) {
309 const bool channelIsShifted = c[i] & 0x800;
310 const uint16_t channelValue = c[i] & 0x7FF;
311 rcData[channelIsShifted ? i + 8 : i] = ((channelValue - 64) * 2 + 860 * 3) / 3;
315 bool isValidPacket(const uint8_t *packet)
317 uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
318 if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
319 (packet[0] == packetLength - 3) &&
320 (packet[1] == rxCc2500SpiConfig()->bindTxId[0]) &&
321 (packet[2] == rxCc2500SpiConfig()->bindTxId[1]) &&
322 (rxCc2500SpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxCc2500SpiConfig()->rxNum)) {
323 return true;
325 return false;
328 rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState)
330 static unsigned receiveTelemetryRetryCount = 0;
331 static bool skipChannels = true;
333 static uint8_t remoteAckId = 0;
335 static timeUs_t packetTimerUs;
337 static bool frameReceived;
338 static timeDelta_t receiveDelayUs;
339 static uint8_t channelsToSkip = 1;
340 static uint32_t packetErrors = 0;
342 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
343 static bool telemetryReceived = false;
344 #endif
346 rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
348 switch (*protocolState) {
349 case STATE_STARTING:
350 listLength = 47;
351 initialiseData(false);
352 *protocolState = STATE_UPDATE;
353 nextChannel(1);
354 cc2500Strobe(CC2500_SRX);
355 break;
356 case STATE_UPDATE:
357 packetTimerUs = micros();
358 *protocolState = STATE_DATA;
359 frameReceived = false; // again set for receive
360 receiveDelayUs = 5300;
361 if (rxSpiCheckBindRequested(false)) {
362 packetTimerUs = 0;
363 timeoutUs = 50;
364 missingPackets = 0;
365 *protocolState = STATE_INIT;
367 break;
370 FALLTHROUGH;
371 // here FS code could be
372 case STATE_DATA:
373 if (rxSpiGetExtiState() && (frameReceived == false)){
374 uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
375 if (ccLen >= packetLength) {
376 cc2500ReadFifo(packet, packetLength);
377 if (isValidPacket(packet)) {
378 missingPackets = 0;
379 timeoutUs = 1;
380 receiveDelayUs = 0;
381 rxSpiLedOn();
382 if (skipChannels) {
383 channelsToSkip = packet[5] << 2;
384 if (packet[4] >= listLength) {
385 if (packet[4] < (64 + listLength)) {
386 channelsToSkip += 1;
387 } else if (packet[4] < (128 + listLength)) {
388 channelsToSkip += 2;
389 } else if (packet[4] < (192 + listLength)) {
390 channelsToSkip += 3;
393 telemetryReceived = true; // now telemetry can be sent
394 skipChannels = false;
396 cc2500setRssiDbm(packet[packetLength - 2]);
398 telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
400 uint8_t remoteNewPacketId = inFrameMarker->data.packetSequenceId;
401 memcpy(&telemetryRxBuffer[remoteNewPacketId].data, &packet[22], TELEMETRY_FRAME_SIZE);
402 telemetryRxBuffer[remoteNewPacketId].needsProcessing = true;
404 responseToSend.raw = 0;
405 uint8_t remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
406 if (remoteNewPacketId != remoteToAckId) {
407 while (remoteToAckId != remoteNewPacketId) {
408 if (!telemetryRxBuffer[remoteToAckId].needsProcessing) {
409 responseToSend.data.ackSequenceId = remoteToAckId;
410 responseToSend.data.retransmissionRequested = 1;
412 receiveTelemetryRetryCount++;
414 break;
417 remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
421 if (!responseToSend.data.retransmissionRequested) {
422 receiveTelemetryRetryCount = 0;
424 remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
425 uint8_t remoteNextAckId = remoteToAckId;
426 while (telemetryRxBuffer[remoteToAckId].needsProcessing && remoteToAckId != remoteAckId) {
427 remoteNextAckId = remoteToAckId;
428 remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
430 remoteAckId = remoteNextAckId;
431 responseToSend.data.ackSequenceId = remoteAckId;
434 if (receiveTelemetryRetryCount >= 5) {
435 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
436 remoteToProcessId = 0;
437 remoteToProcessIndex = 0;
438 #endif
439 remoteAckId = TELEMETRY_SEQUENCE_LENGTH - 1;
440 for (unsigned i = 0; i < TELEMETRY_SEQUENCE_LENGTH; i++) {
441 telemetryRxBuffer[i].needsProcessing = false;
444 receiveTelemetryRetryCount = 0;
447 packetTimerUs = micros();
448 frameReceived = true; // no need to process frame again.
450 if (!frameReceived) {
451 packetErrors++;
452 DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_BAD_FRAME, packetErrors);
453 cc2500Strobe(CC2500_SFRX);
457 if (telemetryReceived) {
458 if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs) { // if received or not received in this time sent telemetry data
459 *protocolState = STATE_TELEMETRY;
460 buildTelemetryFrame(packet);
463 if (cmpTimeUs(micros(), packetTimerUs) > timeoutUs * SYNC_DELAY_MAX) {
464 rxSpiLedToggle();
466 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
467 nextChannel(1);
468 cc2500Strobe(CC2500_SRX);
469 *protocolState = STATE_UPDATE;
471 if (frameReceived) {
472 ret |= RX_SPI_RECEIVED_DATA;
475 break;
476 #ifdef USE_RX_FRSKY_SPI_TELEMETRY
477 case STATE_TELEMETRY:
478 if (cmpTimeUs(micros(), packetTimerUs) >= receiveDelayUs + telemetryDelayUs) { // if received or not received in this time sent telemetry data
479 cc2500Strobe(CC2500_SIDLE);
480 cc2500SetPower(6);
481 cc2500Strobe(CC2500_SFRX);
482 delayMicroseconds(30);
483 #if defined(USE_RX_CC2500_SPI_PA_LNA)
484 cc2500TxEnable();
485 #endif
486 cc2500Strobe(CC2500_SIDLE);
487 cc2500WriteFifo(frame, frame[0] + 1);
489 #if defined(USE_TELEMETRY_SMARTPORT)
490 if (telemetryEnabled) {
491 ret |= RX_SPI_ROCESSING_REQUIRED;
493 #endif
494 *protocolState = STATE_RESUME;
497 break;
498 #endif // USE_RX_FRSKY_SPI_TELEMETRY
499 case STATE_RESUME:
500 if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs + 3700) {
501 packetTimerUs = micros();
502 receiveDelayUs = 5300;
503 frameReceived = false; // again set for receive
504 nextChannel(channelsToSkip);
505 cc2500Strobe(CC2500_SRX);
506 #ifdef USE_RX_CC2500_SPI_PA_LNA
507 cc2500TxDisable();
508 #if defined(USE_RX_CC2500_SPI_DIVERSITY)
509 if (missingPackets >= 2) {
510 cc2500switchAntennae();
512 #endif
513 #endif // USE_RX_CC2500_SPI_PA_LNA
514 if (missingPackets > MAX_MISSING_PKT) {
515 timeoutUs = 50;
516 skipChannels = true;
517 telemetryReceived = false;
518 *protocolState = STATE_UPDATE;
519 break;
521 missingPackets++;
522 DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_MISSING_PACKETS, missingPackets);
523 *protocolState = STATE_DATA;
525 break;
528 return ret;
531 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
532 rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet)
534 static timeMs_t pollingTimeMs = 0;
536 UNUSED(packet);
538 bool clearToSend = false;
539 timeMs_t now = millis();
540 smartPortPayload_t *payload = NULL;
541 if ((now - pollingTimeMs) > 24) {
542 pollingTimeMs = now;
544 clearToSend = true;
545 } else {
546 while (telemetryRxBuffer[remoteToProcessId].needsProcessing && !payload) {
547 if (remoteToProcessIndex >= telemetryRxBuffer[remoteToProcessId].data.dataLength) {
548 remoteToProcessIndex = 0;
549 telemetryRxBuffer[remoteToProcessId].needsProcessing = false;
550 remoteToProcessId = (remoteToProcessId + 1) % TELEMETRY_SEQUENCE_LENGTH;
552 if (!telemetryRxBuffer[remoteToProcessId].needsProcessing) {
553 break;
557 while (remoteToProcessIndex < telemetryRxBuffer[remoteToProcessId].data.dataLength && !payload) {
558 payload = smartPortDataReceive(telemetryRxBuffer[remoteToProcessId].data.data[remoteToProcessIndex], &clearToSend, frSkyXReadyToSend, false);
559 remoteToProcessIndex = remoteToProcessIndex + 1;
564 processSmartPortTelemetry(payload, &clearToSend, NULL);
566 return RX_SPI_RECEIVED_NONE;
568 #endif
570 void frSkyXInit(const rx_spi_protocol_e spiProtocol)
572 switch(spiProtocol) {
573 case RX_SPI_FRSKY_X:
574 packetLength = 32;
575 telemetryDelayUs = 400;
576 break;
577 case RX_SPI_FRSKY_X_LBT:
578 packetLength = 35;
579 telemetryDelayUs = 1400;
580 break;
581 default:
582 break;
584 #if defined(USE_TELEMETRY_SMARTPORT)
585 if (featureIsEnabled(FEATURE_TELEMETRY)) {
586 telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame);
588 #endif
591 #endif