APM:Libraries
AP_Radio_cypress.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_RCINPUT_WITH_AP_RADIO
4 
5 #include <AP_Math/AP_Math.h>
6 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
7 #include <board_config.h>
8 #endif
9 #include "AP_Radio_cypress.h"
10 #include <utility>
11 #include <stdio.h>
13 #include <AP_HAL/utility/dsm.h>
14 #include <AP_Math/crc.h>
15 #include "telem_structure.h"
16 #include <AP_Notify/AP_Notify.h>
18 
19 /*
20  driver for CYRF6936 radio
21 
22  Many thanks to the SuperBitRF project from Paparrazi for their DSM
23  configuration code and register defines
24  https://github.com/esden/superbitrf-firmware
25  */
26 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
27 static THD_WORKING_AREA(_irq_handler_wa, 512);
28 #define TIMEOUT_PRIORITY 181
29 #define EVT_TIMEOUT EVENT_MASK(0)
30 #define EVT_IRQ EVENT_MASK(1)
31 #endif
32 
33 #ifndef CYRF_SPI_DEVICE
34 # define CYRF_SPI_DEVICE "cypress"
35 #endif
36 
37 #ifndef CYRF_IRQ_INPUT
38 # define CYRF_IRQ_INPUT (GPIO_INPUT|GPIO_FLOAT|GPIO_EXTI|GPIO_PORTD|GPIO_PIN15)
39 #endif
40 
41 #ifndef CYRF_RESET_PIN
42 # define CYRF_RESET_PIN (GPIO_OUTPUT|GPIO_PUSHPULL|GPIO_EXTI|GPIO_PORTB|GPIO_PIN0)
43 #endif
44 
45 extern const AP_HAL::HAL& hal;
46 
47 #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { hal.console->printf(fmt, ##args); }} while (0)
48 
49 #define LP_FIFO_SIZE 16 // Physical data FIFO lengths in Radio
50 
51 /* The SPI interface defines */
52 enum {
53  CYRF_CHANNEL = 0x00,
54  CYRF_TX_LENGTH = 0x01,
55  CYRF_TX_CTRL = 0x02,
56  CYRF_TX_CFG = 0x03,
57  CYRF_TX_IRQ_STATUS = 0x04,
58  CYRF_RX_CTRL = 0x05,
59  CYRF_RX_CFG = 0x06,
60  CYRF_RX_IRQ_STATUS = 0x07,
61  CYRF_RX_STATUS = 0x08,
62  CYRF_RX_COUNT = 0x09,
63  CYRF_RX_LENGTH = 0x0A,
64  CYRF_PWR_CTRL = 0x0B,
65  CYRF_XTAL_CTRL = 0x0C,
66  CYRF_IO_CFG = 0x0D,
67  CYRF_GPIO_CTRL = 0x0E,
68  CYRF_XACT_CFG = 0x0F,
69  CYRF_FRAMING_CFG = 0x10,
70  CYRF_DATA32_THOLD = 0x11,
71  CYRF_DATA64_THOLD = 0x12,
72  CYRF_RSSI = 0x13,
73  CYRF_EOP_CTRL = 0x14,
74  CYRF_CRC_SEED_LSB = 0x15,
75  CYRF_CRC_SEED_MSB = 0x16,
76  CYRF_TX_CRC_LSB = 0x17,
77  CYRF_TX_CRC_MSB = 0x18,
78  CYRF_RX_CRC_LSB = 0x19,
79  CYRF_RX_CRC_MSB = 0x1A,
80  CYRF_TX_OFFSET_LSB = 0x1B,
81  CYRF_TX_OFFSET_MSB = 0x1C,
82  CYRF_MODE_OVERRIDE = 0x1D,
83  CYRF_RX_OVERRIDE = 0x1E,
84  CYRF_TX_OVERRIDE = 0x1F,
85  CYRF_TX_BUFFER = 0x20,
86  CYRF_RX_BUFFER = 0x21,
87  CYRF_SOP_CODE = 0x22,
88  CYRF_DATA_CODE = 0x23,
89  CYRF_PREAMBLE = 0x24,
90  CYRF_MFG_ID = 0x25,
91  CYRF_XTAL_CFG = 0x26,
92  CYRF_CLK_OFFSET = 0x27,
93  CYRF_CLK_EN = 0x28,
94  CYRF_RX_ABORT = 0x29,
95  CYRF_AUTO_CAL_TIME = 0x32,
96  CYRF_AUTO_CAL_OFFSET = 0x35,
97  CYRF_ANALOG_CTRL = 0x39,
98 };
99 #define CYRF_DIR (1<<7)
101 // CYRF_MODE_OVERRIDE
102 #define CYRF_RST (1<<0)
103 
104 // CYRF_CLK_EN
105 #define CYRF_RXF (1<<1)
106 
107 // CYRF_XACT_CFG
108 enum {
109  CYRF_MODE_SLEEP = (0x0<<2),
110  CYRF_MODE_IDLE = (0x1<<2),
111  CYRF_MODE_SYNTH_TX = (0x2<<2),
112  CYRF_MODE_SYNTH_RX = (0x3<<2),
113  CYRF_MODE_RX = (0x4<<2),
114 };
115 #define CYRF_FRC_END (1<<5)
116 #define CYRF_ACK_EN (1<<7)
117 
118 // CYRF_IO_CFG
119 #define CYRF_IRQ_GPIO (1<<0)
120 #define CYRF_SPI_3PIN (1<<1)
121 #define CYRF_PACTL_GPIO (1<<2)
122 #define CYRF_PACTL_OD (1<<3)
123 #define CYRF_XOUT_OD (1<<4)
124 #define CYRF_MISO_OD (1<<5)
125 #define CYRF_IRQ_POL (1<<6)
126 #define CYRF_IRQ_OD (1<<7)
127 
128 // CYRF_FRAMING_CFG
129 #define CYRF_LEN_EN (1<<5)
130 #define CYRF_SOP_LEN (1<<6)
131 #define CYRF_SOP_EN (1<<7)
132 
133 // CYRF_RX_STATUS
134 enum {
135  CYRF_RX_DATA_MODE_GFSK = 0x00,
136  CYRF_RX_DATA_MODE_8DR = 0x01,
137  CYRF_RX_DATA_MODE_DDR = 0x10,
138  CYRF_RX_DATA_MODE_NV = 0x11,
139 };
140 #define CYRF_RX_CODE (1<<2)
141 #define CYRF_BAD_CRC (1<<3)
142 #define CYRF_CRC0 (1<<4)
143 #define CYRF_EOP_ERR (1<<5)
144 #define CYRF_PKT_ERR (1<<6)
145 #define CYRF_RX_ACK (1<<7)
146 
147 // CYRF_TX_IRQ_STATUS
148 #define CYRF_TXE_IRQ (1<<0)
149 #define CYRF_TXC_IRQ (1<<1)
150 #define CYRF_TXBERR_IRQ (1<<2)
151 #define CYRF_TXB0_IRQ (1<<3)
152 #define CYRF_TXB8_IRQ (1<<4)
153 #define CYRF_TXB15_IRQ (1<<5)
154 #define CYRF_LV_IRQ (1<<6)
155 #define CYRF_OS_IRQ (1<<7)
156 
157 // CYRF_RX_IRQ_STATUS
158 #define CYRF_RXE_IRQ (1<<0)
159 #define CYRF_RXC_IRQ (1<<1)
160 #define CYRF_RXBERR_IRQ (1<<2)
161 #define CYRF_RXB1_IRQ (1<<3)
162 #define CYRF_RXB8_IRQ (1<<4)
163 #define CYRF_RXB16_IRQ (1<<5)
164 #define CYRF_SOPDET_IRQ (1<<6)
165 #define CYRF_RXOW_IRQ (1<<7)
166 
167 // CYRF_TX_CTRL
168 #define CYRF_TXE_IRQEN (1<<0)
169 #define CYRF_TXC_IRQEN (1<<1)
170 #define CYRF_TXBERR_IRQEN (1<<2)
171 #define CYRF_TXB0_IRQEN (1<<3)
172 #define CYRF_TXB8_IRQEN (1<<4)
173 #define CYRF_TXB15_IRQEN (1<<5)
174 #define CYRF_TX_CLR (1<<6)
175 #define CYRF_TX_GO (1<<7)
176 
177 // CYRF_RX_CTRL
178 #define CYRF_RXE_IRQEN (1<<0)
179 #define CYRF_RXC_IRQEN (1<<1)
180 #define CYRF_RXBERR_IRQEN (1<<2)
181 #define CYRF_RXB1_IRQEN (1<<3)
182 #define CYRF_RXB8_IRQEN (1<<4)
183 #define CYRF_RXB16_IRQEN (1<<5)
184 #define CYRF_RSVD (1<<6)
185 #define CYRF_RX_GO (1<<7)
186 
187 // CYRF_RX_OVERRIDE
188 #define CYRF_ACE (1<<1)
189 #define CYRF_DIS_RXCRC (1<<2)
190 #define CYRF_DIS_CRC0 (1<<3)
191 #define CYRF_FRC_RXDR (1<<4)
192 #define CYRF_MAN_RXACK (1<<5)
193 #define CYRF_RXTX_DLY (1<<6)
194 #define CYRF_ACK_RX (1<<7)
195 
196 // CYRF_TX_OVERRIDE
197 #define CYRF_TX_INV (1<<0)
198 #define CYRF_DIS_TXCRC (1<<2)
199 #define CYRF_OVRD_ACK (1<<3)
200 #define CYRF_MAN_TXACK (1<<4)
201 #define CYRF_FRC_PRE (1<<6)
202 #define CYRF_ACK_TX (1<<7)
203 
204 // CYRF_RX_CFG
205 #define CYRF_VLD_EN (1<<0)
206 #define CYRF_RXOW_EN (1<<1)
207 #define CYRF_FAST_TURN_EN (1<<3)
208 #define CYRF_HILO (1<<4)
209 #define CYRF_ATT (1<<5)
210 #define CYRF_LNA (1<<6)
211 #define CYRF_AGC_EN (1<<7)
212 
213 // CYRF_TX_CFG
214 enum {
215  CYRF_PA_M35 = 0x0,
216  CYRF_PA_M30 = 0x1,
217  CYRF_PA_M24 = 0x2,
218  CYRF_PA_M18 = 0x3,
219  CYRF_PA_M13 = 0x4,
220  CYRF_PA_M5 = 0x5,
221  CYRF_PA_0 = 0x6,
222  CYRF_PA_4 = 0x7,
223 };
224 enum {
225  CYRF_DATA_MODE_GFSK = (0x0 <<3),
226  CYRF_DATA_MODE_8DR = (0x1 <<3),
227  CYRF_DATA_MODE_DDR = (0x2 <<3),
228  CYRF_DATA_MODE_SDR = (0x3 <<3),
229 };
230 #define CYRF_DATA_CODE_LENGTH (1<<5)
231 
232 
233 #define FLAG_WRITE 0x80
234 #define FLAG_AUTO_INC 0x40
235 
236 #define DSM_MAX_CHANNEL 0x4F
237 
238 #define DSM_SCAN_MIN_CH 8
239 #define DSM_SCAN_MID_CH 40
240 #define DSM_SCAN_MAX_CH 70
241 
242 #define FCC_SUPPORT_CW_MODE 0
243 
244 #define AUTOBIND_CHANNEL 12
245 
246 // object instance for trampoline
248 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
249 thread_t *AP_Radio_cypress::_irq_handler_ctx;
250 #endif
251 /*
252  constructor
253  */
255  AP_Radio_backend(_radio)
256 {
257  // link to instance for irq_trampoline
258  radio_instance = this;
259 }
260 
261 /*
262  initialise radio
263  */
264 bool AP_Radio_cypress::init(void)
265 {
266  dev = hal.spi->get_device(CYRF_SPI_DEVICE);
267 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
268  if(_irq_handler_ctx != nullptr) {
269  AP_HAL::panic("AP_Radio_cypress: double instantiation of irq_handler\n");
270  }
271  chVTObjectInit(&timeout_vt);
272  _irq_handler_ctx = chThdCreateStatic(_irq_handler_wa,
273  sizeof(_irq_handler_wa),
274  TIMEOUT_PRIORITY, /* Initial priority. */
275  irq_handler_thd, /* Thread function. */
276  NULL); /* Thread parameter. */
277 #endif
278  load_bind_info();
279 
280  sem = hal.util->new_semaphore();
281 
282  return reset();
283 }
284 
285 /*
286  reset radio
287  */
288 bool AP_Radio_cypress::reset(void)
289 {
291  return false;
292  }
293 
294  /*
295  to reset radio hold reset high for 0.5s, then low for 0.5s
296  */
297 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
298  stm32_configgpio(CYRF_RESET_PIN);
299  stm32_gpiowrite(CYRF_RESET_PIN, 1);
300  hal.scheduler->delay(500);
301  stm32_gpiowrite(CYRF_RESET_PIN, 0);
302  hal.scheduler->delay(500);
303  // use AUX5 as radio IRQ pin
304  stm32_configgpio(CYRF_IRQ_INPUT);
305 #elif defined(HAL_GPIO_RADIO_RESET)
306  hal.gpio->write(HAL_GPIO_RADIO_RESET, 1);
307  hal.scheduler->delay(500);
308  hal.gpio->write(HAL_GPIO_RADIO_RESET, 0);
309  hal.scheduler->delay(500);
310 #endif
311  radio_init();
312  dev->get_semaphore()->give();
313 
314  if (dsm.protocol == DSM_NONE &&
315  get_autobind_time() == 0) {
316  start_recv_bind();
317  }
318 
319  return true;
320 }
321 
322 /*
323  return statistics structure from radio
324  */
326 {
327  return stats;
328 }
329 
330 /*
331  read one pwm channel from radio
332  */
333 uint16_t AP_Radio_cypress::read(uint8_t chan)
334 {
335  if (dsm.need_bind_save) {
336  save_bind_info();
337  }
338  if (chan >= max_channels) {
339  return 0;
340  }
341  return dsm.pwm_channels[chan];
342 }
343 
344 /*
345  update status - called from main thread
346  */
347 void AP_Radio_cypress::update(void)
348 {
349  check_fw_ack();
350 }
351 
352 
353 /*
354  print one second debug info
355  */
357 {
358  Debug(2, "recv:%3u bad:%3u to:%3u re:%u N:%2u TXI:%u TX:%u 1:%4u 2:%4u 3:%4u 4:%4u 5:%4u 6:%4u 7:%4u 8:%4u 14:%u\n",
361  unsigned(stats.timeouts - last_stats.timeouts),
363  num_channels(),
364  unsigned(dsm.send_irq_count),
365  unsigned(dsm.send_count),
366  dsm.pwm_channels[0], dsm.pwm_channels[1], dsm.pwm_channels[2], dsm.pwm_channels[3],
367  dsm.pwm_channels[4], dsm.pwm_channels[5], dsm.pwm_channels[6], dsm.pwm_channels[7],
368  dsm.pwm_channels[13]);
369 }
370 
371 /*
372  return number of active channels
373  */
374 uint8_t AP_Radio_cypress::num_channels(void)
375 {
376  uint32_t now = AP_HAL::millis();
377  uint8_t chan = get_rssi_chan();
378  if (chan > 0) {
379  dsm.pwm_channels[chan-1] = dsm.rssi;
380  dsm.num_channels = MAX(dsm.num_channels, chan);
381  }
382 
383  chan = get_pps_chan();
384  if (chan > 0) {
385  dsm.pwm_channels[chan-1] = t_status.pps;
386  dsm.num_channels = MAX(dsm.num_channels, chan);
387  }
388 
389  chan = get_tx_rssi_chan();
390  if (chan > 0) {
391  dsm.pwm_channels[chan-1] = dsm.tx_rssi;
392  dsm.num_channels = MAX(dsm.num_channels, chan);
393  }
394 
395  chan = get_tx_pps_chan();
396  if (chan > 0) {
397  dsm.pwm_channels[chan-1] = dsm.tx_pps;
398  dsm.num_channels = MAX(dsm.num_channels, chan);
399  }
400 
401  if (now - last_debug_print_ms > 1000) {
402  last_debug_print_ms = now;
403  if (get_debug_level() > 1) {
404  print_debug_info();
405  }
406 
408  t_status.rssi = (uint8_t)dsm.rssi;
409  last_stats = stats;
410  }
411 
412  return dsm.num_channels;
413 }
414 
415 /*
416  send a fwupload ack if needed
417  */
419 {
420  Debug(4,"check need_ack\n");
421  if (fwupload.need_ack && sem->take_nonblocking()) {
422  // ack the send of a DATA96 fw packet to TX
423  fwupload.need_ack = false;
424  uint8_t data16[16] {};
425  uint32_t ack_to = fwupload.offset + fwupload.acked;
426  memcpy(&data16[0], &ack_to, 4);
427  mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
428  Debug(4,"sent ack DATA16\n");
429  sem->give();
430  }
431 }
432 
433 /*
434  return time of last receive in microseconds
435  */
436 uint32_t AP_Radio_cypress::last_recv_us(void)
437 {
438  // we use the parse time, so it matches when channel values are filled in
439  return dsm.last_parse_us;
440 }
441 
442 /*
443  send len bytes as a single packet
444  */
445 bool AP_Radio_cypress::send(const uint8_t *pkt, uint16_t len)
446 {
447  // disabled for now
448  return false;
449 }
450 
451 /* The PN codes */
452 const uint8_t AP_Radio_cypress::pn_codes[5][9][8] = {
453 { /* Row 0 */
454  /* Col 0 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8},
455  /* Col 1 */ {0x88, 0x17, 0x13, 0x3B, 0x2D, 0xBF, 0x06, 0xD6},
456  /* Col 2 */ {0xF1, 0x94, 0x30, 0x21, 0xA1, 0x1C, 0x88, 0xA9},
457  /* Col 3 */ {0xD0, 0xD2, 0x8E, 0xBC, 0x82, 0x2F, 0xE3, 0xB4},
458  /* Col 4 */ {0x8C, 0xFA, 0x47, 0x9B, 0x83, 0xA5, 0x66, 0xD0},
459  /* Col 5 */ {0x07, 0xBD, 0x9F, 0x26, 0xC8, 0x31, 0x0F, 0xB8},
460  /* Col 6 */ {0xEF, 0x03, 0x95, 0x89, 0xB4, 0x71, 0x61, 0x9D},
461  /* Col 7 */ {0x40, 0xBA, 0x97, 0xD5, 0x86, 0x4F, 0xCC, 0xD1},
462  /* Col 8 */ {0xD7, 0xA1, 0x54, 0xB1, 0x5E, 0x89, 0xAE, 0x86}
463 },
464 { /* Row 1 */
465  /* Col 0 */ {0x83, 0xF7, 0xA8, 0x2D, 0x7A, 0x44, 0x64, 0xD3},
466  /* Col 1 */ {0x3F, 0x2C, 0x4E, 0xAA, 0x71, 0x48, 0x7A, 0xC9},
467  /* Col 2 */ {0x17, 0xFF, 0x9E, 0x21, 0x36, 0x90, 0xC7, 0x82},
468  /* Col 3 */ {0xBC, 0x5D, 0x9A, 0x5B, 0xEE, 0x7F, 0x42, 0xEB},
469  /* Col 4 */ {0x24, 0xF5, 0xDD, 0xF8, 0x7A, 0x77, 0x74, 0xE7},
470  /* Col 5 */ {0x3D, 0x70, 0x7C, 0x94, 0xDC, 0x84, 0xAD, 0x95},
471  /* Col 6 */ {0x1E, 0x6A, 0xF0, 0x37, 0x52, 0x7B, 0x11, 0xD4},
472  /* Col 7 */ {0x62, 0xF5, 0x2B, 0xAA, 0xFC, 0x33, 0xBF, 0xAF},
473  /* Col 8 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97}
474 },
475 { /* Row 2 */
476  /* Col 0 */ {0x40, 0x56, 0x32, 0xD9, 0x0F, 0xD9, 0x5D, 0x97},
477  /* Col 1 */ {0x8E, 0x4A, 0xD0, 0xA9, 0xA7, 0xFF, 0x20, 0xCA},
478  /* Col 2 */ {0x4C, 0x97, 0x9D, 0xBF, 0xB8, 0x3D, 0xB5, 0xBE},
479  /* Col 3 */ {0x0C, 0x5D, 0x24, 0x30, 0x9F, 0xCA, 0x6D, 0xBD},
480  /* Col 4 */ {0x50, 0x14, 0x33, 0xDE, 0xF1, 0x78, 0x95, 0xAD},
481  /* Col 5 */ {0x0C, 0x3C, 0xFA, 0xF9, 0xF0, 0xF2, 0x10, 0xC9},
482  /* Col 6 */ {0xF4, 0xDA, 0x06, 0xDB, 0xBF, 0x4E, 0x6F, 0xB3},
483  /* Col 7 */ {0x9E, 0x08, 0xD1, 0xAE, 0x59, 0x5E, 0xE8, 0xF0},
484  /* Col 8 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E}
485 },
486 { /* Row 3 */
487  /* Col 0 */ {0xC0, 0x90, 0x8F, 0xBB, 0x7C, 0x8E, 0x2B, 0x8E},
488  /* Col 1 */ {0x80, 0x69, 0x26, 0x80, 0x08, 0xF8, 0x49, 0xE7},
489  /* Col 2 */ {0x7D, 0x2D, 0x49, 0x54, 0xD0, 0x80, 0x40, 0xC1},
490  /* Col 3 */ {0xB6, 0xF2, 0xE6, 0x1B, 0x80, 0x5A, 0x36, 0xB4},
491  /* Col 4 */ {0x42, 0xAE, 0x9C, 0x1C, 0xDA, 0x67, 0x05, 0xF6},
492  /* Col 5 */ {0x9B, 0x75, 0xF7, 0xE0, 0x14, 0x8D, 0xB5, 0x80},
493  /* Col 6 */ {0xBF, 0x54, 0x98, 0xB9, 0xB7, 0x30, 0x5A, 0x88},
494  /* Col 7 */ {0x35, 0xD1, 0xFC, 0x97, 0x23, 0xD4, 0xC9, 0x88},
495  /* Col 8 */ {0x88, 0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40}
496 },
497 { /* Row 4 */
498  /* Col 0 */ {0xE1, 0xD6, 0x31, 0x26, 0x5F, 0xBD, 0x40, 0x93},
499  /* Col 1 */ {0xDC, 0x68, 0x08, 0x99, 0x97, 0xAE, 0xAF, 0x8C},
500  /* Col 2 */ {0xC3, 0x0E, 0x01, 0x16, 0x0E, 0x32, 0x06, 0xBA},
501  /* Col 3 */ {0xE0, 0x83, 0x01, 0xFA, 0xAB, 0x3E, 0x8F, 0xAC},
502  /* Col 4 */ {0x5C, 0xD5, 0x9C, 0xB8, 0x46, 0x9C, 0x7D, 0x84},
503  /* Col 5 */ {0xF1, 0xC6, 0xFE, 0x5C, 0x9D, 0xA5, 0x4F, 0xB7},
504  /* Col 6 */ {0x58, 0xB5, 0xB3, 0xDD, 0x0E, 0x28, 0xF1, 0xB0},
505  /* Col 7 */ {0x5F, 0x30, 0x3B, 0x56, 0x96, 0x45, 0xF4, 0xA1},
506  /* Col 8 */ {0x03, 0xBC, 0x6E, 0x8A, 0xEF, 0xBD, 0xFE, 0xF8}
507 },
508 };
509 const uint8_t AP_Radio_cypress::pn_bind[] = { 0x98, 0x88, 0x1B, 0xE4, 0x30, 0x79, 0x03, 0x84 };
510 
511 /*The CYRF initial config, binding config and transfer config */
513  {CYRF_MODE_OVERRIDE, CYRF_RST}, // Reset the device
514  {CYRF_CLK_EN, CYRF_RXF}, // Enable the clock
515  {CYRF_AUTO_CAL_TIME, 0x3C}, // From manual, needed for initialization
516  {CYRF_AUTO_CAL_OFFSET, 0x14}, // From manual, needed for initialization
517  {CYRF_RX_CFG, CYRF_LNA | CYRF_FAST_TURN_EN}, // Enable low noise amplifier and fast turning
518  {CYRF_TX_OFFSET_LSB, 0x55}, // From manual, typical configuration
519  {CYRF_TX_OFFSET_MSB, 0x05}, // From manual, typical configuration
520  {CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END}, // Force in Synth RX mode
521  {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_SDR | CYRF_PA_4}, // Enable 64 chip codes, SDR mode and amplifier +4dBm
522  {CYRF_DATA64_THOLD, 0x0E}, // From manual, typical configuration
523  {CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX}, // Set in Synth RX mode (again, really needed?)
524  {CYRF_IO_CFG, CYRF_IRQ_POL}, // IRQ active high
525 };
526 
528  {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_SDR | CYRF_PA_4}, // Enable 64 chip codes, SDR mode and amplifier +4dBm
529  {CYRF_FRAMING_CFG, CYRF_SOP_LEN | 0xE}, // Set SOP CODE to 64 chips and SOP Correlator Threshold to 0xE
530  {CYRF_RX_OVERRIDE, CYRF_FRC_RXDR | CYRF_DIS_RXCRC}, // Force receive data rate and disable receive CRC checker
531  {CYRF_EOP_CTRL, 0x02}, // Only enable EOP symbol count of 2
532  {CYRF_TX_OVERRIDE, CYRF_DIS_TXCRC}, // Disable transmit CRC generate
533 };
535  {CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_8DR | CYRF_PA_4}, // Enable 64 chip codes, 8DR mode and amplifier +4dBm
536  {CYRF_FRAMING_CFG, CYRF_SOP_EN | CYRF_SOP_LEN | CYRF_LEN_EN | 0xE}, // Set SOP CODE enable, SOP CODE to 64 chips, Packet length enable, and SOP Correlator Threshold to 0xE
537  {CYRF_TX_OVERRIDE, 0x00}, // Reset TX overrides
538  {CYRF_RX_OVERRIDE, 0x00}, // Reset RX overrides
539 };
540 
541 /*
542  read radio status, handling the race condition between completion and error
543  */
544 uint8_t AP_Radio_cypress::read_status_debounced(uint8_t adr)
545 {
546  uint8_t ret;
547 
548  dev->set_chip_select(true);
549  ret = read_register(adr);
550 
551  // If COMPLETE and ERROR bits mismatch, then re-read register
552  if ((ret & (CYRF_RXC_IRQ | CYRF_RXE_IRQ)) != 0
553  && (ret & (CYRF_RXC_IRQ | CYRF_RXE_IRQ)) != (CYRF_RXC_IRQ | CYRF_RXE_IRQ)) {
554  uint8_t v2;
555  dev->read(&v2, 1);
556  ret |= v2; // re-read and make bits sticky
557  }
558  dev->set_chip_select(false);
559  return ret;
560 }
561 
562 /*
563  force the initial state of the radio
564  */
566 {
567  while (true) {
568  write_register(CYRF_XACT_CFG, CYRF_FRC_END);
569  uint32_t start_ms = AP_HAL::millis();
570  do {
571  if ((read_register(CYRF_XACT_CFG) & CYRF_FRC_END) == 0) {
572  return; // FORCE_END done (osc running)
573  }
574  } while (AP_HAL::millis() - start_ms < 5);
575 
576  // FORCE_END failed to complete, implying going SLEEP to IDLE and
577  // oscillator failed to start. Recover by returning to SLEEP and
578  // trying to start oscillator again.
579  write_register(CYRF_XACT_CFG, CYRF_MODE_SLEEP);
580  }
581 }
582 
583 /*
584  set desired channel
585  */
586 void AP_Radio_cypress::set_channel(uint8_t channel)
587 {
588  if (dsm.forced_channel != -1) {
589  channel = dsm.forced_channel;
590  }
591  write_register(CYRF_CHANNEL, channel);
592 }
593 
594 void AP_Radio_cypress::radio_set_config(const struct config *conf, uint8_t size)
595 {
596  // setup required radio config
597  for (uint8_t i=0; i<size; i++) {
598  write_register(conf[i].reg, conf[i].value);
599  }
600 }
601 
602 /*
603  initialise the radio
604  */
606 {
607  Debug(1, "Cypress: radio_init starting\n");
608 
609  // wait for radio to settle
610  uint16_t i;
611  for (i=0; i<1000; i++) {
612  uint8_t chan = read_register(CYRF_CHANNEL);
613  if (chan == 1) {
614  break;
615  }
616  write_register(CYRF_CHANNEL, 1);
617  hal.scheduler->delay(10);
618  }
619  if (i == 1000) {
620  Debug(1, "Cypress: radio_init failed\n");
621  return;
622  }
623 
624  // base config
625  radio_set_config(cyrf_config, ARRAY_SIZE(cyrf_config));
626 
627  // start with receive config
628  radio_set_config(cyrf_transfer_config, ARRAY_SIZE(cyrf_transfer_config));
629 
630  if (get_disable_crc()) {
631  write_register(CYRF_RX_OVERRIDE, CYRF_DIS_RXCRC);
632  }
633 
634  dsm_setup_transfer_dsmx();
635 
636  write_register(CYRF_XTAL_CTRL,0x80); // XOUT=BitSerial
637  force_initial_state();
638  write_register(CYRF_PWR_CTRL,0x20); // Disable PMU
639 
640  // start in RECV state
641  state = STATE_RECV;
642 
643  Debug(1, "Cypress: radio_init done\n");
644 
645  start_receive();
646 
647  // setup handler for rising edge of IRQ pin
648 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
649  stm32_gpiosetevent(CYRF_IRQ_INPUT, true, false, false, irq_radio_trampoline);
650 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
652 #endif
653 }
654 
655 void AP_Radio_cypress::dump_registers(uint8_t n)
656 {
657  for (uint8_t i=0; i<n; i++) {
658  uint8_t v = read_register(i);
659  printf("%02x:%02x ", i, v);
660  if ((i+1) % 16 == 0) {
661  printf("\n");
662  }
663  }
664  if (n % 16 != 0) {
665  printf("\n");
666  }
667 }
668 
669 /*
670  read one register value
671  */
672 uint8_t AP_Radio_cypress::read_register(uint8_t reg)
673 {
674  uint8_t v = 0;
675  (void)dev->read_registers(reg, &v, 1);
676  return v;
677 }
678 
679 
680 /*
681  write multiple bytes
682  */
683 void AP_Radio_cypress::write_multiple(uint8_t reg, uint8_t n, const uint8_t *data)
684 {
685  uint8_t pkt[n+1];
686  pkt[0] = reg | FLAG_WRITE;
687  memcpy(&pkt[1], data, n);
688  dev->transfer(pkt, n+1, nullptr, 0);
689 }
690 
691 /*
692  write one register value
693  */
694 void AP_Radio_cypress::write_register(uint8_t reg, uint8_t value)
695 {
696  dev->write_register(reg | FLAG_WRITE, value);
697 }
698 
699 
700 /*
701  support all 4 rc input modes by swapping channels.
702  */
704 {
705  switch (get_stick_mode()) {
706  case 1: {
707  // mode1
708  uint16_t tmp = channels[1];
709  channels[1] = 3000 - channels[2];
710  channels[2] = 3000 - tmp;
711  break;
712  }
713 
714  case 3: {
715  // mode3
716  uint16_t tmp = channels[1];
717  channels[1] = 3000 - channels[2];
718  channels[2] = 3000 - tmp;
719  tmp = channels[0];
720  channels[0] = channels[3];
721  channels[3] = tmp;
722  break;
723  }
724 
725  case 4: {
726  // mode4
727  uint16_t tmp = channels[0];
728  channels[0] = channels[3];
729  channels[3] = tmp;
730  break;
731  }
732 
733  case 2:
734  default:
735  // nothing to do, transmitter is natively mode2
736  break;
737  }
738 }
739 
740 /*
741  check if we are the 2nd RX bound to this TX
742  */
744 {
745  if (dsm.tx_pps <= dsm.telem_send_count ||
746  get_autobind_time() == 0) {
747  return;
748  }
749  // the TX has received more telemetry packets in the last second
750  // than we have ever sent. There must be another RX sending
751  // telemetry packets. We will reset our mfg_id and go back waiting
752  // for a new bind packet, hopefully with the right TX
753  Debug(1,"Double-bind detected\n");
754  memset(dsm.mfg_id, 1, sizeof(dsm.mfg_id));
755  dsm.last_recv_us = 0;
756  dsm_setup_transfer_dsmx();
757 }
758 
759 /*
760  parse channels from a packet
761  */
762 bool AP_Radio_cypress::parse_dsm_channels(const uint8_t *data)
763 {
764  uint16_t num_values = 0;
765  uint16_t pwm_channels[max_channels] {};
766 
767  // default value for channels above 4 is previous value
768  memcpy(&pwm_channels[4], &dsm.pwm_channels[4], (max_channels-4)*sizeof(uint16_t));
769 
771  data,
772  pwm_channels,
773  &num_values,
775  // invalid packet
776  Debug(2, "DSM: bad decode\n");
777  return false;
778  }
779  if (num_values < 5) {
780  Debug(2, "DSM: num_values=%u\n", num_values);
781  return false;
782  }
783 
784  // cope with mode1/mode2
785  map_stick_mode(pwm_channels);
786 
787  memcpy(dsm.pwm_channels, pwm_channels, num_values*sizeof(uint16_t));
788 
789  dsm.last_parse_us = AP_HAL::micros();
790 
791  // suppress channel 8 ack values
792  dsm.num_channels = num_values==8?7:num_values;
793 
794  if (num_values == 8) {
795  // decode telemetry ack value and version
796  uint16_t d=0;
797  if (is_DSM2()) {
798  d = data[14] << 8 | data[15];
799  } else {
800  // see chan_order[] for DSMX
801  d = data[10] << 8 | data[11];
802  }
803  // extra data is sent on channel 8, with 3 bit key and 8 bit data
804  uint8_t chan = d>>11;
805  uint8_t key = (d >> 8) & 0x7;
806  uint8_t v = d & 0xFF;
807  if (chan == 7 && key == 0) {
808  // got an ack from key 0
809  Debug(4, "ack %u seq=%u acked=%u length=%u len=%u\n",
810  v, fwupload.sequence, unsigned(fwupload.acked), unsigned(fwupload.length), fwupload.len);
811  if (fwupload.sequence == v && sem->take_nonblocking()) {
812  fwupload.sequence++;
813  fwupload.acked += fwupload.len;
814  if (fwupload.acked == fwupload.length) {
815  // trigger send of DATA16 ack to client
816  fwupload.need_ack = true;
817  }
818  sem->give();
819  }
820  }
821  if (chan == 7) {
822  // extract telemetry extra data
823  switch (key) {
824  case 1:
825  dsm.tx_firmware_year = v;
826  break;
827  case 2:
828  dsm.tx_firmware_month = v;
829  break;
830  case 3:
831  dsm.tx_firmware_day = v;
832  break;
833  case 4:
834  dsm.tx_rssi = v;
835  break;
836  case 5:
837  dsm.tx_pps = v;
838  dsm.have_tx_pps = true;
839  check_double_bind();
840  break;
841  case 6:
842  if (v != dsm.tx_bl_version) {
843  if (v == 2) {
844  // TX with new filter gets a default power of 6
846  }
847  }
848  dsm.tx_bl_version = v;
849  break;
850  }
851  }
852  }
853  return true;
854 }
855 
856 /*
857  process an incoming bind packet
858  */
859 void AP_Radio_cypress::process_bind(const uint8_t *pkt, uint8_t len)
860 {
861  if (len != 16) {
862  return;
863  }
864  bool ok = (len==16 && pkt[0] == pkt[4] && pkt[1] == pkt[5] && pkt[2] == pkt[6] && pkt[3] == pkt[7]);
865 
866  // Calculate the first sum
867  uint16_t bind_sum = 384 - 0x10;
868  for (uint8_t i = 0; i < 8; i++) {
869  bind_sum += pkt[i];
870  }
871 
872  // Check the first sum
873  if (pkt[8] != bind_sum >> 8 || pkt[9] != (bind_sum & 0xFF)) {
874  ok = false;
875  }
876 
877  // Calculate second sum
878  for (uint8_t i = 8; i < 14; i++) {
879  bind_sum += pkt[i];
880  }
881 
882  // Check the second sum
883  if (pkt[14] != bind_sum >> 8 || pkt[15] != (bind_sum & 0xFF)) {
884  ok = false;
885  }
886 
887  if (state == STATE_AUTOBIND) {
888  uint8_t rssi = read_register(CYRF_RSSI) & 0x1F;
889  Debug(3,"bind RSSI %u\n", rssi);
890  if (rssi < get_autobind_rssi()) {
891  ok = false;
892  }
893  }
894 
895  if (ok) {
896  uint8_t mfg_id[4] = {uint8_t(~pkt[0]), uint8_t(~pkt[1]), uint8_t(~pkt[2]), uint8_t(~pkt[3])};
897  uint8_t num_chan = pkt[11];
898  uint8_t protocol = pkt[12];
899  (void)num_chan;
900  // change to normal receive
901  memcpy(dsm.mfg_id, mfg_id, 4);
902  state = STATE_RECV;
903 
904  radio_set_config(cyrf_transfer_config, ARRAY_SIZE(cyrf_transfer_config));
905 
906  if (get_disable_crc()) {
907  write_register(CYRF_RX_OVERRIDE, CYRF_DIS_RXCRC);
908  }
909 
910  dsm.protocol = (enum dsm_protocol)protocol;
911  dsm_setup_transfer_dsmx();
912 
913  Debug(1, "BIND OK: mfg_id={0x%02x, 0x%02x, 0x%02x, 0x%02x} N=%u P=0x%02x DSM2=%u\n",
914  mfg_id[0], mfg_id[1], mfg_id[2], mfg_id[3],
915  num_chan,
916  protocol,
917  is_DSM2());
918 
919  dsm.last_recv_us = AP_HAL::micros();
920 
921  if (is_DSM2()) {
922  dsm2_start_sync();
923  }
924 
925  dsm.need_bind_save = true;
926  }
927 }
928 
929 /*
930  start DSM2 sync
931  */
933 {
934  uint8_t factory_test = get_factory_test();
935  if (factory_test != 0) {
936  dsm.channels[0] = (factory_test*7) % DSM_MAX_CHANNEL;
937  dsm.channels[1] = (dsm.channels[0] + 5) % DSM_MAX_CHANNEL;
938  dsm.sync = DSM2_OK;
939  } else {
940  Debug(2, "DSM2 start sync\n");
941  dsm.sync = DSM2_SYNC_A;
942  }
943 }
944 
945 /*
946  setup a timeout in timeout_ms milliseconds
947  */
948 void AP_Radio_cypress::setup_timeout(uint32_t timeout_ms)
949 {
950 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
951  hrt_call_after(&wait_call, timeout_ms*1000, (hrt_callout)irq_timeout_trampoline, nullptr);
952 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
953  chVTSet(&timeout_vt, MS2ST(timeout_ms), trigger_timeout_event, nullptr);
954 #endif
955 }
956 
957 /*
958  process an incoming packet
959  */
960 void AP_Radio_cypress::process_packet(const uint8_t *pkt, uint8_t len)
961 {
962  if (len == 16) {
963  bool ok;
964  const uint8_t *id = dsm.mfg_id;
965  uint32_t now = AP_HAL::micros();
966 
967  if (is_DSM2()) {
968  ok = (pkt[0] == ((~id[2])&0xFF) && pkt[1] == (~id[3]&0xFF));
969  } else {
970  ok = (pkt[0] == id[2] && pkt[1] == id[3]);
971  }
972  if (ok && is_DSM2() && dsm.sync < DSM2_OK) {
973  if (dsm.sync == DSM2_SYNC_A) {
974  dsm.channels[0] = dsm.current_rf_channel;
975  dsm.sync = DSM2_SYNC_B;
976  Debug(2, "DSM2 SYNCA chan=%u\n", dsm.channels[0]);
977  dsm.last_recv_us = now;
978  } else {
979  if (dsm.current_rf_channel != dsm.channels[0]) {
980  dsm.channels[1] = dsm.current_rf_channel;
981  dsm.sync = DSM2_OK;
982  Debug(2, "DSM2 SYNCB chan=%u\n", dsm.channels[1]);
983  dsm.last_recv_us = now;
984  }
985  }
986  return;
987  }
988  if (ok && (!is_DSM2() || dsm.sync >= DSM2_SYNC_B)) {
989  ok = parse_dsm_channels(pkt);
990  }
991  if (ok) {
992  uint32_t packet_dt_us = now - dsm.last_recv_us;
993 
994  dsm.last_recv_chan = dsm.current_channel;
995  dsm.last_recv_us = now;
996  if (dsm.crc_errors > 2) {
997  dsm.crc_errors -= 2;
998  }
999 
1000  stats.recv_packets++;
1001 
1002  // sample the RSSI
1003  uint8_t rssi = read_register(CYRF_RSSI) & 0x1F;
1004  dsm.rssi = 0.95 * dsm.rssi + 0.05 * rssi;
1005 
1006  if (packet_dt_us < 5000) {
1007  dsm.pkt_time1 = packet_dt_us;
1008  } else if (packet_dt_us < 8000) {
1009  dsm.pkt_time2 = packet_dt_us;
1010  }
1011 
1012  if (get_telem_enable()) {
1013  if (packet_dt_us < 5000 &&
1014  (get_autobind_time() == 0 || dsm.have_tx_pps)) {
1015  /*
1016  we have just received two packets rapidly, which
1017  means we have about 7ms before the next
1018  one. That gives time for a telemetry packet. We
1019  send it 1ms after we receive the incoming packet
1020 
1021  If auto-bind is enabled we don't send telemetry
1022  till we've received a tx_pps value from the
1023  TX. This allows us to detect double binding (two
1024  RX bound to the same TX)
1025  */
1026  state = STATE_SEND_TELEM;
1027  setup_timeout(1);
1028  }
1029  }
1030  } else {
1031  stats.bad_packets++;
1032  }
1033  } else {
1034  stats.bad_packets++;
1035  }
1036 }
1037 
1038 
1039 /*
1040  start packet receive
1041  */
1043 {
1044  dsm_choose_channel();
1045 
1046  write_register(CYRF_RX_IRQ_STATUS, CYRF_RXOW_IRQ);
1047  write_register(CYRF_RX_CTRL, CYRF_RX_GO | CYRF_RXC_IRQEN | CYRF_RXE_IRQEN);
1048 
1049  dsm.receive_start_us = AP_HAL::micros();
1050  if (state == STATE_AUTOBIND) {
1051  dsm.receive_timeout_msec = 90;
1052  } else if (state == STATE_BIND) {
1053  dsm.receive_timeout_msec = 15;
1054  } else {
1055  dsm.receive_timeout_msec = 12;
1056  }
1057  setup_timeout(dsm.receive_timeout_msec);
1058 }
1059 
1060 /*
1061  handle a receive IRQ
1062  */
1063 void AP_Radio_cypress::irq_handler_recv(uint8_t rx_status)
1064 {
1065  if ((rx_status & (CYRF_RXC_IRQ | CYRF_RXE_IRQ)) == 0) {
1066  // nothing interesting yet
1067  return;
1068  }
1069 
1070  uint8_t pkt[16];
1071  uint8_t rlen = read_register(CYRF_RX_COUNT);
1072  if (rlen > 16) {
1073  rlen = 16;
1074  }
1075  if (rlen > 0) {
1076  dev->read_registers(CYRF_RX_BUFFER, pkt, rlen);
1077  }
1078 
1079  if (rx_status & CYRF_RXE_IRQ) {
1080  uint8_t reason = read_register(CYRF_RX_STATUS);
1081  if (reason & CYRF_BAD_CRC) {
1082  dsm.crc_errors++;
1083  if (dsm.crc_errors > 20) {
1084  Debug(2, "Flip CRC\n");
1085  // flip crc seed, this allows us to resync with transmitter
1086  dsm.crc_seed = ~dsm.crc_seed;
1087  dsm.crc_errors = 0;
1088  }
1089  }
1090  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END);
1091  write_register(CYRF_RX_ABORT, 0);
1092  stats.recv_errors++;
1093  } else if (rx_status & CYRF_RXC_IRQ) {
1094  if (state == STATE_RECV) {
1095  process_packet(pkt, rlen);
1096  } else {
1097  process_bind(pkt, rlen);
1098  }
1099  }
1100 
1101  if (state == STATE_AUTOBIND) {
1102  state = STATE_RECV;
1103  }
1104 
1105  if (state != STATE_SEND_TELEM) {
1106  start_receive();
1107  }
1108 }
1109 
1110 
1111 /*
1112  handle a send IRQ
1113  */
1114 void AP_Radio_cypress::irq_handler_send(uint8_t tx_status)
1115 {
1116  if ((tx_status & (CYRF_TXC_IRQ | CYRF_TXE_IRQ)) == 0) {
1117  // nothing interesting yet
1118  return;
1119  }
1120  state = STATE_RECV;
1121  start_receive();
1122 }
1123 
1124 
1125 /*
1126  IRQ handler
1127  */
1129 {
1130  //hal.console->printf("IRQ\n");
1131  if (!dev->get_semaphore()->take_nonblocking()) {
1132  // we have to wait for timeout instead
1133  return;
1134  }
1135  // always read both rx and tx status. This ensure IRQ is cleared
1136  uint8_t rx_status = read_status_debounced(CYRF_RX_IRQ_STATUS);
1137  uint8_t tx_status = read_status_debounced(CYRF_TX_IRQ_STATUS);
1138 
1139  switch (state) {
1140  case STATE_AUTOBIND:
1141  FALLTHROUGH;
1142  case STATE_RECV:
1143  case STATE_BIND:
1144  irq_handler_recv(rx_status);
1145  break;
1146 
1147  case STATE_SEND_TELEM:
1148  case STATE_SEND_TELEM_WAIT:
1149  irq_handler_send(tx_status);
1150  break;
1151 
1152  case STATE_SEND_FCC:
1153  // stop transmit oscillator
1154  write_register(CYRF_RX_IRQ_STATUS, CYRF_RXOW_IRQ);
1155  write_register(CYRF_RX_CTRL, CYRF_RX_GO | CYRF_RXC_IRQEN | CYRF_RXE_IRQEN);
1156  break;
1157 
1158  default:
1159  break;
1160  }
1161  dev->get_semaphore()->give();
1162 }
1163 
1164 /*
1165  called on radio timeout
1166  */
1168 {
1169  stats.timeouts++;
1170  if (!dev->get_semaphore()->take_nonblocking()) {
1171  // schedule a new timeout
1172  setup_timeout(dsm.receive_timeout_msec);
1173  return;
1174  }
1175 
1176  if (get_fcc_test() != 0 && state != STATE_SEND_FCC) {
1177  Debug(3,"Starting FCC test\n");
1178  state = STATE_SEND_FCC;
1179  } else if (get_fcc_test() == 0 && state == STATE_SEND_FCC) {
1180  Debug(3,"Ending FCC test\n");
1181  state = STATE_RECV;
1182  }
1183 
1184  switch (state) {
1185  case STATE_SEND_TELEM:
1186  send_telem_packet();
1187  break;
1188  case STATE_SEND_FCC:
1189  send_FCC_test_packet();
1190  break;
1191  case STATE_AUTOBIND:
1192  case STATE_SEND_TELEM_WAIT:
1193  state = STATE_RECV;
1194  FALLTHROUGH;
1195  default:
1196  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END);
1197  write_register(CYRF_RX_ABORT, 0);
1198  start_receive();
1199  break;
1200  }
1201 
1202  dev->get_semaphore()->give();
1203 }
1204 
1205 
1206 /*
1207  called on rising edge of radio IRQ pin
1208  */
1209 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
1210 int AP_Radio_cypress::irq_radio_trampoline(int irq, void *context)
1211 {
1213  return 0;
1214 }
1215 #endif
1216 
1217 /*
1218  called on HRT timeout
1219  */
1220 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
1221 int AP_Radio_cypress::irq_timeout_trampoline(int irq, void *context)
1222 {
1224  return 0;
1225 }
1226 #elif CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
1227 void AP_Radio_cypress::irq_handler_thd(void *arg)
1228 {
1229  _irq_handler_ctx = chThdGetSelfX();
1230  (void)arg;
1231  while(true) {
1232  eventmask_t evt = chEvtWaitAny(ALL_EVENTS);
1233  if (evt & EVT_IRQ) {
1235  }
1236  if (evt & EVT_TIMEOUT) {
1238  }
1239  }
1240 }
1241 
1242 void AP_Radio_cypress::trigger_timeout_event(void *arg)
1243 {
1244  (void)arg;
1245  //we are called from ISR context
1246  chSysLockFromISR();
1247  if (_irq_handler_ctx) {
1248  chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
1249  }
1250  chSysUnlockFromISR();
1251 }
1252 
1253 void AP_Radio_cypress::trigger_irq_radio_event()
1254 {
1255  //we are called from ISR context
1256  chSysLockFromISR();
1257  if (_irq_handler_ctx) {
1258  chEvtSignalI(_irq_handler_ctx, EVT_IRQ);
1259  }
1260  chSysUnlockFromISR();
1261 }
1262 #endif
1263 /*
1264  Set the current DSM channel with SOP, CRC and data code
1265  */
1266 void AP_Radio_cypress::dsm_set_channel(uint8_t channel, bool is_dsm2, uint8_t sop_col, uint8_t data_col, uint16_t crc_seed)
1267 {
1268  //printf("dsm_set_channel: %u\n", channel);
1269 
1270  uint8_t pn_row;
1271  pn_row = is_dsm2? channel % 5 : (channel-2) % 5;
1272 
1273  // set CRC seed
1274  write_register(CYRF_CRC_SEED_LSB, crc_seed & 0xff);
1275  write_register(CYRF_CRC_SEED_MSB, crc_seed >> 8);
1276 
1277  // set start of packet code
1278  if (memcmp(dsm.last_sop_code, pn_codes[pn_row][sop_col], 8) != 0) {
1279  write_multiple(CYRF_SOP_CODE, 8, pn_codes[pn_row][sop_col]);
1280  memcpy(dsm.last_sop_code, pn_codes[pn_row][sop_col], 8);
1281  }
1282 
1283  // set data code
1284  if (memcmp(dsm.last_data_code, pn_codes[pn_row][data_col], 16) != 0) {
1285  write_multiple(CYRF_DATA_CODE, 16, pn_codes[pn_row][data_col]);
1286  memcpy(dsm.last_data_code, pn_codes[pn_row][data_col], 16);
1287  }
1288 
1289  if (get_disable_crc() != dsm.last_discrc) {
1290  dsm.last_discrc = get_disable_crc();
1291  Debug(3,"Cypress: DISCRC=%u\n", dsm.last_discrc);
1292  write_register(CYRF_RX_OVERRIDE, dsm.last_discrc?CYRF_DIS_RXCRC:0);
1293  }
1294 
1295  if (get_transmit_power() != dsm.last_transmit_power+1) {
1296  dsm.last_transmit_power = get_transmit_power()-1;
1297  Debug(3,"Cypress: TXPOWER=%u\n", dsm.last_transmit_power);
1298  write_register(CYRF_TX_CFG, CYRF_DATA_CODE_LENGTH | CYRF_DATA_MODE_8DR | dsm.last_transmit_power);
1299  }
1300 
1301  // Change channel
1302  set_channel(channel);
1303 }
1304 
1305 /*
1306  Generate the DSMX channels from the manufacturer ID
1307  */
1308 void AP_Radio_cypress::dsm_generate_channels_dsmx(uint8_t mfg_id[4], uint8_t channels[23])
1309 {
1310  // Calculate the DSMX channels
1311  int idx = 0;
1312  uint32_t id = ~((mfg_id[0] << 24) | (mfg_id[1] << 16) |
1313  (mfg_id[2] << 8) | (mfg_id[3] << 0));
1314  uint32_t id_tmp = id;
1315 
1316  // While not all channels are set
1317  while(idx < 23) {
1318  int i;
1319  int count_3_27 = 0, count_28_51 = 0, count_52_76 = 0;
1320 
1321  id_tmp = id_tmp * 0x0019660D + 0x3C6EF35F; // Randomization
1322  uint8_t next_ch = ((id_tmp >> 8) % 0x49) + 3; // Use least-significant byte and must be larger than 3
1323  if (((next_ch ^ id) & 0x01 ) == 0) {
1324  continue;
1325  }
1326 
1327  // Go trough all already set channels
1328  for (i = 0; i < idx; i++) {
1329  // Channel is already used
1330  if (channels[i] == next_ch) {
1331  break;
1332  }
1333 
1334  // Count the channel groups
1335  if(channels[i] <= 27) {
1336  count_3_27++;
1337  } else if (channels[i] <= 51) {
1338  count_28_51++;
1339  } else {
1340  count_52_76++;
1341  }
1342  }
1343 
1344  // When channel is already used continue
1345  if (i != idx) {
1346  continue;
1347  }
1348 
1349  // Set the channel when channel groups aren't full
1350  if ((next_ch < 28 && count_3_27 < 8) // Channels 3-27: max 8
1351  || (next_ch >= 28 && next_ch < 52 && count_28_51 < 7) // Channels 28-52: max 7
1352  || (next_ch >= 52 && count_52_76 < 8)) { // Channels 52-76: max 8
1353  channels[idx++] = next_ch;
1354  }
1355  }
1356 
1357  Debug(2, "Generated DSMX channels\n");
1358 }
1359 
1360 /*
1361  setup for DSMX transfers
1362  */
1364 {
1365  dsm.current_channel = 0;
1366 
1367  dsm.crc_seed = ~((dsm.mfg_id[0] << 8) + dsm.mfg_id[1]);
1368  dsm.sop_col = (dsm.mfg_id[0] + dsm.mfg_id[1] + dsm.mfg_id[2] + 2) & 0x07;
1369  dsm.data_col = 7 - dsm.sop_col;
1370 
1371  dsm_generate_channels_dsmx(dsm.mfg_id, dsm.channels);
1372 }
1373 
1374 /*
1375  choose channel to receive on
1376  */
1378 {
1379  uint32_t now = AP_HAL::micros();
1380  uint32_t dt = now - dsm.last_recv_us;
1381  const uint32_t cycle_time = dsm.pkt_time1 + dsm.pkt_time2;
1382  uint8_t next_channel;
1383 
1384 
1385  if (state == STATE_BIND) {
1386  if (now - dsm.last_chan_change_us > 15000) {
1387  // always use odd channel numbers for bind
1388  dsm.current_rf_channel |= 1;
1389  dsm.current_rf_channel = (dsm.current_rf_channel+2) % DSM_MAX_CHANNEL;
1390  dsm.last_chan_change_us = now;
1391  }
1392  set_channel(dsm.current_rf_channel);
1393  return;
1394  }
1395 
1396  if (get_autobind_time() != 0 &&
1397  dsm.last_recv_us == 0 &&
1398  now - dsm.last_autobind_send > 300*1000UL &&
1399  now > get_autobind_time() * 1000*1000UL &&
1400  get_factory_test() == 0 &&
1401  state == STATE_RECV) {
1402  // try to receive an auto-bind packet
1403  dsm_set_channel(AUTOBIND_CHANNEL, true, 0, 0, 0);
1404 
1405  state = STATE_AUTOBIND;
1406 
1407  Debug(3,"recv autobind %u\n", unsigned(now - dsm.last_autobind_send));
1408  dsm.last_autobind_send = now;
1409  return;
1410  }
1411 
1412  if (is_DSM2() && dsm.sync == DSM2_SYNC_A) {
1413  if (now - dsm.last_chan_change_us > 15000) {
1414  // only even channels for DSM2 scan
1415  dsm.current_rf_channel &= ~1;
1416  dsm.current_rf_channel = (dsm.current_rf_channel+2) % DSM_MAX_CHANNEL;
1417  dsm.last_chan_change_us = now;
1418  }
1419  //hal.console->printf("%u chan=%u\n", AP_HAL::micros(), dsm.current_rf_channel);
1420  dsm_set_channel(dsm.current_rf_channel, is_DSM2(),
1421  dsm.sop_col, dsm.data_col,
1422  dsm.sync==DSM2_SYNC_B?~dsm.crc_seed:dsm.crc_seed);
1423  return;
1424  }
1425 
1426  if (dt < 1000) {
1427  // normal channel advance
1428  next_channel = dsm.last_recv_chan + 1;
1429  } else if (dt > 20*cycle_time) {
1430  // change channel slowly
1431  next_channel = dsm.last_recv_chan + (dt / (cycle_time*2));
1432  } else {
1433  // predict next channel
1434  next_channel = dsm.last_recv_chan + 1;
1435  next_channel += (dt / cycle_time) * 2;
1436  if (dt % cycle_time > (unsigned)(dsm.pkt_time1 + 1000U)) {
1437  next_channel++;
1438  }
1439  }
1440 
1441  uint8_t chan_count = is_DSM2()?2:23;
1442  dsm.current_channel = next_channel;
1443  if (dsm.current_channel >= chan_count) {
1444  dsm.current_channel %= chan_count;
1445  if (!is_DSM2()) {
1446  dsm.crc_seed = ~dsm.crc_seed;
1447  }
1448  }
1449 
1450  if (is_DSM2() && dsm.sync == DSM2_SYNC_B && dsm.current_channel == 1) {
1451  // scan to next channelb
1452  do {
1453  dsm.channels[1] &= ~1;
1454  dsm.channels[1] = (dsm.channels[1]+2) % DSM_MAX_CHANNEL;
1455  } while (dsm.channels[1] == dsm.channels[0]);
1456  }
1457 
1458  dsm.current_rf_channel = dsm.channels[dsm.current_channel];
1459 
1460  uint16_t seed = dsm.crc_seed;
1461  if (dsm.current_channel & 1) {
1462  seed = ~seed;
1463  }
1464 
1465  if (is_DSM2()) {
1466  if (now - dsm.last_recv_us > 5000000) {
1467  dsm2_start_sync();
1468  }
1469  }
1470 
1471  dsm_set_channel(dsm.current_rf_channel, is_DSM2(),
1472  dsm.sop_col, dsm.data_col, seed);
1473 }
1474 
1475 /*
1476  setup radio for bind
1477  */
1479 {
1480  if (!dev->get_semaphore()->take(0)) {
1481  // shouldn't be possible
1482  return;
1483  }
1484 
1485  Debug(1, "Cypress: start_recv_bind\n");
1486 
1487  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_RX | CYRF_FRC_END);
1488  write_register(CYRF_RX_ABORT, 0);
1489 
1490  state = STATE_BIND;
1491 
1492  radio_set_config(cyrf_bind_config, ARRAY_SIZE(cyrf_bind_config));
1493 
1494  write_register(CYRF_CRC_SEED_LSB, 0);
1495  write_register(CYRF_CRC_SEED_MSB, 0);
1496 
1497  write_multiple(CYRF_SOP_CODE, 8, pn_codes[0][0]);
1498 
1499  uint8_t data_code[16];
1500  memcpy(data_code, pn_codes[0][8], 8);
1501  memcpy(&data_code[8], pn_bind, 8);
1502  write_multiple(CYRF_DATA_CODE, 16, data_code);
1503 
1504  dsm.current_rf_channel = 1;
1505 
1506  start_receive();
1507 
1508  dev->get_semaphore()->give();
1509 }
1510 
1511 /*
1512  save bind info
1513  */
1515 {
1516  // access to storage for bind information
1518  struct bind_info info;
1519 
1520  info.magic = bind_magic;
1521  memcpy(info.mfg_id, dsm.mfg_id, sizeof(info.mfg_id));
1522  info.protocol = dsm.protocol;
1523 
1524  if (bind_storage.write_block(0, &info, sizeof(info))) {
1525  dsm.need_bind_save = false;
1526  }
1527 }
1528 
1529 /*
1530  load bind info
1531  */
1533 {
1534  // access to storage for bind information
1536  struct bind_info info;
1537 
1538  uint8_t factory_test = get_factory_test();
1539 
1540  if (factory_test != 0) {
1541  Debug(1, "In factory test %u\n", factory_test);
1542  memset(dsm.mfg_id, 0, sizeof(dsm.mfg_id));
1543  dsm.mfg_id[0] = factory_test;
1544  dsm.protocol = DSM_DSM2_2;
1545  dsm2_start_sync();
1546  } else if (bind_storage.read_block(&info, 0, sizeof(info)) && info.magic == bind_magic) {
1547  Debug(1, "Loaded mfg_id %02x:%02x:%02x:%02x\n",
1548  info.mfg_id[0], info.mfg_id[1], info.mfg_id[2], info.mfg_id[3]);
1549  memcpy(dsm.mfg_id, info.mfg_id, sizeof(info.mfg_id));
1550  dsm.protocol = info.protocol;
1551  }
1552 }
1553 
1554 bool AP_Radio_cypress::is_DSM2(void)
1555 {
1558  }
1559  return dsm.protocol == DSM_DSM2_1 || dsm.protocol == DSM_DSM2_2;
1560 }
1561 
1562 /*
1563  transmit a 16 byte packet
1564  this is a blind send, not waiting for ack or completion
1565 */
1566 void AP_Radio_cypress::transmit16(const uint8_t data[16])
1567 {
1568  write_register(CYRF_TX_LENGTH, 16);
1569  write_register(CYRF_TX_CTRL, CYRF_TX_CLR);
1570 
1571  write_multiple(CYRF_TX_BUFFER, 16, data);
1572  write_register(CYRF_TX_CTRL, CYRF_TX_GO | CYRF_TXC_IRQEN);
1573  dsm.send_count++;
1574 }
1575 
1576 
1577 /*
1578  send a telemetry structure packet
1579  */
1581 {
1582  struct telem_packet_cypress pkt;
1583 
1584  t_status.flags = 0;
1594 
1595  // send fw update packet for 7/8 of packets if any data pending
1596  if (fwupload.length != 0 &&
1597  fwupload.length > fwupload.acked &&
1598  ((fwupload.counter++ & 0x07) != 0) &&
1599  sem->take_nonblocking()) {
1600  pkt.type = fwupload.fw_type;
1601  pkt.payload.fw.seq = fwupload.sequence;
1602  uint32_t len = fwupload.length>fwupload.acked?fwupload.length - fwupload.acked:0;
1603  pkt.payload.fw.len = len<=8?len:8;
1604  pkt.payload.fw.offset = fwupload.offset+fwupload.acked;
1605  memcpy(&pkt.payload.fw.data[0], &fwupload.pending_data[fwupload.acked], pkt.payload.fw.len);
1606  fwupload.len = pkt.payload.fw.len;
1607  Debug(4, "sent fw seq=%u offset=%u len=%u type=%u\n",
1608  pkt.payload.fw.seq,
1609  pkt.payload.fw.offset,
1610  pkt.payload.fw.len,
1611  pkt.type);
1612  sem->give();
1613  pkt.crc = crc_crc8((const uint8_t *)&pkt.type, 15);
1614  } else {
1615  pkt.type = TELEM_STATUS;
1616  pkt.payload.status = t_status;
1617  pkt.crc = crc_crc8((const uint8_t *)&pkt.type, 15);
1618  dsm.telem_send_count++;
1619  }
1620 
1621  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_TX | CYRF_FRC_END);
1622  write_register(CYRF_RX_ABORT, 0);
1623  transmit16((uint8_t*)&pkt);
1624 
1625  state = STATE_SEND_TELEM_WAIT;
1626  setup_timeout(2);
1627 }
1628 
1629 /*
1630  send a FCC test packet
1631  */
1633 {
1634  uint8_t pkt[16] = { 0, 1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15 };
1635 
1636  state = STATE_SEND_FCC;
1637 
1638  uint8_t channel=0;
1639 
1640  switch (get_fcc_test()) {
1641  case 0:
1642  // switch back to normal operation
1643  dsm.forced_channel = -1;
1644  send_telem_packet();
1645  return;
1646  case 1:
1647  case 4:
1648  channel = DSM_SCAN_MIN_CH;
1649  break;
1650  case 2:
1651  case 5:
1652  channel = DSM_SCAN_MID_CH;
1653  break;
1654  case 3:
1655  case 6:
1656  default:
1657  channel = DSM_SCAN_MAX_CH;
1658  break;
1659  }
1660 
1661  Debug(5,"FCC send %u\n", channel);
1662 
1663  if (channel != dsm.forced_channel) {
1664  Debug(1,"FCC channel %u\n", channel);
1665  dsm.forced_channel = channel;
1666 
1667  radio_set_config(cyrf_config, ARRAY_SIZE(cyrf_config));
1668  radio_set_config(cyrf_transfer_config, ARRAY_SIZE(cyrf_transfer_config));
1669 
1670  set_channel(channel);
1671  }
1672 
1673 #if FCC_SUPPORT_CW_MODE
1674  if (get_fcc_test() > 3) {
1675  // continuous preamble transmit is closest approximation to CW
1676  // that is possible with this chip
1677  write_register(CYRF_PREAMBLE,0x01);
1678  write_register(CYRF_PREAMBLE,0x00);
1679  write_register(CYRF_PREAMBLE,0x00);
1680 
1681  write_register(CYRF_TX_OVERRIDE, CYRF_FRC_PRE);
1682  write_register(CYRF_TX_CTRL, CYRF_TX_GO);
1683 
1684  setup_timeout(500);
1685  } else {
1686  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_TX | CYRF_FRC_END);
1687  write_register(CYRF_RX_ABORT, 0);
1688  transmit16(pkt);
1689  setup_timeout(10);
1690  }
1691 #else
1692  write_register(CYRF_XACT_CFG, CYRF_MODE_SYNTH_TX | CYRF_FRC_END);
1693  write_register(CYRF_RX_ABORT, 0);
1694  transmit16(pkt);
1695  setup_timeout(10);
1696 #endif
1697 }
1698 
1699 // handle a data96 mavlink packet for fw upload
1700 void AP_Radio_cypress::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
1701 {
1702  uint32_t ofs=0;
1703  memcpy(&ofs, &m.data[0], 4);
1704  Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
1705  if (sem->take_nonblocking()) {
1706  fwupload.chan = chan;
1707  fwupload.need_ack = false;
1708  fwupload.offset = ofs;
1709  fwupload.length = MIN(m.len-4, 92);
1710  fwupload.acked = 0;
1711  fwupload.sequence++;
1712  if (m.type == 43) {
1713  // sending a tune to play - for development testing
1714  fwupload.fw_type = TELEM_PLAY;
1715  fwupload.length = MIN(m.len, 90);
1716  fwupload.offset = 0;
1717  memcpy(&fwupload.pending_data[0], &m.data[0], fwupload.length);
1718  } else {
1719  // sending a chunk of firmware OTA upload
1720  fwupload.fw_type = TELEM_FW;
1721  memcpy(&fwupload.pending_data[0], &m.data[4], fwupload.length);
1722  }
1723  sem->give();
1724  }
1725 }
1726 
1727 #endif // HAL_RCINPUT_WITH_AP_RADIO
1728 
void dsm_set_channel(uint8_t channel, bool is_dsm2, uint8_t sop_col, uint8_t data_col, uint16_t crc_seed)
mavlink_channel_t chan
int printf(const char *fmt,...)
Definition: stdio.c:113
bool get_soft_armed() const
Definition: Util.h:15
bool init(void) override
static thread_t * _irq_handler_ctx
void start_recv_bind(void) override
uint8_t get_tx_rssi_chan(void) const
void send_telem_packet(void)
static void trigger_timeout_event(void *arg)
#define TELEM_FLAG_POS_OK
uint8_t get_debug_level(void) const
void start_receive(void)
uint32_t recv_errors
Definition: AP_Radio.h:64
#define FALLTHROUGH
Definition: AP_Common.h:50
uint16_t pwm_channels[CC2500_MAX_CHANNELS]
uint8_t get_rssi_chan(void) const
void save_bind_info(void)
void irq_timeout(void)
void send_FCC_test_packet(void)
bool send(const uint8_t *pkt, uint16_t len) override
AP_HAL::OwnPtr< AP_HAL::SPIDevice > dev
void write_multiple(uint8_t reg, uint8_t n, const uint8_t *data)
AP_Radio::stats last_stats
uint8_t get_factory_test(void) const
uint8_t crc_crc8(const uint8_t *p, uint8_t len)
Definition: crc.cpp:50
AP_HAL::Util * util
Definition: HAL.h:115
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
#define HAL_SEMAPHORE_BLOCK_FOREVER
Definition: Semaphores.h:5
void save_bind_info(void)
virtual bool take(uint32_t timeout_ms) WARN_IF_UNUSED=0
uint8_t num_channels(void) override
AP_Radio_cypress(AP_Radio &radio)
virtual Semaphore * new_semaphore(void)
Definition: Util.h:108
void radio_init(void)
void dsm_setup_transfer_dsmx(void)
AP_RSSI * rssi()
Definition: AP_RSSI.cpp:220
static AP_Radio_cypress * radio_instance
uint8_t read_register(uint8_t reg)
uint8_t note_adjust
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
virtual void write(uint8_t pin, uint8_t value)=0
void set_channel(uint8_t channel)
#define MIN(a, b)
Definition: usb_conf.h:215
static auto MAX(const A &one, const B &two) -> decltype(one > two ? one :two)
Definition: AP_Math.h:202
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override
struct telem_status t_status
uint32_t timeouts
Definition: AP_Radio.h:67
bool get_telem_enable(void) const
static const uint8_t pn_bind[]
void start_recv_bind(void) override
virtual void delay(uint16_t ms)=0
uint32_t recv_packets
Definition: AP_Radio.h:65
bool parse_dsm_channels(const uint8_t *data)
virtual bool attach_interrupt(uint8_t interrupt_num, AP_HAL::Proc p, uint8_t mode)=0
static const uint8_t pn_codes[5][9][8]
uint8_t flight_mode
void transmit16(const uint8_t data[16])
void radio_init(void)
virtual bool take_nonblocking() WARN_IF_UNUSED=0
bool reset(void) override
uint8_t get_autobind_rssi(void) const
virtual OwnPtr< SPIDevice > get_device(const char *name)
Definition: SPIDevice.h:68
void irq_handler_send(uint8_t tx_status)
static const config cyrf_transfer_config[]
void process_bind(const uint8_t *pkt, uint8_t len)
void check_double_bind(void)
void check_fw_ack(void)
virtual Semaphore * get_semaphore() override=0
uint8_t num_channels(void) override
static const config cyrf_bind_config[]
#define Debug(fmt, args ...)
static uint8_t max_channels
void radio_set_config(const struct config *config, uint8_t size)
int8_t get_fcc_test(void) const
uint32_t millis()
Definition: system.cpp:157
#define TELEM_FLAG_VIDEO
uint16_t read(uint8_t chan) override
static const config cyrf_config[]
bool get_disable_crc(void) const
uint64_t micros64()
Definition: system.cpp:162
#define HAL_GPIO_INTERRUPT_RISING
Definition: GPIO.h:13
void set_tx_max_power_default(uint8_t v)
uint8_t get_stick_mode(void) const
static int state
Definition: Util.cpp:20
bool dsm_decode(uint64_t frame_time, const uint8_t dsm_frame[16], uint16_t *values, uint16_t *num_values, uint16_t max_values)
Definition: dsm.cpp:195
void irq_handler(void)
virtual bool set_chip_select(bool set)
Definition: Device.h:214
virtual bool give()=0
float v
Definition: Printf.cpp:15
void print_debug_info(void)
AP_HAL::SPIDeviceManager * spi
Definition: HAL.h:107
#define TELEM_FLAG_ARM_OK
void irq_timeout(void)
void irq_handler(void)
#define TELEM_FLAG_BATT_OK
#define ARRAY_SIZE(_arr)
Definition: AP_Common.h:80
void dsm_choose_channel(void)
static virtual_timer_t timeout_vt
static void trigger_irq_radio_event(void)
#define NULL
Definition: hal_types.h:59
void update(void) override
AP_Radio::stats stats
static AP_Radio_cc2500 * radio_instance
uint8_t get_tx_buzzer_adjust(void) const
void process_packet(const uint8_t *pkt, uint8_t len)
void setup_timeout(uint32_t timeout_ms)
virtual bool transfer(const uint8_t *send, uint32_t send_len, uint8_t *recv, uint32_t recv_len) override=0
uint32_t bad_packets
Definition: AP_Radio.h:63
void load_bind_info(void)
static struct notify_flags_and_values_type flags
Definition: AP_Notify.h:117
uint8_t get_transmit_power(void) const
bool is_DSM2(void)
void write_register(uint8_t reg, uint8_t value)
void force_initial_state(void)
uint8_t get_autobind_time(void) const
AP_HAL::GPIO * gpio
Definition: HAL.h:111
void dsm_generate_channels_dsmx(uint8_t mfg_id[4], uint8_t channels[23])
float value
uint8_t get_tx_pps_chan(void) const
uint8_t get_tx_max_power(void) const
bool read_registers(uint8_t first_reg, uint8_t *recv, uint32_t recv_len)
Definition: Device.h:113
uint8_t read_status_debounced(uint8_t adr)
AP_HAL::Semaphore * sem
bool read(uint8_t *recv, uint32_t recv_len)
Definition: Device.h:156
void check_fw_ack(void)
#define TELEM_FLAG_GPS_OK
struct AP_Radio_cc2500::@168 fwupload
static int irq_timeout_trampoline(int irq, void *context)
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void dsm2_start_sync(void)
static int irq_radio_trampoline(int irq, void *context)
uint8_t get_pps_chan(void) const
bool reset(void) override
void dump_registers(uint8_t n)
bool load_bind_info(void)
uint32_t last_recv_us(void) override
THD_WORKING_AREA(_timer_thread_wa, 2048)
bool write_register(uint8_t reg, uint8_t val, bool checked=false)
Definition: Device.h:125
#define TELEM_FLAG_ARMED
const AP_Radio::stats & get_stats(void) override
uint32_t micros()
Definition: system.cpp:152
static void irq_handler_thd(void *arg)
void map_stick_mode(uint16_t *channels)
void irq_handler_recv(uint8_t rx_status)
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
AP_Radio::ap_radio_protocol get_protocol(void) const
static const uint16_t bind_magic