APM:Libraries
AP_Radio_cc2500.cpp
Go to the documentation of this file.
1 /*
2  driver for TI CC2500 radio
3 
4  Many thanks to the cleanflight and betaflight projects
5  */
6 #include <AP_HAL/AP_HAL.h>
7 
8 // #pragma GCC optimize("O0")
9 
10 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
11 #if HAL_RCINPUT_WITH_AP_RADIO
12 
13 #include <AP_Math/AP_Math.h>
14 #include "AP_Radio_cc2500.h"
15 #include <utility>
16 #include <stdio.h>
18 #include <AP_Notify/AP_Notify.h>
20 #include <AP_Math/crc.h>
21 
22 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
23 static THD_WORKING_AREA(_irq_handler_wa, 512);
24 #define TIMEOUT_PRIORITY 250 //Right above timer thread
25 #define EVT_TIMEOUT EVENT_MASK(0)
26 #define EVT_IRQ EVENT_MASK(1)
27 #define EVT_BIND EVENT_MASK(2)
28 #endif
29 
30 extern const AP_HAL::HAL& hal;
31 
32 #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { hal.console->printf(fmt, ##args); }} while (0)
33 
34 #define LP_FIFO_SIZE 16 // Physical data FIFO lengths in Radio
35 
36 // object instance for trampoline
38 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
40 virtual_timer_t AP_Radio_cc2500::timeout_vt;
42 #endif
43 
44 /*
45  constructor
46  */
48  AP_Radio_backend(_radio),
49  cc2500(hal.spi->get_device("cc2500"))
50 {
51  // link to instance for irq_trampoline
52  radio_instance = this;
53 }
54 
55 /*
56  initialise radio
57  */
58 bool AP_Radio_cc2500::init(void)
59 {
60 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
61  if(_irq_handler_ctx != nullptr) {
62  AP_HAL::panic("AP_Radio_cc2500: double instantiation of irq_handler\n");
63  }
64  chVTObjectInit(&timeout_vt);
65  _irq_handler_ctx = chThdCreateStatic(_irq_handler_wa,
66  sizeof(_irq_handler_wa),
67  TIMEOUT_PRIORITY, /* Initial priority. */
68  irq_handler_thd, /* Thread function. */
69  NULL); /* Thread parameter. */
70 #endif
71  sem = hal.util->new_semaphore();
72 
73  return reset();
74 }
75 
76 /*
77  reset radio
78  */
79 bool AP_Radio_cc2500::reset(void)
80 {
81  if (!cc2500.lock_bus()) {
82  return false;
83  }
84 
85  radio_init();
86  cc2500.unlock_bus();
87 
88  return true;
89 }
90 
91 /*
92  return statistics structure from radio
93  */
95 {
96  return stats;
97 }
98 
99 /*
100  read one pwm channel from radio
101  */
102 uint16_t AP_Radio_cc2500::read(uint8_t chan)
103 {
104  if (chan >= CC2500_MAX_CHANNELS) {
105  return 0;
106  }
107  return pwm_channels[chan];
108 }
109 
110 /*
111  update status - called from main thread
112  */
113 void AP_Radio_cc2500::update(void)
114 {
115  check_fw_ack();
116 }
117 
118 
119 /*
120  return number of active channels
121  */
122 uint8_t AP_Radio_cc2500::num_channels(void)
123 {
124  uint32_t now = AP_HAL::millis();
125  uint8_t chan = get_rssi_chan();
126  if (chan > 0) {
127  pwm_channels[chan-1] = t_status.rssi;
128  chan_count = MAX(chan_count, chan);
129  }
130 
131  chan = get_pps_chan();
132  if (chan > 0) {
133  pwm_channels[chan-1] = t_status.pps;
134  chan_count = MAX(chan_count, chan);
135  }
136 
137  chan = get_tx_rssi_chan();
138  if (chan > 0) {
139  pwm_channels[chan-1] = tx_rssi;
140  chan_count = MAX(chan_count, chan);
141  }
142 
143  chan = get_tx_pps_chan();
144  if (chan > 0) {
145  pwm_channels[chan-1] = tx_pps;
146  chan_count = MAX(chan_count, chan);
147  }
148 
149  if (now - last_pps_ms > 1000) {
150  last_pps_ms = now;
151  t_status.pps = stats.recv_packets - last_stats.recv_packets;
152  last_stats = stats;
153  if (lost != 0 || timeouts != 0) {
154  Debug(3,"lost=%u timeouts=%u TS=%u\n", unsigned(lost), unsigned(timeouts), sizeof(struct telem_packet_cc2500));
155  }
156  lost=0;
157  timeouts=0;
158  }
159  return chan_count;
160 }
161 
162 /*
163  return time of last receive in microseconds
164  */
165 uint32_t AP_Radio_cc2500::last_recv_us(void)
166 {
167  return packet_timer;
168 }
169 
170 /*
171  send len bytes as a single packet
172  */
173 bool AP_Radio_cc2500::send(const uint8_t *pkt, uint16_t len)
174 {
175  // disabled for now
176  return false;
177 }
178 
180  {CC2500_00_IOCFG2, 0x01}, // GD2 high on RXFIFO filled or end of packet
181  {CC2500_17_MCSM1, 0x0C}, // stay in RX on packet receive, CCA always, TX -> IDLE
182  {CC2500_18_MCSM0, 0x18}, // XOSC expire 64, cal on IDLE -> TX or RX
183  {CC2500_06_PKTLEN, 0x1E}, // packet length 30
184  {CC2500_07_PKTCTRL1, 0x04}, // enable RSSI+LQI, no addr check, no autoflush, PQT=0
185  {CC2500_08_PKTCTRL0, 0x01}, // var length mode, no CRC, FIFO enable, no whitening
186  {CC2500_3E_PATABLE, 0xFF}, // ?? what are we doing to PA table here?
187  {CC2500_0B_FSCTRL1, 0x0A}, // IF=253.90625kHz assuming 26MHz crystal
188  {CC2500_0C_FSCTRL0, 0x00}, // freqoffs = 0
189  {CC2500_0D_FREQ2, 0x5C}, // freq control high
190  {CC2500_0E_FREQ1, 0x76}, // freq control middle
191  {CC2500_0F_FREQ0, 0x27}, // freq control low
192  {CC2500_10_MDMCFG4, 0x7B}, // data rate control
193  {CC2500_11_MDMCFG3, 0x61}, // data rate control
194  {CC2500_12_MDMCFG2, 0x13}, // 30/32 sync word bits, no manchester, GFSK, DC filter enabled
195  {CC2500_13_MDMCFG1, 0x23}, // chan spacing exponent 3, preamble 4 bytes, FEC disabled
196  {CC2500_14_MDMCFG0, 0x7A}, // chan spacing 299.926757kHz for 26MHz crystal
197  {CC2500_15_DEVIATN, 0x51}, // modem deviation 25.128906kHz for 26MHz crystal
198  {CC2500_19_FOCCFG, 0x16}, // frequency offset compensation
199  {CC2500_1A_BSCFG, 0x6C}, // bit sync config
200  {CC2500_1B_AGCCTRL2, 0x43}, // target amplitude 33dB
201  {CC2500_1C_AGCCTRL1, 0x40}, // AGC control 2
202  {CC2500_1D_AGCCTRL0, 0x91}, // AGC control 0
203  {CC2500_21_FREND1, 0x56}, // frontend config1
204  {CC2500_22_FREND0, 0x10}, // frontend config0
205  {CC2500_23_FSCAL3, 0xA9}, // frequency synth cal3
206  {CC2500_24_FSCAL2, 0x0A}, // frequency synth cal2
207  {CC2500_25_FSCAL1, 0x00}, // frequency synth cal1
208  {CC2500_26_FSCAL0, 0x11}, // frequency synth cal0
209  {CC2500_29_FSTEST, 0x59}, // test bits
210  {CC2500_2C_TEST2, 0x88}, // test settings
211  {CC2500_2D_TEST1, 0x31}, // test settings
212  {CC2500_2E_TEST0, 0x0B}, // test settings
213  {CC2500_03_FIFOTHR, 0x07}, // TX fifo threashold 33, RX fifo threshold 32
214  {CC2500_09_ADDR, 0x00}, // device address 0 (broadcast)
215 };
216 
217 const uint16_t CRCTable[] = {
218  0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
219  0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
220  0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
221  0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
222  0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
223  0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
224  0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
225  0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
226  0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
227  0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
228  0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
229  0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
230  0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
231  0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
232  0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
233  0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
234  0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
235  0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
236  0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
237  0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
238  0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
239  0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
240  0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
241  0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
242  0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
243  0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
244  0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
245  0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
246  0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
247  0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
248  0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
249  0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
250 };
251 
252 /*
253  initialise the radio
254  */
256 {
257  if (cc2500.ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST) != 0x80 ||
258  cc2500.ReadReg(CC2500_31_VERSION | CC2500_READ_BURST) != 0x03) {
259  Debug(1, "cc2500: radio not found\n");
260  return;
261  }
262 
263  Debug(1, "cc2500: radio_init starting\n");
264 
265  cc2500.Reset();
266  hal.scheduler->delay_microseconds(100);
267  for (uint8_t i=0; i<ARRAY_SIZE(radio_config); i++) {
268  // write twice to cope with possible SPI errors
269  cc2500.WriteRegCheck(radio_config[i].reg, radio_config[i].value);
270  }
271  cc2500.Strobe(CC2500_SIDLE); // Go to idle...
272 
273  for (uint8_t c=0;c<0xFF;c++) {
274  //calibrate all channels
275  cc2500.Strobe(CC2500_SIDLE);
276  cc2500.WriteRegCheck(CC2500_0A_CHANNR, c);
277  cc2500.Strobe(CC2500_SCAL);
278  hal.scheduler->delay_microseconds(900);
279  calData[c][0] = cc2500.ReadReg(CC2500_23_FSCAL3);
280  calData[c][1] = cc2500.ReadReg(CC2500_24_FSCAL2);
281  calData[c][2] = cc2500.ReadReg(CC2500_25_FSCAL1);
282  }
283 
284  hal.scheduler->delay_microseconds(10*1000);
285 
286  // setup handler for rising edge of IRQ pin
287 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
288  stm32_gpiosetevent(CYRF_IRQ_INPUT, true, false, false, irq_radio_trampoline);
289 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
290  hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, HAL_GPIO_INTERRUPT_RISING);
291 #endif
292 
293  initTuneRx();
294 
295  if (load_bind_info()) {
296  Debug(3,"Loaded bind info\n");
297  listLength = 47;
298  initialiseData(0);
299  protocolState = STATE_SEARCH;
300  chanskip = 1;
301  nextChannel(1);
302  } else {
303  protocolState = STATE_BIND_TUNING;
304  }
305 
306  chVTSet(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
307 }
308 
310 {
311  //we are called from ISR context
312  chSysLockFromISR();
313  irq_time_us = AP_HAL::micros();
314  chEvtSignalI(_irq_handler_ctx, EVT_IRQ);
315  chSysUnlockFromISR();
316 }
317 
319 {
320  (void)arg;
321  //we are called from ISR context
322  chSysLockFromISR();
323  chVTSetI(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
324  chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
325  chSysUnlockFromISR();
326 }
327 
329 {
330  protocolState = STATE_BIND_TUNING;
331  chan_count = 0;
332  packet_timer = AP_HAL::micros();
333  chEvtSignal(_irq_handler_ctx, EVT_BIND);
334  Debug(1,"Starting bind\n");
335 }
336 
337 // handle a data96 mavlink packet for fw upload
338 void AP_Radio_cc2500::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
339 {
340  uint32_t ofs=0;
341  memcpy(&ofs, &m.data[0], 4);
342  Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
343  if (sem->take_nonblocking()) {
344  fwupload.chan = chan;
345  fwupload.need_ack = false;
346  fwupload.offset = ofs;
347  fwupload.length = MIN(m.len-4, 92);
348  fwupload.acked = 0;
349  fwupload.sequence++;
350  if (m.type == 43) {
351  // sending a tune to play - for development testing
352  fwupload.fw_type = TELEM_PLAY;
353  fwupload.length = MIN(m.len, 90);
354  fwupload.offset = 0;
355  memcpy(&fwupload.pending_data[0], &m.data[0], fwupload.length);
356  } else {
357  // sending a chunk of firmware OTA upload
358  fwupload.fw_type = TELEM_FW;
359  memcpy(&fwupload.pending_data[0], &m.data[4], fwupload.length);
360  }
361  sem->give();
362  }
363 }
364 
365 /*
366  handle a FrSky D16 packet
367  */
368 bool AP_Radio_cc2500::handle_D16_packet(const uint8_t *packet)
369 {
370  if (packet[0] != 0x1D) {
371  return false;
372  }
373  if (packet[1] != bindTxId[0] ||
374  packet[2] != bindTxId[1]) {
375  Debug(3, "p1=%02x p2=%02x p6=%02x\n", packet[1], packet[2], packet[6]);
376  // not for us
377  return false;
378  }
379  if (packet[7] == 0x00 ||
380  packet[7] == 0x20 ||
381  packet[7] == 0x10 ||
382  packet[7] == 0x12 ||
383  packet[7] == 0x14 ||
384  packet[7] == 0x16 ||
385  packet[7] == 0x18 ||
386  packet[7] == 0x1A ||
387  packet[7] == 0x1C ||
388  packet[7] == 0x1E) {
389  // channel packet or range check packet
390  parse_frSkyX(packet);
391 
392  packet3 = packet[3];
393 
394  uint8_t hop_chan = packet[4] & 0x3F;
395  uint8_t skip = (packet[4]>>6) | (packet[5]<<2);
396  if (channr != hop_chan) {
397  Debug(2, "channr=%u hop_chan=%u\n", channr, hop_chan);
398  }
399  channr = hop_chan;
400  if (chanskip != skip) {
401  Debug(2, "chanskip=%u skip=%u\n", chanskip, skip);
402  }
403  chanskip = skip;
404  return true;
405  }
406  return false;
407 }
408 
409 /*
410  handle a SRT packet
411  */
412 bool AP_Radio_cc2500::handle_SRT_packet(const uint8_t *packet)
413 {
414  const struct srt_packet *pkt = (const struct srt_packet *)packet;
415  if (pkt->length != sizeof(struct srt_packet)-1 ||
416  pkt->txid[0] != bindTxId[0] ||
417  pkt->txid[1] != bindTxId[1]) {
418  Debug(3, "len=%u p1=%02x p2=%02x\n", pkt->length, pkt->txid[0], pkt->txid[1]);
419  // not for us
420  return false;
421  }
422  if (pkt->version != 1) {
423  // only support version 1 so far
424  return false;
425  }
426  pwm_channels[0] = pkt->chan1 + 1000 + ((pkt->chan_high&0xC0)<<2);
427  pwm_channels[1] = pkt->chan2 + 1000 + ((pkt->chan_high&0x30)<<4);
428  pwm_channels[2] = pkt->chan3 + 1000 + ((pkt->chan_high&0x0C)<<6);
429  pwm_channels[3] = pkt->chan4 + 1000 + ((pkt->chan_high&0x03)<<8);
430  // we map the buttons onto two PWM channels for ease of integration with ArduPilot
431  pwm_channels[4] = 1000 + (pkt->buttons & 0x7) * 100;
432  pwm_channels[5] = 1000 + (pkt->buttons >> 3) * 100;
433 
434  uint8_t data = pkt->data;
435  /*
436  decode special data field
437  */
438  switch (pkt->pkt_type) {
439  case PKTYPE_VOLTAGE:
440  // voltage from TX is in 0.025 volt units. Convert to 0.01 volt units for easier display
441  pwm_channels[6] = data * 4;
442  break;
443  case PKTYPE_YEAR:
444  tx_date.firmware_year = data;
445  break;
446  case PKTYPE_MONTH:
447  tx_date.firmware_month = data;
448  break;
449  case PKTYPE_DAY:
450  tx_date.firmware_day = data;
451  break;
452  case PKTYPE_TELEM_RSSI:
453  tx_rssi = data;
454  break;
455  case PKTYPE_TELEM_PPS:
456  tx_pps = data;
457  break;
458  case PKTYPE_BL_VERSION:
459  // unused so far for cc2500
460  break;
461  case PKTYPE_FW_ACK: {
462  // got an fw upload ack
463  Debug(4, "ack %u seq=%u acked=%u length=%u len=%u\n",
464  data, fwupload.sequence, unsigned(fwupload.acked), unsigned(fwupload.length), fwupload.len);
465  if (fwupload.sequence == data && sem->take_nonblocking()) {
466  fwupload.sequence++;
467  fwupload.acked += fwupload.len;
468  if (fwupload.acked == fwupload.length) {
469  // trigger send of DATA16 ack to client
470  fwupload.need_ack = true;
471  }
472  sem->give();
473  }
474  break;
475  }
476  }
477 
478  if (chan_count < 7) {
479  chan_count = 7;
480  }
481 
482  if (pkt->channr != channr) {
483  Debug(2, "channr=%u hop_chan=%u\n", channr, pkt->channr);
484  channr = pkt->channr;
485  }
486  if (pkt->chanskip != chanskip) {
487  Debug(2, "chanskip=%u skip=%u\n", chanskip, pkt->chanskip);
488  chanskip = pkt->chanskip;
489  }
490  return true;
491 }
492 
493 // main IRQ handler
495 {
496  uint8_t ccLen;
497  bool matched = false;
498  do {
499  ccLen = cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST);
500  hal.scheduler->delay_microseconds(20);
501  uint8_t ccLen2 = cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST);
502  matched = (ccLen == ccLen2);
503  } while (!matched);
504 
505  if (ccLen & 0x80) {
506  Debug(3,"Fifo overflow %02x\n", ccLen);
507  // RX FIFO overflow
508  cc2500.Strobe(CC2500_SFRX);
509  cc2500.Strobe(CC2500_SRX);
510  return;
511  }
512 
513  uint8_t packet[ccLen];
514  cc2500.ReadFifo(packet, ccLen);
515 
516  if (get_fcc_test() != 0) {
517  // don't process interrupts in FCCTEST mode
518  return;
519  }
520 
521  if (ccLen != 32 && ccLen != sizeof(srt_packet)+2) {
522  cc2500.Strobe(CC2500_SFRX);
523  cc2500.Strobe(CC2500_SRX);
524  Debug(3, "bad len %u\n", ccLen);
525  return;
526  }
527 
528  if (get_debug_level() > 6) {
529  Debug(6, "CC2500 IRQ state=%u\n", unsigned(protocolState));
530  Debug(6,"len=%u\n", ccLen);
531  for (uint8_t i=0; i<ccLen; i++) {
532  Debug(6, "%02x:%02x ", i, packet[i]);
533  if ((i+1) % 16 == 0) {
534  Debug(6, "\n");
535  }
536  }
537  if (ccLen % 16 != 0) {
538  Debug(6, "\n");
539  }
540  }
541 
542  if (!check_crc(ccLen, packet)) {
543  Debug(3, "bad CRC ccLen=%u\n", ccLen);
544  return;
545  }
546 
547  switch (protocolState) {
548  case STATE_BIND_TUNING:
549  tuneRx(ccLen, packet);
550  break;
551 
552  case STATE_BIND_BINDING:
553  if (getBindData(ccLen, packet)) {
554  Debug(2,"Bind complete\n");
555  protocolState = STATE_BIND_COMPLETE;
556  }
557  break;
558 
559  case STATE_BIND_COMPLETE:
560  protocolState = STATE_STARTING;
561  save_bind_info();
562  Debug(3,"listLength=%u\n", listLength);
563  Debug(3,"Saved bind info\n");
564  break;
565 
566  case STATE_STARTING:
567  listLength = 47;
568  initialiseData(0);
569  protocolState = STATE_SEARCH;
570  chanskip = 1;
571  nextChannel(1);
572  break;
573 
574  case STATE_SEARCH:
575  protocolState = STATE_DATA;
576  FALLTHROUGH;
577 
578  case STATE_DATA: {
579  bool ok = false;
580  if (ccLen == 32) {
581  ok = handle_D16_packet(packet);
582  } else if (ccLen == sizeof(srt_packet)+2) {
583  ok = handle_SRT_packet(packet);
584  }
585  if (ok) {
586  // get RSSI value from status byte
587  uint8_t rssi_raw = packet[ccLen-2];
588  float rssi_dbm;
589  if (rssi_raw >= 128) {
590  rssi_dbm = ((((uint16_t)rssi_raw) * 18) >> 5) - 82;
591  } else {
592  rssi_dbm = ((((uint16_t)rssi_raw) * 18) >> 5) + 65;
593  }
594  rssi_filtered = 0.95 * rssi_filtered + 0.05 * rssi_dbm;
595  t_status.rssi = uint8_t(MAX(rssi_filtered, 1));
596 
597  stats.recv_packets++;
598 
599  packet_timer = irq_time_us;
600  chVTSet(&timeout_vt, MS2ST(10), trigger_timeout_event, nullptr);
601 
602  cc2500.Strobe(CC2500_SIDLE);
603  cc2500.SetPower(get_transmit_power());
604  if (ccLen == 32 || get_protocol() == AP_Radio::PROTOCOL_D16) {
605  send_D16_telemetry();
606  } else {
607  send_SRT_telemetry();
608  }
609 
610  // we can safely sleep here as we have a dedicated thread for radio processing. We need to sleep
611  // for enough time for the packet to be fully transmitted
612  cc2500.unlock_bus();
613  hal.scheduler->delay_microseconds(3500);
614  cc2500.lock_bus();
615 
616  nextChannel(chanskip);
617  }
618  break;
619  }
620 
621  case STATE_FCCTEST:
622  // nothing to do, all done in timeout code
623  Debug(3,"IRQ in FCCTEST state\n");
624  break;
625 
626  default:
627  Debug(2,"state %u\n", (unsigned)protocolState);
628  break;
629  }
630 }
631 
632 // handle timeout IRQ
634 {
635  if (get_fcc_test() != 0 && protocolState != STATE_FCCTEST) {
636  protocolState = STATE_FCCTEST;
637  Debug(1,"Starting FCCTEST %d\n", get_fcc_test());
638  setChannel(labs(get_fcc_test()) * 10);
639  send_D16_telemetry();
640  }
641 
642  switch (protocolState) {
643  case STATE_BIND_TUNING: {
644  if (bindOffset >= 126) {
645  if (check_best_LQI()) {
646  return;
647  }
648  bindOffset = -126;
649  }
650  uint32_t now = AP_HAL::millis();
651  if (now - timeTunedMs > 20) {
652  timeTunedMs = now;
653  bindOffset += 5;
654  Debug(6,"bindOffset=%d\n", int(bindOffset));
655  cc2500.Strobe(CC2500_SIDLE);
656  cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
657  cc2500.Strobe(CC2500_SFRX);
658  cc2500.Strobe(CC2500_SRX);
659  }
660  break;
661  }
662 
663  case STATE_DATA: {
664  uint32_t now = AP_HAL::micros();
665 
666  if (now - packet_timer > 50*sync_time_us) {
667  Debug(3,"searching %u\n", unsigned(now - packet_timer));
668  cc2500.Strobe(CC2500_SIDLE);
669  cc2500.Strobe(CC2500_SFRX);
670  nextChannel(1);
671  cc2500.Strobe(CC2500_SRX);
672  timeouts++;
673  protocolState = STATE_SEARCH;
674  } else {
675  nextChannel(chanskip);
676  // to keep the timeouts 1ms behind the expected time we
677  // need to set the timeout to 9ms
678  chVTSet(&timeout_vt, MS2ST(9), trigger_timeout_event, nullptr);
679  lost++;
680  }
681  break;
682  }
683 
684  case STATE_SEARCH:
685  // shift by one channel at a time when searching
686  nextChannel(1);
687  break;
688 
689  case STATE_FCCTEST: {
690  if (get_fcc_test() == 0) {
691  protocolState = STATE_DATA;
692  Debug(1,"Ending FCCTEST\n");
693  }
694  setChannel(labs(get_fcc_test()) * 10);
695  cc2500.SetPower(get_transmit_power());
696  send_D16_telemetry();
697  break;
698  }
699 
700  default:
701  break;
702  }
703 }
704 
705 void AP_Radio_cc2500::irq_handler_thd(void *arg)
706 {
707  (void)arg;
708  while(true) {
709  eventmask_t evt = chEvtWaitAny(ALL_EVENTS);
710 
711  radio_instance->cc2500.lock_bus();
712 
713  switch(evt) {
714  case EVT_IRQ:
715  if (radio_instance->protocolState == STATE_FCCTEST) {
716  hal.console->printf("IRQ FCC\n");
717  }
718  radio_instance->irq_handler();
719  break;
720  case EVT_TIMEOUT:
721  if (radio_instance->cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x80) {
722  irq_time_us = AP_HAL::micros();
723  radio_instance->irq_handler();
724  } else {
725  radio_instance->irq_timeout();
726  }
727  break;
728  case EVT_BIND:
729  radio_instance->initTuneRx();
730  break;
731  default:
732  break;
733  }
734 
735  radio_instance->cc2500.unlock_bus();
736  }
737 }
738 
740 {
741  cc2500.WriteReg(CC2500_19_FOCCFG, 0x14);
742  timeTunedMs = AP_HAL::millis();
743  bindOffset = -126;
744  best_lqi = 255;
745  best_bindOffset = bindOffset;
746  cc2500.WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
747  //cc2500.WriteReg(CC2500_07_PKTCTRL1, 0x0C);
748  cc2500.WriteReg(CC2500_18_MCSM0, 0x8);
749 
750  cc2500.Strobe(CC2500_SIDLE);
751  cc2500.WriteReg(CC2500_23_FSCAL3, calData[0][0]);
752  cc2500.WriteReg(CC2500_24_FSCAL2, calData[0][1]);
753  cc2500.WriteReg(CC2500_25_FSCAL1, calData[0][2]);
754  cc2500.WriteReg(CC2500_0A_CHANNR, 0);
755  cc2500.Strobe(CC2500_SFRX);
756  cc2500.Strobe(CC2500_SRX);
757 }
758 
759 void AP_Radio_cc2500::initialiseData(uint8_t adr)
760 {
761  cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, bindOffset);
762  cc2500.WriteRegCheck(CC2500_18_MCSM0, 0x8);
763  cc2500.WriteRegCheck(CC2500_09_ADDR, adr ? 0x03 : bindTxId[0]);
764  //cc2500.WriteRegCheck(CC2500_07_PKTCTRL1, 0x0D); // address check, no broadcast, autoflush, status enable
765  cc2500.WriteRegCheck(CC2500_19_FOCCFG, 0x16);
766  hal.scheduler->delay_microseconds(10*1000);
767 }
768 
770 {
771  cc2500.Strobe(CC2500_SIDLE);
772  cc2500.WriteReg(CC2500_23_FSCAL3, calData[0][0]);
773  cc2500.WriteReg(CC2500_24_FSCAL2, calData[0][1]);
774  cc2500.WriteReg(CC2500_25_FSCAL1, calData[0][2]);
775  cc2500.WriteReg(CC2500_0A_CHANNR, 0);
776  cc2500.Strobe(CC2500_SFRX);
777  hal.scheduler->delay_microseconds(20); // waiting flush FIFO
778 
779  cc2500.Strobe(CC2500_SRX);
780  listLength = 0;
781 }
782 
783 /*
784  we've wrapped in the search for the best bind offset. Accept the
785  best so far if its good enough
786  */
788 {
789  if (best_lqi >= 50) {
790  return false;
791  }
792  bindOffset = best_bindOffset;
793  initGetBind();
794  initialiseData(1);
795  protocolState = STATE_BIND_BINDING;
796  bind_mask = 0;
797  listLength = 0;
798  Debug(2,"Bind tuning %d with Lqi %u\n", best_bindOffset, best_lqi);
799  return true;
800 }
801 
802 /*
803  check if we have received a packet with sufficiently good link
804  quality to start binding
805  */
806 bool AP_Radio_cc2500::tuneRx(uint8_t ccLen, uint8_t *packet)
807 {
808  if (bindOffset >= 126) {
809  // we've scanned the whole range, if any were below 50 then
810  // accept it
811  if (check_best_LQI()) {
812  return true;
813  }
814  bindOffset = -126;
815  }
816  if ((packet[ccLen - 1] & 0x80) && packet[2] == 0x01) {
817  uint8_t Lqi = packet[ccLen - 1] & 0x7F;
818  if (Lqi < best_lqi) {
819  best_lqi = Lqi;
820  best_bindOffset = bindOffset;
821  }
822  }
823  return false;
824 }
825 
826 /*
827  get a block of hopping data from a bind packet
828  */
829 bool AP_Radio_cc2500::getBindData(uint8_t ccLen, uint8_t *packet)
830 {
831  // parse a bind data packet */
832  if ((packet[ccLen - 1] & 0x80) && packet[2] == 0x01) {
833  if (bind_mask == 0) {
834  bindTxId[0] = packet[3];
835  bindTxId[1] = packet[4];
836  } else if (bindTxId[0] != packet[3] ||
837  bindTxId[1] != packet[4]) {
838  Debug(2,"Bind restart\n");
839  bind_mask = 0;
840  listLength = 0;
841  }
842 
843  for (uint8_t n = 0; n < 5; n++) {
844  uint8_t c = packet[5] + n;
845  if (c < sizeof(bindHopData)) {
846  bindHopData[c] = packet[6 + n];
847  bind_mask |= (uint64_t(1)<<c);
848  listLength = MAX(listLength, c+1);
849  }
850  }
851  // bind has finished when we have hopping data for all channels
852  return (listLength == 47 && bind_mask == ((uint64_t(1)<<47)-1));
853  }
854  return false;
855 }
856 
857 void AP_Radio_cc2500::setChannel(uint8_t channel)
858 {
859  cc2500.Strobe(CC2500_SIDLE);
860  cc2500.WriteReg(CC2500_23_FSCAL3, calData[channel][0]);
861  cc2500.WriteReg(CC2500_24_FSCAL2, calData[channel][1]);
862  cc2500.WriteReg(CC2500_25_FSCAL1, calData[channel][2]);
863  cc2500.WriteReg(CC2500_0A_CHANNR, channel);
864  cc2500.Strobe(CC2500_SRX);
865 }
866 
867 void AP_Radio_cc2500::nextChannel(uint8_t skip)
868 {
869  channr = (channr + skip) % listLength;
870  setChannel(bindHopData[channr]);
871 }
872 
873 void AP_Radio_cc2500::parse_frSkyX(const uint8_t *packet)
874 {
875  uint16_t c[8];
876 
877  c[0] = (uint16_t)((packet[10] <<8)& 0xF00) | packet[9];
878  c[1] = (uint16_t)((packet[11]<<4)&0xFF0) | (packet[10]>>4);
879  c[2] = (uint16_t)((packet[13] <<8)& 0xF00) | packet[12];
880  c[3] = (uint16_t)((packet[14]<<4)&0xFF0) | (packet[13]>>4);
881  c[4] = (uint16_t)((packet[16] <<8)& 0xF00) | packet[15];
882  c[5] = (uint16_t)((packet[17]<<4)&0xFF0) | (packet[16]>>4);
883  c[6] = (uint16_t)((packet[19] <<8)& 0xF00) | packet[18];
884  c[7] = (uint16_t)((packet[20]<<4)&0xFF0) | (packet[19]>>4);
885 
886  uint8_t j;
887  for (uint8_t i=0;i<8;i++) {
888  if(c[i] > 2047) {
889  j = 8;
890  c[i] = c[i] - 2048;
891  } else {
892  j = 0;
893  }
894  if (c[i] == 0) {
895  continue;
896  }
897  uint16_t word_temp = (((c[i]-64)<<1)/3+860);
898  if ((word_temp > 800) && (word_temp < 2200)) {
899  uint8_t chan = i+j;
900  if (chan < CC2500_MAX_CHANNELS) {
901  pwm_channels[chan] = word_temp;
902  if (chan >= chan_count) {
903  chan_count = chan+1;
904  }
905  }
906  }
907  }
908 }
909 
910 uint16_t AP_Radio_cc2500::calc_crc(const uint8_t *data, uint8_t len)
911 {
912  uint16_t crc = 0;
913  for(uint8_t i=0; i < len; i++) {
914  crc = (crc<<8) ^ (CRCTable[((uint8_t)(crc>>8) ^ *data++) & 0xFF]);
915  }
916  return crc;
917 }
918 
919 bool AP_Radio_cc2500::check_crc(uint8_t ccLen, uint8_t *packet)
920 {
921  if (ccLen == sizeof(srt_packet)+2) {
922  struct srt_packet *pkt = (struct srt_packet *)packet;
923  // SRT packet
924  uint16_t lcrc = calc_crc(packet,sizeof(struct srt_packet)-2);
925  return lcrc == ((pkt->crc[0]<<8) | pkt->crc[1]);
926  } else if (ccLen == 32) {
927  // D16 packet
928  uint16_t lcrc = calc_crc(&packet[3],(ccLen-7));
929  return ((lcrc >>8)==packet[ccLen-4] && (lcrc&0x00FF)==packet[ccLen-3]);
930  }
931  return false;
932 }
933 
934 /*
935  save bind info
936  */
938 {
939  // access to storage for bind information
941  struct bind_info info;
942 
943  info.magic = bind_magic;
944  info.bindTxId[0] = bindTxId[0];
945  info.bindTxId[1] = bindTxId[1];
946  info.bindOffset = bindOffset;
947  info.listLength = listLength;
948  memcpy(info.bindHopData, bindHopData, sizeof(info.bindHopData));
949  bind_storage.write_block(0, &info, sizeof(info));
950 }
951 
952 /*
953  load bind info
954  */
956 {
957  // access to storage for bind information
959  struct bind_info info;
960 
961  if (!bind_storage.read_block(&info, 0, sizeof(info)) || info.magic != bind_magic) {
962  return false;
963  }
964 
965  bindTxId[0] = info.bindTxId[0];
966  bindTxId[1] = info.bindTxId[1];
967  bindOffset = info.bindOffset;
968  listLength = info.listLength;
969  memcpy(bindHopData, info.bindHopData, sizeof(bindHopData));
970 
971  return true;
972 }
973 
974 /*
975  send a D16 telemetry packet
976  */
978 {
979  uint8_t frame[15];
980 
981  memset(frame, 0, sizeof(frame));
982 
983  frame[0] = sizeof(frame)-1;
984  frame[1] = bindTxId[0];
985  frame[2] = bindTxId[1];
986  frame[3] = packet3;
987  if (telem_send_rssi) {
988  frame[4] = MAX(MIN(t_status.rssi, 0x7f),1) | 0x80;
989  } else {
990  frame[4] = uint8_t(hal.analogin->board_voltage() * 10) & 0x7F;
991  }
992  telem_send_rssi = !telem_send_rssi;
993 
994  uint16_t lcrc = calc_crc(&frame[3], 10);
995  frame[13] = lcrc>>8;
996  frame[14] = lcrc;
997 
998  cc2500.Strobe(CC2500_SIDLE);
999  cc2500.Strobe(CC2500_SFTX);
1000  if (get_fcc_test() >= 0) {
1001  // in negative FCC test modes we don't write to the FIFO, which gives
1002  // continuous transmission
1003  cc2500.WriteFifo(frame, sizeof(frame));
1004  }
1005  cc2500.Strobe(CC2500_STX);
1006 }
1007 
1008 
1009 /*
1010  send a SRT telemetry packet
1011  */
1013 {
1014  struct telem_packet_cc2500 pkt {};
1015 
1016  pkt.length = sizeof(pkt)-1;
1017 
1018  t_status.flags = 0;
1019  t_status.flags |= AP_Notify::flags.gps_status >= 3?TELEM_FLAG_GPS_OK:0;
1020  t_status.flags |= AP_Notify::flags.pre_arm_check?TELEM_FLAG_ARM_OK:0;
1022  t_status.flags |= hal.util->get_soft_armed()?TELEM_FLAG_ARMED:0;
1023  t_status.flags |= AP_Notify::flags.have_pos_abs?TELEM_FLAG_POS_OK:0;
1025  t_status.flight_mode = AP_Notify::flags.flight_mode;
1026  t_status.tx_max = get_tx_max_power();
1027  t_status.note_adjust = get_tx_buzzer_adjust();
1028 
1029  // send fw update packet for 7/8 of packets if any data pending
1030  if (fwupload.length != 0 &&
1031  fwupload.length > fwupload.acked &&
1032  ((fwupload.counter++ & 0x07) != 0) &&
1033  sem->take_nonblocking()) {
1034  pkt.type = fwupload.fw_type;
1035  pkt.payload.fw.seq = fwupload.sequence;
1036  uint32_t len = fwupload.length>fwupload.acked?fwupload.length - fwupload.acked:0;
1037  pkt.payload.fw.len = len<=8?len:8;
1038  pkt.payload.fw.offset = fwupload.offset+fwupload.acked;
1039  memcpy(&pkt.payload.fw.data[0], &fwupload.pending_data[fwupload.acked], pkt.payload.fw.len);
1040  fwupload.len = pkt.payload.fw.len;
1041  Debug(4, "sent fw seq=%u offset=%u len=%u type=%u\n",
1042  pkt.payload.fw.seq,
1043  pkt.payload.fw.offset,
1044  pkt.payload.fw.len,
1045  pkt.type);
1046  sem->give();
1047  } else {
1048  pkt.type = TELEM_STATUS;
1049  pkt.payload.status = t_status;
1050  }
1051  pkt.txid[0] = bindTxId[0];
1052  pkt.txid[1] = bindTxId[1];
1053 
1054  uint16_t lcrc = calc_crc((const uint8_t *)&pkt, sizeof(pkt)-2);
1055  pkt.crc[0] = lcrc>>8;
1056  pkt.crc[1] = lcrc&0xFF;
1057 
1058  cc2500.Strobe(CC2500_SIDLE);
1059  cc2500.Strobe(CC2500_SFTX);
1060  if (get_fcc_test() >= 0) {
1061  // in negative FCC test modes we don't write to the FIFO, which gives
1062  // continuous transmission
1063  cc2500.WriteFifo((const uint8_t *)&pkt, sizeof(pkt));
1064  }
1065  cc2500.Strobe(CC2500_STX);
1066 }
1067 
1068 /*
1069  send a fwupload ack if needed
1070  */
1072 {
1073  if (fwupload.need_ack && sem->take_nonblocking()) {
1074  // ack the send of a DATA96 fw packet to TX
1075  fwupload.need_ack = false;
1076  uint8_t data16[16] {};
1077  uint32_t ack_to = fwupload.offset + fwupload.acked;
1078  memcpy(&data16[0], &ack_to, 4);
1079  mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
1080  Debug(4,"sent ack DATA16\n");
1081  sem->give();
1082  }
1083 }
1084 
1085 #endif // HAL_RCINPUT_WITH_AP_RADIO
1086 #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
bool get_soft_armed() const
Definition: Util.h:15
void nextChannel(uint8_t skip)
static thread_t * _irq_handler_ctx
uint8_t get_tx_rssi_chan(void) const
bool send(const uint8_t *pkt, uint16_t len) override
static void trigger_timeout_event(void *arg)
#define TELEM_FLAG_POS_OK
uint8_t get_debug_level(void) const
virtual float board_voltage(void)=0
#define CC2500_SRX
Definition: driver_cc2500.h:95
AP_Radio_cc2500(AP_Radio &radio)
struct telem_status status
#define FALLTHROUGH
Definition: AP_Common.h:50
AP_HAL::UARTDriver * console
Definition: HAL.h:110
bool tuneRx(uint8_t ccLen, uint8_t *packet)
bool init(void) override
void update(void) override
uint8_t get_rssi_chan(void) const
void save_bind_info(void)
bool getBindData(uint8_t ccLen, uint8_t *packet)
void irq_timeout(void)
AP_HAL::OwnPtr< AP_HAL::Device > get_device(const char *name)
Definition: BusTest.cpp:22
uint8_t data[8]
uint8_t length
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
void radio_init(void)
uint16_t read(uint8_t chan) override
void send_D16_telemetry(void)
virtual bool reset(void)=0
uint8_t chan_high
#define MIN(a, b)
Definition: usb_conf.h:215
void setChannel(uint8_t channel)
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
uint8_t txid[2]
void start_recv_bind(void) override
static uint32_t irq_time_us
virtual bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)=0
uint32_t last_recv_us(void) override
#define CC2500_STX
Definition: driver_cc2500.h:98
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
bool reset(void) override
uint8_t chan2
void check_fw_ack(void)
uint8_t num_channels(void) override
#define CC2500_MAX_CHANNELS
#define Debug(fmt, args ...)
void initTuneRx(void)
int8_t get_fcc_test(void) const
uint32_t millis()
Definition: system.cpp:157
#define TELEM_FLAG_VIDEO
#define HAL_GPIO_INTERRUPT_RISING
Definition: GPIO.h:13
void initialiseData(uint8_t adr)
uint8_t crc[2]
bool handle_D16_packet(const uint8_t *packet)
void irq_handler(void)
#define TELEM_FLAG_ARM_OK
#define TELEM_FLAG_BATT_OK
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
bool check_crc(uint8_t ccLen, uint8_t *packet)
static virtual_timer_t timeout_vt
static void trigger_irq_radio_event(void)
#define NULL
Definition: hal_types.h:59
#define CC2500_READ_BURST
Definition: driver_cc2500.h:84
void parse_frSkyX(const uint8_t *packet)
static AP_Radio_cc2500 * radio_instance
uint8_t get_tx_buzzer_adjust(void) const
#define CC2500_SFTX
uint8_t chanskip
bool handle_SRT_packet(const uint8_t *packet)
void send_SRT_telemetry(void)
bool check_best_LQI(void)
uint8_t buttons
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
#define CC2500_SCAL
Definition: driver_cc2500.h:93
uint8_t get_transmit_power(void) const
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
AP_HAL::GPIO * gpio
Definition: HAL.h:111
uint8_t channr
virtual void delay_microseconds(uint16_t us)=0
float value
uint8_t get_tx_pps_chan(void) const
uint8_t get_tx_max_power(void) const
uint8_t chan1
#define TELEM_FLAG_GPS_OK
const AP_Radio::stats & get_stats(void) override
void initGetBind(void)
uint16_t calc_crc(const uint8_t *data, uint8_t len)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static const config radio_config[]
uint8_t get_pps_chan(void) const
uint8_t pkt_type
bool load_bind_info(void)
THD_WORKING_AREA(_timer_thread_wa, 2048)
#define CC2500_SFRX
#define TELEM_FLAG_ARMED
#define CC2500_SIDLE
uint8_t chan4
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override
uint8_t version
uint32_t micros()
Definition: system.cpp:152
static void irq_handler_thd(void *arg)
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
uint8_t chan3
AP_Radio::ap_radio_protocol get_protocol(void) const
uint8_t data
union telem_packet_cc2500::@175 payload
AP_HAL::AnalogIn * analogin
Definition: HAL.h:108
struct telem_firmware fw