AP_Radio_cypress.cpp 50 KB

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