Paparazzi UAS v7.0_unstable
Paparazzi is a free software Unmanned Aircraft System.
All Data Structures Namespaces Files Functions Variables Typedefs Enumerations Enumerator Macros Modules Pages
cc2500_frsky_shared.c
Go to the documentation of this file.
1#include "cc2500_compat.h"
2
4#include "cc2500_settings.h"
6#include "cc2500_common.h"
8#include "cc2500_frsky_d.h"
9#include "cc2500_frsky_x.h"
10#include "cc2500_frsky_shared.h"
11
12// betaflight/src/main/rx/cc2500_frsky_shared.c @ 766c90b
13/*
14 * This file is part of Cleanflight and Betaflight.
15 *
16 * Cleanflight and Betaflight are free software. You can redistribute
17 * this software and/or modify this software under the terms of the
18 * GNU General Public License as published by the Free Software
19 * Foundation, either version 3 of the License, or (at your option)
20 * any later version.
21 *
22 * Cleanflight and Betaflight are distributed in the hope that they
23 * will be useful, but WITHOUT ANY WARRANTY; without even the implied
24 * warranty of MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
25 * See the GNU General Public License for more details.
26 *
27 * You should have received a copy of the GNU General Public License
28 * along with this software.
29 *
30 * If not, see <http://www.gnu.org/licenses/>.
31 */
32
33#include <stdbool.h>
34
35//#include "platform.h"
36
37#ifdef USE_RX_FRSKY_SPI
38
39//#include "common/maths.h"
40//
41//#include "drivers/rx/rx_cc2500.h"
42//#include "drivers/io.h"
43//#include "drivers/time.h"
44//
45//#include "fc/config.h"
46//
47//#include "pg/rx.h"
48//#include "pg/rx_spi.h"
49//#include "pg/rx_spi_cc2500.h"
50//
51//#include "rx/rx.h"
52//#include "rx/rx_spi.h"
53//#include "rx/rx_spi_common.h"
54//
55//#include "rx/cc2500_common.h"
56//#include "rx/cc2500_frsky_common.h"
57//#include "rx/cc2500_frsky_d.h"
58//#include "rx/cc2500_frsky_x.h"
59//
60//#include "cc2500_frsky_shared.h"
61
63
66
69
70static uint8_t calData[255][3];
75
78typedef void setRcDataFn(uint16_t *rcData, const uint8_t *payload);
79
83
84static void initialise() {
111
112 switch (spiProtocol) {
113 case RX_SPI_FRSKY_D:
124
125 break;
126 case RX_SPI_FRSKY_X:
137
138 break;
150
151 break;
152 default:
153
154 break;
155 }
156
157 for(unsigned c = 0;c < 0xFF; c++)
158 { //calibrate all channels
162 delayMicroseconds(900); //
166 }
167}
168
181
199
200static bool tuneRx(uint8_t *packet)
201{
202 if (bindOffset >= 126) {
203 bindOffset = -126;
204 }
205 if ((millis() - timeTunedMs) > 50) {
207 bindOffset += 5;
209 }
210 if (cc2500getGdo()) {
212 if (ccLen) {
214 if (packet[ccLen - 1] & 0x80) {
215 if (packet[2] == 0x01) {
216 uint8_t Lqi = packet[ccLen - 1] & 0x7F;
217 // higher lqi represent better link quality
218 if (Lqi > 50) {
220 return true;
221 }
222 }
223 }
224 }
225 }
226
227 return false;
228}
229
244
246{
247 // len|bind |tx
248 // 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|
249 // Start by getting bind packet 0 and the txid
250 if (cc2500getGdo()) {
252 if (ccLen) {
254 if (packet[ccLen - 1] & 0x80) {
255 if (packet[2] == 0x01) {
256 if (packet[5] == 0x00) {
259 for (uint8_t n = 0; n < 5; n++) {
261 packet[6 + n];
262 }
263
265
266 return true;
267 }
268 }
269 }
270 }
271 }
272
273 return false;
274}
275
277{
278 if (bindIdx <= 120) {
279 if (cc2500getGdo()) {
281 if (ccLen) {
283 if (packet[ccLen - 1] & 0x80) {
284 if (packet[2] == 0x01) {
285 if ((packet[3] == rxCc2500SpiConfig()->bindTxId[0]) &&
286 (packet[4] == rxCc2500SpiConfig()->bindTxId[1])) {
287 if (packet[5] == bindIdx) {
288#if defined(DJTS)
289 if (packet[5] == 0x2D) {
290 for (uint8_t i = 0; i < 2; i++) {
292 }
293 listLength = 47;
294
295 return true;
296 }
297#endif
298
299 for (uint8_t n = 0; n < 5; n++) {
300 if (packet[6 + n] == packet[ccLen - 3] || (packet[6 + n] == 0)) {
301 if (bindIdx >= 0x2D) {
302 listLength = packet[5] + n;
303
304 return true;
305 }
306 }
307
309 }
310
311 bindIdx = bindIdx + 5;
312
313 return false;
314 }
315 }
316 }
317 }
318 }
319 }
320
321 return false;
322 } else {
323 return true;
324 }
325}
326
328{
330
331 switch (protocolState) {
332 case STATE_INIT:
333 if ((millis() - start_time) > 10) {
334 initialise();
335
337 }
338
339 break;
340 case STATE_BIND:
341 if (rxSpiCheckBindRequested(true) || rxCc2500SpiConfig()->autoBind) {
342 rxSpiLedOn();
343 initTuneRx();
344
346 } else {
348 }
349
350 break;
352 if (tuneRx(packet)) {
353 initGetBind();
354 initialiseData(true);
355
357 }
358
359 break;
361 if (getBind1(packet)) {
363 }
364
365 break;
367 if (getBind2(packet)) {
369
371 }
372
373 break;
375 if (!rxCc2500SpiConfig()->autoBind) {
376 writeEEPROM();
377 } else {
378 uint8_t ctr = 80;
379 while (ctr--) {
381 delay(50);
382 }
383 }
384
387
388 break;
389 default:
391
392 break;
393 }
394
395 return ret;
396}
397
406
408{
409 setRcData(rcData, payload);
410}
411
413{
414 static uint8_t channr = 0;
415
416 channr += skip;
417 while (channr >= listLength) {
419 }
422 calData[rxCc2500SpiConfig()->bindHopData[channr]][0]);
424 calData[rxCc2500SpiConfig()->bindHopData[channr]][1]);
426 calData[rxCc2500SpiConfig()->bindHopData[channr]][2]);
430 }
431}
432
434{
436 if (!cc2500SpiInit()) {
437 return false;
438 }
439
441
442 switch (spiProtocol) {
443 case RX_SPI_FRSKY_D:
445
448 frSkyDInit();
449
450 break;
451 case RX_SPI_FRSKY_X:
454
456#if defined(USE_RX_FRSKY_SPI_TELEMETRY) && defined(USE_TELEMETRY_SMARTPORT)
458#endif
461
462 break;
463 default:
464
465 break;
466 }
467
468#if defined(USE_RX_FRSKY_SPI_TELEMETRY)
471 }
472#endif
473
474 missingPackets = 0;
475 timeoutUs = 50;
476
477 start_time = millis();
479
480 return true;
481}
482#endif
void cc2500WriteReg(uint8_t address, uint8_t data)
Definition cc2500.c:206
void cc2500ReadFifo(uint8_t *dpbuffer, uint8_t len)
Definition cc2500.c:174
uint8_t cc2500ReadReg(uint8_t reg)
Definition cc2500.c:199
void cc2500Strobe(uint8_t address)
Definition cc2500.c:204
uint8_t cc2500Reset(void)
Definition cc2500.c:228
#define CC2500_SIDLE
Definition cc2500.h:155
#define CC2500_SFRX
Definition cc2500.h:161
#define CC2500_SRX
Definition cc2500.h:148
#define CC2500_SCAL
Definition cc2500.h:146
#define CC2500_READ_BURST
Definition cc2500.h:137
@ CC2500_1B_AGCCTRL2
Definition cc2500.h:92
@ CC2500_08_PKTCTRL0
Definition cc2500.h:73
@ CC2500_1D_AGCCTRL0
Definition cc2500.h:94
@ CC2500_2C_TEST2
Definition cc2500.h:109
@ CC2500_03_FIFOTHR
Definition cc2500.h:68
@ CC2500_13_MDMCFG1
Definition cc2500.h:84
@ CC2500_17_MCSM1
Definition cc2500.h:88
@ CC2500_23_FSCAL3
Definition cc2500.h:100
@ CC2500_22_FREND0
Definition cc2500.h:99
@ CC2500_3E_PATABLE
Definition cc2500.h:128
@ CC2500_0A_CHANNR
Definition cc2500.h:75
@ CC2500_12_MDMCFG2
Definition cc2500.h:83
@ CC2500_10_MDMCFG4
Definition cc2500.h:81
@ CC2500_18_MCSM0
Definition cc2500.h:89
@ CC2500_1A_BSCFG
Definition cc2500.h:91
@ CC2500_02_IOCFG0
Definition cc2500.h:67
@ CC2500_0E_FREQ1
Definition cc2500.h:79
@ CC2500_0C_FSCTRL0
Definition cc2500.h:77
@ CC2500_07_PKTCTRL1
Definition cc2500.h:72
@ CC2500_1C_AGCCTRL1
Definition cc2500.h:93
@ CC2500_0B_FSCTRL1
Definition cc2500.h:76
@ CC2500_0F_FREQ0
Definition cc2500.h:80
@ CC2500_25_FSCAL1
Definition cc2500.h:102
@ CC2500_3B_RXBYTES
Definition cc2500.h:125
@ CC2500_19_FOCCFG
Definition cc2500.h:90
@ CC2500_29_FSTEST
Definition cc2500.h:106
@ CC2500_11_MDMCFG3
Definition cc2500.h:82
@ CC2500_21_FREND1
Definition cc2500.h:98
@ CC2500_06_PKTLEN
Definition cc2500.h:71
@ CC2500_2E_TEST0
Definition cc2500.h:111
@ CC2500_09_ADDR
Definition cc2500.h:74
@ CC2500_24_FSCAL2
Definition cc2500.h:101
@ CC2500_14_MDMCFG0
Definition cc2500.h:85
@ CC2500_26_FSCAL0
Definition cc2500.h:103
@ CC2500_15_DEVIATN
Definition cc2500.h:86
@ CC2500_2D_TEST1
Definition cc2500.h:110
@ CC2500_0D_FREQ2
Definition cc2500.h:78
bool cc2500SpiInit(void)
bool cc2500getGdo(void)
uint32_t timeMs_t
#define delayMicroseconds(us)
int32_t timeDelta_t
#define millis()
#define delay(ms)
static void frSkyDSetRcData(uint16_t *rcData, const uint8_t *payload)
static rx_spi_received_e frSkyDHandlePacket(uint8_t *const packet, uint8_t *const protocolState)
#define RC_CHANNEL_COUNT_FRSKY_D
static void frSkyDInit(void)
static bool tuneRx(uint8_t *packet)
rx_spi_received_e frSkySpiDataReceived(uint8_t *packet)
timeDelta_t timeoutUs
void setRcDataFn(uint16_t *rcData, const uint8_t *payload)
rx_spi_received_e processFrameFn(uint8_t *const packet)
static void initGetBind(void)
uint32_t missingPackets
static bool getBind1(uint8_t *packet)
static bool getBind2(uint8_t *packet)
uint8_t listLength
static void initialise()
void frSkySpiSetRcData(uint16_t *rcData, const uint8_t *payload)
static timeMs_t start_time
static processFrameFn * processFrame
rx_spi_received_e frSkySpiProcessFrame(uint8_t *packet)
void nextChannel(uint8_t skip)
static setRcDataFn * setRcData
static uint8_t calData[255][3]
static void initTuneRx(void)
static timeMs_t timeTunedMs
rx_spi_received_e handlePacketFn(uint8_t *const packet, uint8_t *const protocolState)
static int8_t bindOffset
static handlePacketFn * handlePacket
bool frSkySpiInit(const rxSpiConfig_t *rxSpiConfig, rxRuntimeConfig_t *rxRuntimeConfig)
void initialiseData(bool inBindState)
static uint8_t protocolState
static uint8_t bindIdx
static rx_spi_protocol_e spiProtocol
@ STATE_BIND_BINDING1
@ STATE_BIND_BINDING2
@ STATE_BIND_COMPLETE
@ STATE_INIT
@ STATE_STARTING
@ STATE_BIND_TUNING
@ STATE_BIND
void frSkyXInit(const rx_spi_protocol_e spiProtocol)
rx_spi_received_e frSkyXHandlePacket(uint8_t *const packet, uint8_t *const protocolState)
rx_spi_received_e frSkyXProcessFrame(uint8_t *const packet)
void frSkyXSetRcData(uint16_t *rcData, const uint8_t *packet)
#define RC_CHANNEL_COUNT_FRSKY_X
int16_t rcData[MAX_SUPPORTED_RC_CHANNEL_COUNT]
Definition cc2500_rx.c:118
rssiSource_e rssiSource
Definition cc2500_rx.c:100
rxRuntimeConfig_t rxRuntimeConfig
Definition cc2500_rx.c:131
@ RSSI_SOURCE_RX_PROTOCOL
Definition cc2500_rx.h:158
@ RSSI_SOURCE_NONE
Definition cc2500_rx.h:155
uint8_t channelCount
Definition cc2500_rx.h:145
rx_spi_protocol_e
@ RX_SPI_FRSKY_X
@ RX_SPI_FRSKY_D
@ RX_SPI_FRSKY_X_LBT
rx_spi_received_e
@ RX_SPI_RECEIVED_NONE
@ RX_SPI_RECEIVED_BIND
void rxSpiLedOn(void)
void rxSpiLedToggle(void)
void rxSpiCommonIOInit(const rxSpiConfig_t *rxSpiConfig)
bool rxSpiCheckBindRequested(bool reset)
const rxCc2500SpiConfig_t * rxCc2500SpiConfig(void)
rxCc2500SpiConfig_t * rxCc2500SpiConfigMutable(void)
const rxSpiConfig_t * rxSpiConfig(void)
#define writeEEPROM()
uint8_t rx_spi_protocol
uint16_t foo
Definition main_demo5.c:58
unsigned short uint16_t
Typedef defining 16 bit unsigned short type.
unsigned int uint32_t
Typedef defining 32 bit unsigned int type.
unsigned char uint8_t
Typedef defining 8 bit unsigned char type.
signed char int8_t
Typedef defining 8 bit char type.