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/>.
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"
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
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
{
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
{
93 uint8_t data
[TELEMETRY_DATA_SIZE
];
94 } __attribute__ ((__packed__
)) telemetryData_t
;
96 typedef struct telemetryBuffer_s
{
98 uint8_t needsProcessing
;
101 #define TELEMETRY_FRAME_SIZE sizeof(telemetryData_t)
103 typedef struct telemetryPayload_s
{
106 telemetrySequenceMarker_t sequence
;
107 telemetryData_t data
;
109 } __attribute__ ((__packed__
)) telemetryPayload_t
;
111 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
112 static telemetryData_t telemetryTxBuffer
[TELEMETRY_SEQUENCE_LENGTH
];
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;
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 word
= (*(&crcTable_Short
[val
& 0x0f]));
141 return word
^ (0x1081 * val
);
144 static uint16_t calculateCrc(const uint8_t *data
, uint8_t len
) {
146 for (unsigned i
= 0; i
< len
; i
++) {
147 crc
= (crc
<< 8) ^ crcTable((uint8_t)(crc
>> 8) ^ *data
++);
152 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
153 #if defined(USE_TELEMETRY_SMARTPORT)
154 static uint8_t appendSmartPortData(uint8_t *buf
)
156 static uint8_t telemetryOutReader
= 0;
159 for (index
= 0; index
< TELEMETRY_DATA_SIZE
; index
++) { // max 5 bytes in a frame
160 if (telemetryOutReader
== telemetryOutWriter
) { // no new data
163 buf
[index
] = telemetryOutBuffer
[telemetryOutReader
];
164 telemetryOutReader
= (telemetryOutReader
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
171 static void buildTelemetryFrame(uint8_t *packet
)
173 static uint8_t localPacketId
;
175 static bool evenRun
= false;
177 frame
[0] = 0x0E;//length
178 frame
[1] = rxCc2500SpiConfig()->bindTxId
[0];
179 frame
[2] = rxCc2500SpiConfig()->bindTxId
[1];
181 if (spiProtocol
== RX_SPI_FRSKY_X_V2
|| spiProtocol
== RX_SPI_FRSKY_X_LBT_V2
) {
182 frame
[3] = rxCc2500SpiConfig()->bindTxId
[2];
184 frame
[3] = packet
[3];
188 frame
[4] = (uint8_t)cc2500getRssiDbm() | 0x80;
191 switch (rxCc2500SpiConfig()->a1Source
) {
192 case FRSKY_SPI_A1_SOURCE_EXTADC
:
193 a1Value
= (uint8_t)((adcGetChannel(ADC_EXTERNAL1
) & 0xfe0) >> 5);
195 case FRSKY_SPI_A1_SOURCE_CONST
:
196 a1Value
= A1_CONST_X
& 0x7f;
198 case FRSKY_SPI_A1_SOURCE_VBAT
:
200 a1Value
= getLegacyBatteryVoltage() & 0x7f;
207 telemetrySequenceMarker_t
*inFrameMarker
= (telemetrySequenceMarker_t
*)&packet
[21];
208 telemetrySequenceMarker_t
*outFrameMarker
= (telemetrySequenceMarker_t
*)&frame
[5];
209 if (inFrameMarker
->data
.initRequest
) { // check syncronization at startup ok if not no sport telemetry
210 outFrameMarker
-> raw
= 0;
211 outFrameMarker
->data
.initRequest
= 1;
212 outFrameMarker
->data
.initResponse
= 1;
216 if (inFrameMarker
->data
.retransmissionRequested
) {
217 uint8_t retransmissionFrameId
= inFrameMarker
->data
.ackSequenceId
;
218 outFrameMarker
->raw
= responseToSend
.raw
& SEQUENCE_MARKER_REMOTE_PART
;
219 outFrameMarker
->data
.packetSequenceId
= retransmissionFrameId
;
221 memcpy(&frame
[6], &telemetryTxBuffer
[retransmissionFrameId
], TELEMETRY_FRAME_SIZE
);
223 uint8_t localAckId
= inFrameMarker
->data
.ackSequenceId
;
224 if (localPacketId
!= (localAckId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
) {
225 outFrameMarker
->raw
= responseToSend
.raw
& SEQUENCE_MARKER_REMOTE_PART
;
226 outFrameMarker
->data
.packetSequenceId
= localPacketId
;
228 frame
[6] = appendSmartPortData(&frame
[7]);
229 memcpy(&telemetryTxBuffer
[localPacketId
], &frame
[6], TELEMETRY_FRAME_SIZE
);
231 localPacketId
= (localPacketId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
236 uint16_t lcrc
= calculateCrc(&frame
[3], 10);
241 static bool frSkyXReadyToSend(void)
246 #if defined(USE_TELEMETRY_SMARTPORT)
247 static void frSkyXTelemetrySendByte(uint8_t c
) {
248 if (c
== FSSP_DLE
|| c
== FSSP_START_STOP
) {
249 telemetryOutBuffer
[telemetryOutWriter
] = FSSP_DLE
;
250 telemetryOutWriter
= (telemetryOutWriter
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
251 telemetryOutBuffer
[telemetryOutWriter
] = c
^ FSSP_DLE_XOR
;
252 telemetryOutWriter
= (telemetryOutWriter
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
254 telemetryOutBuffer
[telemetryOutWriter
] = c
;
255 telemetryOutWriter
= (telemetryOutWriter
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
259 static void frSkyXTelemetryWriteFrame(const smartPortPayload_t
*payload
)
261 telemetryOutBuffer
[telemetryOutWriter
] = FSSP_START_STOP
;
262 telemetryOutWriter
= (telemetryOutWriter
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
263 telemetryOutBuffer
[telemetryOutWriter
] = FSSP_SENSOR_ID1
& 0x1f;
264 telemetryOutWriter
= (telemetryOutWriter
+ 1) % TELEMETRY_OUT_BUFFER_SIZE
;
265 uint8_t *data
= (uint8_t *)payload
;
266 for (unsigned i
= 0; i
< sizeof(smartPortPayload_t
); i
++) {
267 frSkyXTelemetrySendByte(*data
++);
271 #endif // USE_RX_FRSKY_SPI_TELEMETRY
274 void frSkyXSetRcData(uint16_t *rcData
, const uint8_t *packet
)
277 // ignore failsafe packet
278 if (packet
[7] != 0) {
281 c
[0] = (uint16_t)((packet
[10] << 8) & 0xF00) | packet
[9];
282 c
[1] = (uint16_t)((packet
[11] << 4) & 0xFF0) | (packet
[10] >> 4);
283 c
[2] = (uint16_t)((packet
[13] << 8) & 0xF00) | packet
[12];
284 c
[3] = (uint16_t)((packet
[14] << 4) & 0xFF0) | (packet
[13] >> 4);
285 c
[4] = (uint16_t)((packet
[16] << 8) & 0xF00) | packet
[15];
286 c
[5] = (uint16_t)((packet
[17] << 4) & 0xFF0) | (packet
[16] >> 4);
287 c
[6] = (uint16_t)((packet
[19] << 8) & 0xF00) | packet
[18];
288 c
[7] = (uint16_t)((packet
[20] << 4) & 0xFF0) | (packet
[19] >> 4);
290 for (unsigned i
= 0; i
< 8; i
++) {
291 const bool channelIsShifted
= c
[i
] & 0x800;
292 const uint16_t channelValue
= c
[i
] & 0x7FF;
293 rcData
[channelIsShifted
? i
+ 8 : i
] = ((channelValue
- 64) * 2 + 860 * 3) / 3;
297 bool isValidPacket(const uint8_t *packet
)
299 bool useBindTxId2
= false;
301 if (spiProtocol
== RX_SPI_FRSKY_X_V2
|| spiProtocol
== RX_SPI_FRSKY_X_LBT_V2
) {
303 if (!(packet
[packetLength
- 1] & 0x80)) {
308 uint16_t lcrc
= calculateCrc(&packet
[3], (packetLength
- 7));
310 if ((lcrc
>> 8) == packet
[packetLength
- 4] && (lcrc
& 0x00FF) == packet
[packetLength
- 3] &&
311 (packet
[0] == packetLength
- 3) &&
312 (packet
[1] == rxCc2500SpiConfig()->bindTxId
[0]) &&
313 (packet
[2] == rxCc2500SpiConfig()->bindTxId
[1]) &&
314 (!useBindTxId2
|| (packet
[3] == rxCc2500SpiConfig()->bindTxId
[2])) &&
315 (rxCc2500SpiConfig()->rxNum
== 0 || packet
[6] == 0 || packet
[6] == rxCc2500SpiConfig()->rxNum
)) {
321 rx_spi_received_e
frSkyXHandlePacket(uint8_t * const packet
, uint8_t * const protocolState
)
323 static unsigned receiveTelemetryRetryCount
= 0;
324 static bool skipChannels
= true;
326 static uint8_t remoteAckId
= 0;
328 static timeUs_t packetTimerUs
;
330 static bool frameReceived
;
331 static timeDelta_t receiveDelayUs
;
332 static uint8_t channelsToSkip
= 1;
333 static uint32_t packetErrors
= 0;
335 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
336 static bool telemetryReceived
= false;
339 rx_spi_received_e ret
= RX_SPI_RECEIVED_NONE
;
341 switch (*protocolState
) {
344 initialiseData(false);
345 *protocolState
= STATE_UPDATE
;
347 cc2500Strobe(CC2500_SRX
);
350 packetTimerUs
= micros();
351 *protocolState
= STATE_DATA
;
352 frameReceived
= false; // again set for receive
353 receiveDelayUs
= 5300;
354 if (rxSpiCheckBindRequested(false)) {
358 *protocolState
= STATE_INIT
;
364 // here FS code could be
366 if (rxSpiGetExtiState() && (!frameReceived
)) {
367 uint8_t ccLen
= cc2500ReadReg(CC2500_3B_RXBYTES
| CC2500_READ_BURST
) & 0x7F;
368 if (ccLen
>= packetLength
) {
369 cc2500ReadFifo(packet
, packetLength
);
370 if (isValidPacket(packet
)) {
376 channelsToSkip
= (packet
[5] << 2) | (packet
[4] >> 6);
377 telemetryReceived
= true; // now telemetry can be sent
378 skipChannels
= false;
380 cc2500setRssiDbm(packet
[packetLength
- 2]);
382 telemetrySequenceMarker_t
*inFrameMarker
= (telemetrySequenceMarker_t
*)&packet
[21];
384 uint8_t remoteNewPacketId
= inFrameMarker
->data
.packetSequenceId
;
385 memcpy(&telemetryRxBuffer
[remoteNewPacketId
].data
, &packet
[22], TELEMETRY_FRAME_SIZE
);
386 telemetryRxBuffer
[remoteNewPacketId
].needsProcessing
= true;
388 responseToSend
.raw
= 0;
389 uint8_t remoteToAckId
= (remoteAckId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
390 if (remoteNewPacketId
!= remoteToAckId
) {
391 while (remoteToAckId
!= remoteNewPacketId
) {
392 if (!telemetryRxBuffer
[remoteToAckId
].needsProcessing
) {
393 responseToSend
.data
.ackSequenceId
= remoteToAckId
;
394 responseToSend
.data
.retransmissionRequested
= 1;
396 receiveTelemetryRetryCount
++;
401 remoteToAckId
= (remoteToAckId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
405 if (!responseToSend
.data
.retransmissionRequested
) {
406 receiveTelemetryRetryCount
= 0;
408 remoteToAckId
= (remoteAckId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
409 uint8_t remoteNextAckId
= remoteToAckId
;
410 while (telemetryRxBuffer
[remoteToAckId
].needsProcessing
&& remoteToAckId
!= remoteAckId
) {
411 remoteNextAckId
= remoteToAckId
;
412 remoteToAckId
= (remoteToAckId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
414 remoteAckId
= remoteNextAckId
;
415 responseToSend
.data
.ackSequenceId
= remoteAckId
;
418 if (receiveTelemetryRetryCount
>= 5) {
419 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
420 remoteToProcessId
= 0;
421 remoteToProcessIndex
= 0;
423 remoteAckId
= TELEMETRY_SEQUENCE_LENGTH
- 1;
424 for (unsigned i
= 0; i
< TELEMETRY_SEQUENCE_LENGTH
; i
++) {
425 telemetryRxBuffer
[i
].needsProcessing
= false;
428 receiveTelemetryRetryCount
= 0;
431 packetTimerUs
= micros();
432 frameReceived
= true; // no need to process frame again.
434 if (!frameReceived
) {
436 DEBUG_SET(DEBUG_RX_FRSKY_SPI
, DEBUG_DATA_BAD_FRAME
, packetErrors
);
437 cc2500Strobe(CC2500_SFRX
);
441 if (telemetryReceived
) {
442 if (cmpTimeUs(micros(), packetTimerUs
) > receiveDelayUs
) { // if received or not received in this time sent telemetry data
443 *protocolState
= STATE_TELEMETRY
;
444 buildTelemetryFrame(packet
);
447 if (cmpTimeUs(micros(), packetTimerUs
) > timeoutUs
* SYNC_DELAY_MAX
) {
450 setRssiDirect(0, RSSI_SOURCE_RX_PROTOCOL
);
452 cc2500Strobe(CC2500_SRX
);
453 *protocolState
= STATE_UPDATE
;
456 ret
|= RX_SPI_RECEIVED_DATA
;
458 frameReceived
= false;
462 #ifdef USE_RX_FRSKY_SPI_TELEMETRY
463 case STATE_TELEMETRY
:
464 if (cmpTimeUs(micros(), packetTimerUs
) >= receiveDelayUs
+ telemetryDelayUs
) { // if received or not received in this time sent telemetry data
465 cc2500Strobe(CC2500_SIDLE
);
467 cc2500Strobe(CC2500_SFRX
);
468 delayMicroseconds(30);
469 #if defined(USE_RX_CC2500_SPI_PA_LNA)
472 cc2500Strobe(CC2500_SIDLE
);
473 cc2500WriteFifo(frame
, frame
[0] + 1);
475 #if defined(USE_TELEMETRY_SMARTPORT)
476 if (telemetryEnabled
) {
477 ret
|= RX_SPI_ROCESSING_REQUIRED
;
480 *protocolState
= STATE_RESUME
;
484 #endif // USE_RX_FRSKY_SPI_TELEMETRY
486 if (cmpTimeUs(micros(), packetTimerUs
) > receiveDelayUs
+ 3700) {
487 packetTimerUs
= micros();
488 receiveDelayUs
= 5300;
489 frameReceived
= false; // again set for receive
490 nextChannel(channelsToSkip
);
491 cc2500Strobe(CC2500_SRX
);
492 #ifdef USE_RX_CC2500_SPI_PA_LNA
494 #if defined(USE_RX_CC2500_SPI_DIVERSITY)
495 if (missingPackets
>= 2) {
496 cc2500switchAntennae();
499 #endif // USE_RX_CC2500_SPI_PA_LNA
500 if (missingPackets
> MAX_MISSING_PKT
) {
503 telemetryReceived
= false;
504 *protocolState
= STATE_UPDATE
;
508 DEBUG_SET(DEBUG_RX_FRSKY_SPI
, DEBUG_DATA_MISSING_PACKETS
, missingPackets
);
509 *protocolState
= STATE_DATA
;
517 #if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
518 rx_spi_received_e
frSkyXProcessFrame(uint8_t * const packet
)
520 static timeMs_t pollingTimeMs
= 0;
524 bool clearToSend
= false;
525 timeMs_t now
= millis();
526 smartPortPayload_t
*payload
= NULL
;
527 if ((now
- pollingTimeMs
) > 24) {
532 while (telemetryRxBuffer
[remoteToProcessId
].needsProcessing
&& !payload
) {
533 if (remoteToProcessIndex
>= telemetryRxBuffer
[remoteToProcessId
].data
.dataLength
) {
534 remoteToProcessIndex
= 0;
535 telemetryRxBuffer
[remoteToProcessId
].needsProcessing
= false;
536 remoteToProcessId
= (remoteToProcessId
+ 1) % TELEMETRY_SEQUENCE_LENGTH
;
538 if (!telemetryRxBuffer
[remoteToProcessId
].needsProcessing
) {
543 while (remoteToProcessIndex
< telemetryRxBuffer
[remoteToProcessId
].data
.dataLength
&& !payload
) {
544 payload
= smartPortDataReceive(telemetryRxBuffer
[remoteToProcessId
].data
.data
[remoteToProcessIndex
], &clearToSend
, frSkyXReadyToSend
, false);
545 remoteToProcessIndex
= remoteToProcessIndex
+ 1;
550 processSmartPortTelemetry(payload
, &clearToSend
, NULL
);
552 return RX_SPI_RECEIVED_NONE
;
556 uint8_t frSkyXInit(void)
558 switch(spiProtocol
) {
560 packetLength
= FRSKY_RX_D16FCC_LENGTH
;
561 telemetryDelayUs
= 400;
563 case RX_SPI_FRSKY_X_LBT
:
564 packetLength
= FRSKY_RX_D16LBT_LENGTH
;
565 telemetryDelayUs
= 1400;
567 case RX_SPI_FRSKY_X_V2
:
568 packetLength
= FRSKY_RX_D16v2_LENGTH
;
569 telemetryDelayUs
= 400;
571 case RX_SPI_FRSKY_X_LBT_V2
:
572 packetLength
= FRSKY_RX_D16v2_LENGTH
;
573 telemetryDelayUs
= 1500;
578 #if defined(USE_TELEMETRY_SMARTPORT)
579 if (featureIsEnabled(FEATURE_TELEMETRY
)) {
580 telemetryEnabled
= initSmartPortTelemetryExternal(frSkyXTelemetryWriteFrame
);