If RSSI Channel is set to Disabled when using S.Bus then generate RSS… (#5090)
[betaflight.git] / src / main / rx / cc2500_frsky_shared.c
blob3714a1641112ea024e41e50199adaf7e7ad7f090
1 /*
2 * This file is part of Cleanflight.
4 * Cleanflight is free software: you can redistribute it and/or modify
5 * it under the terms of the GNU General Public License as published by
6 * the Free Software Foundation, either version 3 of the License, or
7 * (at your option) any later version.
9 * Cleanflight is distributed in the hope that it will be useful,
10 * but WITHOUT ANY WARRANTY; without even the implied warranty of
11 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
12 * GNU General Public License for more details.
14 * You should have received a copy of the GNU General Public License
15 * along with Cleanflight. If not, see <http://www.gnu.org/licenses/>.
18 #include <stdbool.h>
20 #include "platform.h"
22 #ifdef USE_RX_FRSKY_SPI
24 #include "common/maths.h"
26 #include "drivers/rx/rx_cc2500.h"
27 #include "drivers/io.h"
28 #include "drivers/time.h"
30 #include "fc/config.h"
32 #include "pg/pg.h"
33 #include "pg/pg_ids.h"
35 #include "rx/rx.h"
36 #include "rx/rx_spi.h"
38 #include "rx/cc2500_frsky_common.h"
39 #include "rx/cc2500_frsky_d.h"
40 #include "rx/cc2500_frsky_x.h"
42 #include "cc2500_frsky_shared.h"
44 static rx_spi_protocol_e spiProtocol;
46 static timeMs_t start_time;
47 static uint8_t protocolState;
49 uint32_t missingPackets;
50 timeDelta_t timeoutUs;
52 static uint8_t calData[255][3];
53 static timeMs_t timeTunedMs;
54 uint8_t listLength;
55 static uint8_t bindIdx;
56 static int8_t bindOffset;
57 static bool lastBindPinStatus;
59 static bool bindRequested;
61 typedef uint8_t handlePacketFn(uint8_t * const packet, uint8_t * const protocolState);
62 typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload);
64 static handlePacketFn *handlePacket;
65 static setRcDataFn *setRcData;
67 IO_t gdoPin;
68 static IO_t bindPin = DEFIO_IO(NONE);
69 static IO_t frSkyLedPin;
71 #if defined(USE_RX_FRSKY_SPI_PA_LNA)
72 static IO_t txEnPin;
73 static IO_t rxLnaEnPin;
74 static IO_t antSelPin;
75 #endif
77 #ifdef USE_RX_FRSKY_SPI_TELEMETRY
78 int16_t rssiDbm;
79 #endif
81 PG_REGISTER_WITH_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig, PG_RX_FRSKY_SPI_CONFIG, 0);
83 PG_RESET_TEMPLATE(rxFrSkySpiConfig_t, rxFrSkySpiConfig,
84 .autoBind = false,
85 .bindTxId = {0, 0},
86 .bindOffset = 0,
87 .bindHopData = {0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
88 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
89 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0,
90 0, 0, 0, 0, 0, 0, 0, 0, 0, 0, 0},
91 .rxNum = 0,
94 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
95 void setRssiDbm(uint8_t value)
97 if (value >= 128) {
98 rssiDbm = ((((uint16_t)value) * 18) >> 5) - 82;
99 } else {
100 rssiDbm = ((((uint16_t)value) * 18) >> 5) + 65;
103 setRssiUnfiltered(constrain(rssiDbm << 3, 0, 1023), RSSI_SOURCE_RX_PROTOCOL);
105 #endif // USE_RX_FRSKY_SPI_TELEMETRY
107 #if defined(USE_RX_FRSKY_SPI_PA_LNA)
108 void TxEnable(void)
110 IOHi(txEnPin);
113 void TxDisable(void)
115 IOLo(txEnPin);
117 #endif
119 void LedOn(void)
121 #if defined(RX_FRSKY_SPI_LED_PIN_INVERTED)
122 IOLo(frSkyLedPin);
123 #else
124 IOHi(frSkyLedPin);
125 #endif
128 void LedOff(void)
130 #if defined(RX_FRSKY_SPI_LED_PIN_INVERTED)
131 IOHi(frSkyLedPin);
132 #else
133 IOLo(frSkyLedPin);
134 #endif
137 void frSkySpiBind(void)
139 bindRequested = true;
142 static void initialise() {
143 cc2500Reset();
144 cc2500WriteReg(CC2500_02_IOCFG0, 0x01);
145 cc2500WriteReg(CC2500_17_MCSM1, 0x0C);
146 cc2500WriteReg(CC2500_18_MCSM0, 0x18);
147 cc2500WriteReg(CC2500_07_PKTCTRL1, 0x04);
148 cc2500WriteReg(CC2500_3E_PATABLE, 0xFF);
149 cc2500WriteReg(CC2500_0C_FSCTRL0, 0x00);
150 cc2500WriteReg(CC2500_0D_FREQ2, 0x5C);
151 cc2500WriteReg(CC2500_0E_FREQ1, 0x76);
152 cc2500WriteReg(CC2500_0F_FREQ0, 0x27);
153 cc2500WriteReg(CC2500_13_MDMCFG1, 0x23);
154 cc2500WriteReg(CC2500_14_MDMCFG0, 0x7A);
155 cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
156 cc2500WriteReg(CC2500_1A_BSCFG, 0x6C);
157 cc2500WriteReg(CC2500_1B_AGCCTRL2, 0x03);
158 cc2500WriteReg(CC2500_1C_AGCCTRL1, 0x40);
159 cc2500WriteReg(CC2500_1D_AGCCTRL0, 0x91);
160 cc2500WriteReg(CC2500_21_FREND1, 0x56);
161 cc2500WriteReg(CC2500_22_FREND0, 0x10);
162 cc2500WriteReg(CC2500_23_FSCAL3, 0xA9);
163 cc2500WriteReg(CC2500_24_FSCAL2, 0x0A);
164 cc2500WriteReg(CC2500_25_FSCAL1, 0x00);
165 cc2500WriteReg(CC2500_26_FSCAL0, 0x11);
166 cc2500WriteReg(CC2500_29_FSTEST, 0x59);
167 cc2500WriteReg(CC2500_2C_TEST2, 0x88);
168 cc2500WriteReg(CC2500_2D_TEST1, 0x31);
169 cc2500WriteReg(CC2500_2E_TEST0, 0x0B);
170 cc2500WriteReg(CC2500_03_FIFOTHR, 0x07);
171 cc2500WriteReg(CC2500_09_ADDR, 0x00);
173 switch (spiProtocol) {
174 case RX_SPI_FRSKY_D:
175 cc2500WriteReg(CC2500_06_PKTLEN, 0x19);
176 cc2500WriteReg(CC2500_08_PKTCTRL0, 0x05);
177 cc2500WriteReg(CC2500_0B_FSCTRL1, 0x08);
178 cc2500WriteReg(CC2500_10_MDMCFG4, 0xAA);
179 cc2500WriteReg(CC2500_11_MDMCFG3, 0x39);
180 cc2500WriteReg(CC2500_12_MDMCFG2, 0x11);
181 cc2500WriteReg(CC2500_15_DEVIATN, 0x42);
183 break;
184 case RX_SPI_FRSKY_X:
185 cc2500WriteReg(CC2500_06_PKTLEN, 0x1E);
186 cc2500WriteReg(CC2500_08_PKTCTRL0, 0x01);
187 cc2500WriteReg(CC2500_0B_FSCTRL1, 0x0A);
188 cc2500WriteReg(CC2500_10_MDMCFG4, 0x7B);
189 cc2500WriteReg(CC2500_11_MDMCFG3, 0x61);
190 cc2500WriteReg(CC2500_12_MDMCFG2, 0x13);
191 cc2500WriteReg(CC2500_15_DEVIATN, 0x51);
193 break;
194 default:
196 break;
199 for(unsigned c = 0;c < 0xFF; c++)
200 { //calibrate all channels
201 cc2500Strobe(CC2500_SIDLE);
202 cc2500WriteReg(CC2500_0A_CHANNR, c);
203 cc2500Strobe(CC2500_SCAL);
204 delayMicroseconds(900); //
205 calData[c][0] = cc2500ReadReg(CC2500_23_FSCAL3);
206 calData[c][1] = cc2500ReadReg(CC2500_24_FSCAL2);
207 calData[c][2] = cc2500ReadReg(CC2500_25_FSCAL1);
211 void initialiseData(uint8_t adr)
213 cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)rxFrSkySpiConfig()->bindOffset);
214 cc2500WriteReg(CC2500_18_MCSM0, 0x8);
215 cc2500WriteReg(CC2500_09_ADDR, adr ? 0x03 : rxFrSkySpiConfig()->bindTxId[0]);
216 cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0D);
217 cc2500WriteReg(CC2500_19_FOCCFG, 0x16);
218 delay(10);
221 static void initTuneRx(void)
223 cc2500WriteReg(CC2500_19_FOCCFG, 0x14);
224 timeTunedMs = millis();
225 bindOffset = -126;
226 cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
227 cc2500WriteReg(CC2500_07_PKTCTRL1, 0x0C);
228 cc2500WriteReg(CC2500_18_MCSM0, 0x8);
230 cc2500Strobe(CC2500_SIDLE);
231 cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]);
232 cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]);
233 cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]);
234 cc2500WriteReg(CC2500_0A_CHANNR, 0);
235 cc2500Strobe(CC2500_SFRX);
236 cc2500Strobe(CC2500_SRX);
239 static bool tuneRx(uint8_t *packet)
241 if (bindOffset >= 126) {
242 bindOffset = -126;
244 if ((millis() - timeTunedMs) > 50) {
245 timeTunedMs = millis();
246 bindOffset += 5;
247 cc2500WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
249 if (IORead(gdoPin)) {
250 uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
251 if (ccLen) {
252 cc2500ReadFifo(packet, ccLen);
253 if (packet[ccLen - 1] & 0x80) {
254 if (packet[2] == 0x01) {
255 uint8_t Lqi = packet[ccLen - 1] & 0x7F;
256 if (Lqi < 50) {
257 rxFrSkySpiConfigMutable()->bindOffset = bindOffset;
259 return true;
266 return false;
269 static void initGetBind(void)
271 cc2500Strobe(CC2500_SIDLE);
272 cc2500WriteReg(CC2500_23_FSCAL3, calData[0][0]);
273 cc2500WriteReg(CC2500_24_FSCAL2, calData[0][1]);
274 cc2500WriteReg(CC2500_25_FSCAL1, calData[0][2]);
275 cc2500WriteReg(CC2500_0A_CHANNR, 0);
276 cc2500Strobe(CC2500_SFRX);
277 delayMicroseconds(20); // waiting flush FIFO
279 cc2500Strobe(CC2500_SRX);
280 listLength = 0;
281 bindIdx = 0x05;
284 static bool getBind1(uint8_t *packet)
286 // len|bind |tx
287 // id|03|01|idx|h0|h1|h2|h3|h4|00|00|00|00|00|00|00|00|00|00|00|00|00|00|00|CHK1|CHK2|RSSI|LQI/CRC|
288 // Start by getting bind packet 0 and the txid
289 if (IORead(gdoPin)) {
290 uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
291 if (ccLen) {
292 cc2500ReadFifo(packet, ccLen);
293 if (packet[ccLen - 1] & 0x80) {
294 if (packet[2] == 0x01) {
295 if (packet[5] == 0x00) {
296 rxFrSkySpiConfigMutable()->bindTxId[0] = packet[3];
297 rxFrSkySpiConfigMutable()->bindTxId[1] = packet[4];
298 for (uint8_t n = 0; n < 5; n++) {
299 rxFrSkySpiConfigMutable()->bindHopData[packet[5] + n] =
300 packet[6 + n];
303 rxFrSkySpiConfigMutable()->rxNum = packet[12];
305 return true;
312 return false;
315 static bool getBind2(uint8_t *packet)
317 if (bindIdx <= 120) {
318 if (IORead(gdoPin)) {
319 uint8_t ccLen = cc2500ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x7F;
320 if (ccLen) {
321 cc2500ReadFifo(packet, ccLen);
322 if (packet[ccLen - 1] & 0x80) {
323 if (packet[2] == 0x01) {
324 if ((packet[3] == rxFrSkySpiConfig()->bindTxId[0]) &&
325 (packet[4] == rxFrSkySpiConfig()->bindTxId[1])) {
326 if (packet[5] == bindIdx) {
327 #if defined(DJTS)
328 if (packet[5] == 0x2D) {
329 for (uint8_t i = 0; i < 2; i++) {
330 rxFrSkySpiConfigMutable()->bindHopData[packet[5] + i] = packet[6 + i];
332 listLength = 47;
334 return true;
336 #endif
338 for (uint8_t n = 0; n < 5; n++) {
339 if (packet[6 + n] == packet[ccLen - 3] || (packet[6 + n] == 0)) {
340 if (bindIdx >= 0x2D) {
341 listLength = packet[5] + n;
343 return true;
347 rxFrSkySpiConfigMutable()->bindHopData[packet[5] + n] = packet[6 + n];
350 bindIdx = bindIdx + 5;
352 return false;
360 return false;
361 } else {
362 return true;
366 bool checkBindRequested(bool reset)
368 if (bindPin) {
369 bool bindPinStatus = IORead(bindPin);
370 if (lastBindPinStatus && !bindPinStatus) {
371 bindRequested = true;
373 lastBindPinStatus = bindPinStatus;
376 if (!bindRequested) {
377 return false;
378 } else {
379 if (reset) {
380 bindRequested = false;
383 return true;
387 rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
389 rx_spi_received_e ret = RX_SPI_RECEIVED_NONE;
391 switch (protocolState) {
392 case STATE_INIT:
393 if ((millis() - start_time) > 10) {
394 initialise();
396 protocolState = STATE_BIND;
399 break;
400 case STATE_BIND:
401 if (checkBindRequested(true) || rxFrSkySpiConfig()->autoBind) {
402 LedOn();
403 initTuneRx();
405 protocolState = STATE_BIND_TUNING;
406 } else {
407 protocolState = STATE_STARTING;
410 break;
411 case STATE_BIND_TUNING:
412 if (tuneRx(packet)) {
413 initGetBind();
414 initialiseData(1);
416 protocolState = STATE_BIND_BINDING1;
419 break;
420 case STATE_BIND_BINDING1:
421 if (getBind1(packet)) {
422 protocolState = STATE_BIND_BINDING2;
425 break;
426 case STATE_BIND_BINDING2:
427 if (getBind2(packet)) {
428 cc2500Strobe(CC2500_SIDLE);
430 protocolState = STATE_BIND_COMPLETE;
433 break;
434 case STATE_BIND_COMPLETE:
435 if (!rxFrSkySpiConfig()->autoBind) {
436 writeEEPROM();
437 } else {
438 uint8_t ctr = 40;
439 while (ctr--) {
440 LedOn();
441 delay(50);
442 LedOff();
443 delay(50);
447 ret = RX_SPI_RECEIVED_BIND;
448 protocolState = STATE_STARTING;
450 break;
451 default:
452 ret = handlePacket(packet, &protocolState);
454 break;
457 return ret;
460 void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload)
462 setRcData(rcData, payload);
465 void nextChannel(uint8_t skip)
467 static uint8_t channr = 0;
469 channr += skip;
470 while (channr >= listLength) {
471 channr -= listLength;
473 cc2500Strobe(CC2500_SIDLE);
474 cc2500WriteReg(CC2500_23_FSCAL3,
475 calData[rxFrSkySpiConfig()->bindHopData[channr]][0]);
476 cc2500WriteReg(CC2500_24_FSCAL2,
477 calData[rxFrSkySpiConfig()->bindHopData[channr]][1]);
478 cc2500WriteReg(CC2500_25_FSCAL1,
479 calData[rxFrSkySpiConfig()->bindHopData[channr]][2]);
480 cc2500WriteReg(CC2500_0A_CHANNR, rxFrSkySpiConfig()->bindHopData[channr]);
481 if (spiProtocol == RX_SPI_FRSKY_D) {
482 cc2500Strobe(CC2500_SFRX);
486 #if defined(USE_RX_FRSKY_SPI_PA_LNA) && defined(USE_RX_FRSKY_SPI_DIVERSITY)
487 void switchAntennae(void)
489 static bool alternativeAntennaSelected = true;
491 if (alternativeAntennaSelected) {
492 IOLo(antSelPin);
493 } else {
494 IOHi(antSelPin);
496 alternativeAntennaSelected = !alternativeAntennaSelected;
498 #endif
500 static bool frSkySpiDetect(void)
502 const uint8_t chipPartNum = cc2500ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST); //CC2500 read registers chip part num
503 const uint8_t chipVersion = cc2500ReadReg(CC2500_31_VERSION | CC2500_READ_BURST); //CC2500 read registers chip version
504 if (chipPartNum == 0x80 && chipVersion == 0x03) {
505 return true;
508 return false;
511 bool frSkySpiInit(const rxConfig_t *rxConfig, rxRuntimeConfig_t *rxRuntimeConfig)
513 #if !defined(RX_FRSKY_SPI_DISABLE_CHIP_DETECTION)
514 if (!frSkySpiDetect()) {
515 return false;
517 #else
518 UNUSED(frSkySpiDetect);
519 #endif
521 spiProtocol = rxConfig->rx_spi_protocol;
523 switch (spiProtocol) {
524 case RX_SPI_FRSKY_D:
525 rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_D;
527 handlePacket = frSkyDHandlePacket;
528 setRcData = frSkyDSetRcData;
529 frSkyDInit();
531 break;
532 case RX_SPI_FRSKY_X:
533 rxRuntimeConfig->channelCount = RC_CHANNEL_COUNT_FRSKY_X;
535 handlePacket = frSkyXHandlePacket;
536 setRcData = frSkyXSetRcData;
537 frSkyXInit();
539 break;
540 default:
542 break;
545 #if defined(USE_RX_FRSKY_SPI_TELEMETRY)
546 if (rssiSource == RSSI_SOURCE_NONE) {
547 rssiSource = RSSI_SOURCE_RX_PROTOCOL;
549 #endif
551 // gpio init here
552 gdoPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_GDO_0_PIN));
553 IOInit(gdoPin, OWNER_RX_SPI, 0);
554 IOConfigGPIO(gdoPin, IOCFG_IN_FLOATING);
555 frSkyLedPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_LED_PIN));
556 IOInit(frSkyLedPin, OWNER_LED, 0);
557 IOConfigGPIO(frSkyLedPin, IOCFG_OUT_PP);
558 #if defined(USE_RX_FRSKY_SPI_PA_LNA)
559 rxLnaEnPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_LNA_EN_PIN));
560 IOInit(rxLnaEnPin, OWNER_RX_SPI, 0);
561 IOConfigGPIO(rxLnaEnPin, IOCFG_OUT_PP);
562 IOHi(rxLnaEnPin); // always on at the moment
563 txEnPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_TX_EN_PIN));
564 IOInit(txEnPin, OWNER_RX_SPI, 0);
565 IOConfigGPIO(txEnPin, IOCFG_OUT_PP);
566 #if defined(USE_RX_FRSKY_SPI_DIVERSITY)
567 antSelPin = IOGetByTag(IO_TAG(RX_FRSKY_SPI_ANT_SEL_PIN));
568 IOInit(antSelPin, OWNER_RX_SPI, 0);
569 IOConfigGPIO(antSelPin, IOCFG_OUT_PP);
570 #endif
571 #endif // USE_RX_FRSKY_SPI_PA_LNA
572 #if defined(BINDPLUG_PIN)
573 bindPin = IOGetByTag(IO_TAG(BINDPLUG_PIN));
574 IOInit(bindPin, OWNER_RX_BIND, 0);
575 IOConfigGPIO(bindPin, IOCFG_IPU);
577 lastBindPinStatus = IORead(bindPin);
578 #endif
580 #if defined(USE_RX_FRSKY_SPI_PA_LNA)
581 #if defined(USE_RX_FRSKY_SPI_DIVERSITY)
582 IOHi(antSelPin);
583 #endif
584 TxDisable();
585 #endif // USE_RX_FRSKY_SPI_PA_LNA
587 missingPackets = 0;
588 timeoutUs = 50;
590 start_time = millis();
591 protocolState = STATE_INIT;
593 return true;
595 #endif