Fix rx spi processing required (#13454)
[betaflight.git] / src / main / rx / cc2500_frsky_x.c
blob12f35b47906f9952c58e13b788da9202c5ab63bd
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_Short[] = {
63 0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
64 0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
67 #define TELEMETRY_OUT_BUFFER_SIZE 64
69 #define TELEMETRY_SEQUENCE_LENGTH 4
71 #define A1_CONST_X 50
73 typedef struct telemetrySequenceMarkerData_s {
74 unsigned int packetSequenceId: 2;
75 unsigned int unused: 1;
76 unsigned int initRequest: 1;
77 unsigned int ackSequenceId: 2;
78 unsigned int retransmissionRequested: 1;
79 unsigned int initResponse: 1;
80 } __attribute__ ((__packed__)) telemetrySequenceMarkerData_t;
82 typedef union telemetrySequenceMarker_s {
83 uint8_t raw;
84 telemetrySequenceMarkerData_t data;
85 } __attribute__ ((__packed__)) telemetrySequenceMarker_t;
87 #define SEQUENCE_MARKER_REMOTE_PART 0xf0
89 #define TELEMETRY_DATA_SIZE 5
91 typedef struct telemetryData_s {
92 uint8_t dataLength;
93 uint8_t data[TELEMETRY_DATA_SIZE];
94 } __attribute__ ((__packed__)) telemetryData_t;
96 typedef struct telemetryBuffer_s {
97 telemetryData_t data;
98 uint8_t needsProcessing;
99 } telemetryBuffer_t;
101 #define TELEMETRY_FRAME_SIZE sizeof(telemetryData_t)
103 typedef struct telemetryPayload_s {
104 uint8_t packetConst;
105 uint8_t rssiA1;
106 telemetrySequenceMarker_t sequence;
107 telemetryData_t data;
108 uint8_t crc[2];
109 } __attribute__ ((__packed__)) telemetryPayload_t;
111 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
112 static telemetryData_t telemetryTxBuffer[TELEMETRY_SEQUENCE_LENGTH];
113 #endif
115 static telemetryBuffer_t telemetryRxBuffer[TELEMETRY_SEQUENCE_LENGTH];
117 static telemetrySequenceMarker_t responseToSend;
119 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
120 static uint8_t frame[20];
122 #if defined(USE_TELEMETRY_SMARTPORT)
123 static uint8_t telemetryOutWriter;
125 static uint8_t telemetryOutBuffer[TELEMETRY_OUT_BUFFER_SIZE];
127 static bool telemetryEnabled = false;
129 static uint8_t remoteToProcessId = 0;
130 static uint8_t remoteToProcessIndex = 0;
131 #endif
132 #endif // USE_RX_FRSKY_SPI_TELEMETRY
134 static uint8_t packetLength;
135 static uint16_t telemetryDelayUs;
137 static uint16_t crcTable(uint8_t val)
139 uint16_t word;
140 word = (*(&crcTable_Short[val & 0x0f]));
141 val /= 16;
142 return word ^ (0x1081 * val);
145 static uint16_t calculateCrc(const uint8_t *data, uint8_t len)
147 uint16_t crc = 0;
148 for (unsigned i = 0; i < len; i++) {
149 crc = (crc << 8) ^ crcTable((uint8_t)(crc >> 8) ^ *data++);
151 return crc;
154 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
155 #if defined(USE_TELEMETRY_SMARTPORT)
156 static uint8_t appendSmartPortData(uint8_t *buf)
158 static uint8_t telemetryOutReader = 0;
160 uint8_t index;
161 for (index = 0; index < TELEMETRY_DATA_SIZE; index++) { // max 5 bytes in a frame
162 if (telemetryOutReader == telemetryOutWriter) { // no new data
163 break;
165 buf[index] = telemetryOutBuffer[telemetryOutReader];
166 telemetryOutReader = (telemetryOutReader + 1) % TELEMETRY_OUT_BUFFER_SIZE;
169 return index;
171 #endif
173 static void buildTelemetryFrame(uint8_t *packet)
175 static uint8_t localPacketId;
177 static bool evenRun = false;
179 frame[0] = 0x0E;//length
180 frame[1] = rxCc2500SpiConfig()->bindTxId[0];
181 frame[2] = rxCc2500SpiConfig()->bindTxId[1];
183 if (spiProtocol == RX_SPI_FRSKY_X_V2 || spiProtocol == RX_SPI_FRSKY_X_LBT_V2) {
184 frame[3] = rxCc2500SpiConfig()->bindTxId[2];
185 } else {
186 frame[3] = packet[3];
189 if (evenRun) {
190 frame[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
191 } else {
192 uint8_t a1Value;
193 switch (rxCc2500SpiConfig()->a1Source) {
194 case FRSKY_SPI_A1_SOURCE_EXTADC:
195 a1Value = (uint8_t)((adcGetChannel(ADC_EXTERNAL1) & 0xfe0) >> 5);
196 break;
197 case FRSKY_SPI_A1_SOURCE_CONST:
198 a1Value = A1_CONST_X & 0x7f;
199 break;
200 case FRSKY_SPI_A1_SOURCE_VBAT:
201 default:
202 a1Value = getLegacyBatteryVoltage() & 0x7f;
203 break;
205 frame[4] = a1Value;
207 evenRun = !evenRun;
209 telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
210 telemetrySequenceMarker_t *outFrameMarker = (telemetrySequenceMarker_t *)&frame[5];
211 if (inFrameMarker->data.initRequest) { // check syncronization at startup ok if not no sport telemetry
212 outFrameMarker-> raw = 0;
213 outFrameMarker->data.initRequest = 1;
214 outFrameMarker->data.initResponse = 1;
216 localPacketId = 0;
217 } else {
218 if (inFrameMarker->data.retransmissionRequested) {
219 uint8_t retransmissionFrameId = inFrameMarker->data.ackSequenceId;
220 outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART;
221 outFrameMarker->data.packetSequenceId = retransmissionFrameId;
223 memcpy(&frame[6], &telemetryTxBuffer[retransmissionFrameId], TELEMETRY_FRAME_SIZE);
224 } else {
225 uint8_t localAckId = inFrameMarker->data.ackSequenceId;
226 if (localPacketId != (localAckId + 1) % TELEMETRY_SEQUENCE_LENGTH) {
227 outFrameMarker->raw = responseToSend.raw & SEQUENCE_MARKER_REMOTE_PART;
228 outFrameMarker->data.packetSequenceId = localPacketId;
230 #if defined(USE_TELEMETRY_SMARTPORT)
231 frame[6] = appendSmartPortData(&frame[7]);
232 memcpy(&telemetryTxBuffer[localPacketId], &frame[6], TELEMETRY_FRAME_SIZE);
233 #endif
234 localPacketId = (localPacketId + 1) % TELEMETRY_SEQUENCE_LENGTH;
239 uint16_t lcrc = calculateCrc(&frame[3], 10);
240 frame[13]=lcrc>>8;
241 frame[14]=lcrc;
244 #if defined(USE_TELEMETRY_SMARTPORT)
245 static bool frSkyXReadyToSend(void)
247 return true;
249 #endif
251 #if defined(USE_TELEMETRY_SMARTPORT)
252 static void frSkyXTelemetrySendByte(uint8_t c)
254 if (c == FSSP_DLE || c == FSSP_START_STOP) {
255 telemetryOutBuffer[telemetryOutWriter] = FSSP_DLE;
256 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
257 telemetryOutBuffer[telemetryOutWriter] = c ^ FSSP_DLE_XOR;
258 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
259 } else {
260 telemetryOutBuffer[telemetryOutWriter] = c;
261 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
265 static void frSkyXTelemetryWriteFrame(const smartPortPayload_t *payload)
267 telemetryOutBuffer[telemetryOutWriter] = FSSP_START_STOP;
268 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
269 telemetryOutBuffer[telemetryOutWriter] = FSSP_SENSOR_ID1 & 0x1f;
270 telemetryOutWriter = (telemetryOutWriter + 1) % TELEMETRY_OUT_BUFFER_SIZE;
271 uint8_t *data = (uint8_t *)payload;
272 for (unsigned i = 0; i < sizeof(smartPortPayload_t); i++) {
273 frSkyXTelemetrySendByte(*data++);
276 #endif
277 #endif // USE_RX_FRSKY_SPI_TELEMETRY
280 void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet)
282 uint16_t c[8];
283 // ignore failsafe packet
284 if (packet[7] != 0) {
285 return;
287 c[0] = (uint16_t)((packet[10] << 8) & 0xF00) | packet[9];
288 c[1] = (uint16_t)((packet[11] << 4) & 0xFF0) | (packet[10] >> 4);
289 c[2] = (uint16_t)((packet[13] << 8) & 0xF00) | packet[12];
290 c[3] = (uint16_t)((packet[14] << 4) & 0xFF0) | (packet[13] >> 4);
291 c[4] = (uint16_t)((packet[16] << 8) & 0xF00) | packet[15];
292 c[5] = (uint16_t)((packet[17] << 4) & 0xFF0) | (packet[16] >> 4);
293 c[6] = (uint16_t)((packet[19] << 8) & 0xF00) | packet[18];
294 c[7] = (uint16_t)((packet[20] << 4) & 0xFF0) | (packet[19] >> 4);
296 for (unsigned i = 0; i < 8; i++) {
297 const bool channelIsShifted = c[i] & 0x800;
298 const uint16_t channelValue = c[i] & 0x7FF;
299 rcData[channelIsShifted ? i + 8 : i] = ((channelValue - 64) * 2 + 860 * 3) / 3;
303 bool isValidPacket(const uint8_t *packet)
305 bool useBindTxId2 = false;
307 if (spiProtocol == RX_SPI_FRSKY_X_V2 || spiProtocol == RX_SPI_FRSKY_X_LBT_V2) {
308 useBindTxId2 = true;
309 if (!(packet[packetLength - 1] & 0x80)) {
310 return false;
314 uint16_t lcrc = calculateCrc(&packet[3], (packetLength - 7));
316 if ((lcrc >> 8) == packet[packetLength - 4] && (lcrc & 0x00FF) == packet[packetLength - 3] &&
317 (packet[0] == packetLength - 3) &&
318 (packet[1] == rxCc2500SpiConfig()->bindTxId[0]) &&
319 (packet[2] == rxCc2500SpiConfig()->bindTxId[1]) &&
320 (!useBindTxId2 || (packet[3] == rxCc2500SpiConfig()->bindTxId[2])) &&
321 (rxCc2500SpiConfig()->rxNum == 0 || packet[6] == 0 || packet[6] == rxCc2500SpiConfig()->rxNum)) {
322 return true;
324 return false;
327 rx_spi_received_e frSkyXHandlePacket(uint8_t * const packet, uint8_t * const protocolState)
329 static unsigned receiveTelemetryRetryCount = 0;
330 static bool skipChannels = true;
332 static uint8_t remoteAckId = 0;
334 static timeUs_t packetTimerUs;
336 static bool frameReceived;
337 static timeDelta_t receiveDelayUs;
338 static uint8_t channelsToSkip = 1;
339 static uint32_t packetErrors = 0;
341 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
342 static bool telemetryReceived = false;
343 #endif
345 rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
347 switch (*protocolState) {
348 case STATE_STARTING:
349 listLength = 47;
350 initialiseData(false);
351 *protocolState = STATE_UPDATE;
352 nextChannel(1);
353 cc2500Strobe(CC2500_SRX);
354 break;
355 case STATE_UPDATE:
356 packetTimerUs = micros();
357 *protocolState = STATE_DATA;
358 frameReceived = false; // again set for receive
359 receiveDelayUs = 5300;
360 if (rxSpiCheckBindRequested(false)) {
361 packetTimerUs = 0;
362 timeoutUs = 50;
363 missingPackets = 0;
364 *protocolState = STATE_INIT;
366 break;
369 FALLTHROUGH;
370 // here FS code could be
371 case STATE_DATA:
372 if (rxSpiGetExtiState() && (!frameReceived)) {
373 uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
374 if (ccLen >= packetLength) {
375 cc2500ReadFifo(packet, packetLength);
376 if (isValidPacket(packet)) {
377 missingPackets = 0;
378 timeoutUs = 1;
379 receiveDelayUs = 0;
380 rxSpiLedOn();
381 if (skipChannels) {
382 channelsToSkip = (packet[5] << 2) | (packet[4] >> 6);
383 telemetryReceived = true; // now telemetry can be sent
384 skipChannels = false;
386 cc2500setRssiDbm(packet[packetLength - 2]);
388 telemetrySequenceMarker_t *inFrameMarker = (telemetrySequenceMarker_t *)&packet[21];
390 uint8_t remoteNewPacketId = inFrameMarker->data.packetSequenceId;
391 memcpy(&telemetryRxBuffer[remoteNewPacketId].data, &packet[22], TELEMETRY_FRAME_SIZE);
392 telemetryRxBuffer[remoteNewPacketId].needsProcessing = true;
394 responseToSend.raw = 0;
395 uint8_t remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
396 if (remoteNewPacketId != remoteToAckId) {
397 while (remoteToAckId != remoteNewPacketId) {
398 if (!telemetryRxBuffer[remoteToAckId].needsProcessing) {
399 responseToSend.data.ackSequenceId = remoteToAckId;
400 responseToSend.data.retransmissionRequested = 1;
402 receiveTelemetryRetryCount++;
404 break;
407 remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
411 if (!responseToSend.data.retransmissionRequested) {
412 receiveTelemetryRetryCount = 0;
414 remoteToAckId = (remoteAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
415 uint8_t remoteNextAckId = remoteToAckId;
416 while (telemetryRxBuffer[remoteToAckId].needsProcessing && remoteToAckId != remoteAckId) {
417 remoteNextAckId = remoteToAckId;
418 remoteToAckId = (remoteToAckId + 1) % TELEMETRY_SEQUENCE_LENGTH;
420 remoteAckId = remoteNextAckId;
421 responseToSend.data.ackSequenceId = remoteAckId;
424 if (receiveTelemetryRetryCount >= 5) {
425 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
426 remoteToProcessId = 0;
427 remoteToProcessIndex = 0;
428 #endif
429 remoteAckId = TELEMETRY_SEQUENCE_LENGTH - 1;
430 for (unsigned i = 0; i < TELEMETRY_SEQUENCE_LENGTH; i++) {
431 telemetryRxBuffer[i].needsProcessing = false;
434 receiveTelemetryRetryCount = 0;
437 packetTimerUs = micros();
438 frameReceived = true; // no need to process frame again.
440 if (!frameReceived) {
441 packetErrors++;
442 DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_BAD_FRAME, packetErrors);
443 cc2500Strobe(CC2500_SFRX);
447 if (telemetryReceived) {
448 if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs) { // if received or not received in this time sent telemetry data
449 *protocolState = STATE_TELEMETRY;
450 buildTelemetryFrame(packet);
453 if (cmpTimeUs(micros(), packetTimerUs) > timeoutUs * SYNC_DELAY_MAX) {
454 rxSpiLedToggle();
456 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL);
457 nextChannel(1);
458 cc2500Strobe(CC2500_SRX);
459 *protocolState = STATE_UPDATE;
461 if (frameReceived) {
462 ret |= RX_SPI_RECEIVED_DATA;
464 frameReceived = false;
467 break;
468 #ifdef USE_RX_FRSKY_SPI_TELEMETRY
469 case STATE_TELEMETRY:
470 if (cmpTimeUs(micros(), packetTimerUs) >= receiveDelayUs + telemetryDelayUs) { // if received or not received in this time sent telemetry data
471 cc2500Strobe(CC2500_SIDLE);
472 cc2500SetPower(6);
473 cc2500Strobe(CC2500_SFRX);
474 delayMicroseconds(30);
475 #if defined(USE_RX_CC2500_SPI_PA_LNA)
476 cc2500TxEnable();
477 #endif
478 cc2500Strobe(CC2500_SIDLE);
479 cc2500WriteFifo(frame, frame[0] + 1);
481 #if defined(USE_TELEMETRY_SMARTPORT)
482 if (telemetryEnabled) {
483 ret |= RX_SPI_PROCESSING_REQUIRED;
485 #endif
486 *protocolState = STATE_RESUME;
489 break;
490 #endif // USE_RX_FRSKY_SPI_TELEMETRY
491 case STATE_RESUME:
492 if (cmpTimeUs(micros(), packetTimerUs) > receiveDelayUs + 3700) {
493 packetTimerUs = micros();
494 receiveDelayUs = 5300;
495 frameReceived = false; // again set for receive
496 nextChannel(channelsToSkip);
497 cc2500Strobe(CC2500_SRX);
498 #ifdef USE_RX_CC2500_SPI_PA_LNA
499 cc2500TxDisable();
500 #if defined(USE_RX_CC2500_SPI_DIVERSITY)
501 if (missingPackets >= 2) {
502 cc2500switchAntennae();
504 #endif
505 #endif // USE_RX_CC2500_SPI_PA_LNA
506 if (missingPackets > MAX_MISSING_PKT) {
507 timeoutUs = 50;
508 skipChannels = true;
509 telemetryReceived = false;
510 *protocolState = STATE_UPDATE;
511 break;
513 missingPackets++;
514 DEBUG_SET(DEBUG_RX_FRSKY_SPI, DEBUG_DATA_MISSING_PACKETS, missingPackets);
515 *protocolState = STATE_DATA;
517 break;
520 return ret;
523 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
524 rx_spi_received_e frSkyXProcessFrame(uint8_t * const packet)
526 static timeMs_t pollingTimeMs = 0;
528 UNUSED(packet);
530 bool clearToSend = false;
531 timeMs_t now = millis();
532 smartPortPayload_t *payload = NULL;
533 if ((now - pollingTimeMs) > 24) {
534 pollingTimeMs = now;
536 clearToSend = true;
537 } else {
538 while (telemetryRxBuffer[remoteToProcessId].needsProcessing && !payload) {
539 if (remoteToProcessIndex >= telemetryRxBuffer[remoteToProcessId].data.dataLength) {
540 remoteToProcessIndex = 0;
541 telemetryRxBuffer[remoteToProcessId].needsProcessing = false;
542 remoteToProcessId = (remoteToProcessId + 1) % TELEMETRY_SEQUENCE_LENGTH;
544 if (!telemetryRxBuffer[remoteToProcessId].needsProcessing) {
545 break;
549 while (remoteToProcessIndex < telemetryRxBuffer[remoteToProcessId].data.dataLength && !payload) {
550 payload = smartPortDataReceive(telemetryRxBuffer[remoteToProcessId].data.data[remoteToProcessIndex], &clearToSend, frSkyXReadyToSend, false);
551 remoteToProcessIndex = remoteToProcessIndex + 1;
556 processSmartPortTelemetry(payload, &clearToSend, NULL);
558 return RX_SPI_RECEIVED_NONE;
560 #endif
562 uint8_t frSkyXInit(void)
564 switch(spiProtocol) {
565 case RX_SPI_FRSKY_X:
566 packetLength = FRSKY_RX_D16FCC_LENGTH;
567 telemetryDelayUs = 400;
568 break;
569 case RX_SPI_FRSKY_X_LBT:
570 packetLength = FRSKY_RX_D16LBT_LENGTH;
571 telemetryDelayUs = 1400;
572 break;
573 case RX_SPI_FRSKY_X_V2:
574 packetLength = FRSKY_RX_D16v2_LENGTH;
575 telemetryDelayUs = 400;
576 break;
577 case RX_SPI_FRSKY_X_LBT_V2:
578 packetLength = FRSKY_RX_D16v2_LENGTH;
579 telemetryDelayUs = 1500;
580 break;
581 default:
582 break;
584 #if defined(USE_TELEMETRY_SMARTPORT)
585 if (featureIsEnabled(FEATURE_TELEMETRY)) {
586 telemetryEnabled = initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame);
588 #endif
589 return packetLength;
592 #endif