AP_Radio_cc2500.cpp 47 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949950951952953954955956957958959960961962963964965966967968969970971972973974975976977978979980981982983984985986987988989990991992993994995996997998999100010011002100310041005100610071008100910101011101210131014101510161017101810191020102110221023102410251026102710281029103010311032103310341035103610371038103910401041104210431044104510461047104810491050105110521053105410551056105710581059106010611062106310641065106610671068106910701071107210731074107510761077107810791080108110821083108410851086108710881089109010911092109310941095109610971098109911001101110211031104110511061107110811091110111111121113111411151116111711181119112011211122112311241125112611271128112911301131113211331134113511361137113811391140114111421143114411451146114711481149115011511152115311541155115611571158115911601161116211631164116511661167116811691170117111721173117411751176117711781179118011811182118311841185118611871188118911901191119211931194119511961197119811991200120112021203120412051206120712081209121012111212121312141215121612171218121912201221122212231224122512261227122812291230123112321233123412351236123712381239124012411242124312441245124612471248124912501251125212531254125512561257125812591260126112621263126412651266126712681269127012711272127312741275127612771278127912801281128212831284128512861287128812891290129112921293129412951296129712981299130013011302130313041305130613071308130913101311131213131314131513161317131813191320132113221323132413251326132713281329133013311332133313341335133613371338133913401341134213431344134513461347134813491350135113521353135413551356135713581359136013611362136313641365136613671368136913701371137213731374137513761377137813791380138113821383138413851386138713881389139013911392139313941395139613971398139914001401140214031404140514061407140814091410141114121413141414151416141714181419142014211422142314241425142614271428142914301431143214331434143514361437143814391440144114421443144414451446144714481449145014511452145314541455145614571458145914601461146214631464146514661467146814691470147114721473147414751476147714781479148014811482148314841485148614871488148914901491149214931494149514961497149814991500150115021503150415051506150715081509151015111512151315141515151615171518151915201521152215231524152515261527152815291530153115321533153415351536153715381539154015411542154315441545154615471548154915501551155215531554155515561557155815591560156115621563156415651566156715681569
  1. /*
  2. driver for TI CC2500 radio
  3. Many thanks to the cleanflight and betaflight projects
  4. */
  5. #include <AP_HAL/AP_HAL.h>
  6. // #pragma GCC optimize("O0")
  7. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  8. #if HAL_RCINPUT_WITH_AP_RADIO
  9. #include <AP_Math/AP_Math.h>
  10. #include "AP_Radio_cc2500.h"
  11. #include <utility>
  12. #include <stdio.h>
  13. #include <StorageManager/StorageManager.h>
  14. #include <AP_Notify/AP_Notify.h>
  15. #include <GCS_MAVLink/GCS_MAVLink.h>
  16. #include <AP_Math/crc.h>
  17. #include <AP_Param/AP_Param.h>
  18. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  19. #define TIMEOUT_PRIORITY 185
  20. #define EVT_TIMEOUT EVENT_MASK(0)
  21. #define EVT_IRQ EVENT_MASK(1)
  22. #define EVT_BIND EVENT_MASK(2)
  23. #endif
  24. extern const AP_HAL::HAL& hal;
  25. #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0)
  26. // object instance for trampoline
  27. AP_Radio_cc2500 *AP_Radio_cc2500::radio_singleton;
  28. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  29. thread_t *AP_Radio_cc2500::_irq_handler_ctx;
  30. virtual_timer_t AP_Radio_cc2500::timeout_vt;
  31. uint32_t AP_Radio_cc2500::irq_time_us;
  32. #endif
  33. #define USE_D16_FORMAT 0
  34. /*
  35. we are setup for a channel spacing of 0.3MHz, with channel 0 being 2403.6MHz
  36. For D16 protocol we select 47 channels from a max of 235 channels
  37. For SRT protocol we select 23 channels from a max of 235 channels,
  38. and avoid channels near to the WiFi channel of the Sonix video board
  39. */
  40. #if USE_D16_FORMAT
  41. #define NUM_CHANNELS 47
  42. #define MAX_CHANNEL_NUMBER 0xEB
  43. #define INTER_PACKET_MS 9
  44. #define INTER_PACKET_INITIAL_MS (INTER_PACKET_MS+2)
  45. #define PACKET_SENT_DELAY_US 3300
  46. #else
  47. #define NUM_CHANNELS 23
  48. #define MAX_CHANNEL_NUMBER 0xEB
  49. #define INTER_PACKET_MS 9
  50. #define INTER_PACKET_INITIAL_MS (INTER_PACKET_MS+5)
  51. #define PACKET_SENT_DELAY_US 2800
  52. #endif
  53. #define SEARCH_START_PKTS 40
  54. #define AUTOBIND_CHANNEL 100
  55. /*
  56. constructor
  57. */
  58. AP_Radio_cc2500::AP_Radio_cc2500(AP_Radio &_radio) :
  59. AP_Radio_backend(_radio),
  60. cc2500(hal.spi->get_device("cc2500"))
  61. {
  62. // link to instance for irq_trampoline
  63. radio_singleton = this;
  64. }
  65. /*
  66. initialise radio
  67. */
  68. bool AP_Radio_cc2500::init(void)
  69. {
  70. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  71. if (_irq_handler_ctx != nullptr) {
  72. AP_HAL::panic("AP_Radio_cc2500: double instantiation of irq_handler\n");
  73. }
  74. chVTObjectInit(&timeout_vt);
  75. _irq_handler_ctx = chThdCreateFromHeap(NULL,
  76. THD_WORKING_AREA_SIZE(2048),
  77. "radio_cc2500",
  78. TIMEOUT_PRIORITY,
  79. irq_handler_thd,
  80. NULL);
  81. #endif
  82. return reset();
  83. }
  84. /*
  85. reset radio
  86. */
  87. bool AP_Radio_cc2500::reset(void)
  88. {
  89. if (!cc2500.lock_bus()) {
  90. return false;
  91. }
  92. radio_init();
  93. cc2500.unlock_bus();
  94. return true;
  95. }
  96. /*
  97. return statistics structure from radio
  98. */
  99. const AP_Radio::stats &AP_Radio_cc2500::get_stats(void)
  100. {
  101. return stats;
  102. }
  103. /*
  104. read one pwm channel from radio
  105. */
  106. uint16_t AP_Radio_cc2500::read(uint8_t chan)
  107. {
  108. if (chan >= CC2500_MAX_PWM_CHANNELS) {
  109. return 0;
  110. }
  111. return pwm_channels[chan];
  112. }
  113. /*
  114. update status - called from main thread
  115. */
  116. void AP_Radio_cc2500::update(void)
  117. {
  118. check_fw_ack();
  119. }
  120. /*
  121. return number of active channels
  122. */
  123. uint8_t AP_Radio_cc2500::num_channels(void)
  124. {
  125. uint32_t now = AP_HAL::millis();
  126. uint8_t chan = get_rssi_chan();
  127. if (chan > 0) {
  128. pwm_channels[chan-1] = t_status.rssi;
  129. chan_count = MAX(chan_count, chan);
  130. }
  131. chan = get_pps_chan();
  132. if (chan > 0) {
  133. pwm_channels[chan-1] = t_status.pps;
  134. chan_count = MAX(chan_count, chan);
  135. }
  136. chan = get_tx_rssi_chan();
  137. if (chan > 0) {
  138. pwm_channels[chan-1] = tx_rssi;
  139. chan_count = MAX(chan_count, chan);
  140. }
  141. chan = get_tx_pps_chan();
  142. if (chan > 0) {
  143. pwm_channels[chan-1] = tx_pps;
  144. chan_count = MAX(chan_count, chan);
  145. }
  146. pwm_channels[11] = (stats.recv_packets % 1000);
  147. chan_count = MAX(chan_count, 12);
  148. if (now - last_pps_ms > 1000) {
  149. last_pps_ms = now;
  150. t_status.pps = stats.recv_packets - last_stats.recv_packets;
  151. last_stats = stats;
  152. if (lost != 0 || timeouts != 0) {
  153. Debug(timeouts!=0?2:3,"lost=%u timeouts=%u TS=%u\n",
  154. unsigned(lost), unsigned(timeouts), sizeof(struct telem_packet_cc2500));
  155. }
  156. lost=0;
  157. timeouts=0;
  158. }
  159. return chan_count;
  160. }
  161. /*
  162. return time of last receive in microseconds
  163. */
  164. uint32_t AP_Radio_cc2500::last_recv_us(void)
  165. {
  166. return packet_timer;
  167. }
  168. /*
  169. send len bytes as a single packet
  170. */
  171. bool AP_Radio_cc2500::send(const uint8_t *pkt, uint16_t len)
  172. {
  173. // disabled for now
  174. return false;
  175. }
  176. const AP_Radio_cc2500::config AP_Radio_cc2500::radio_config_GFSK[] = {
  177. /*
  178. radio config for GFSK with 57kHz deviation
  179. */
  180. {CC2500_00_IOCFG2, 0x01}, // GD2 high on RXFIFO filled or end of packet
  181. {CC2500_17_MCSM1, 0x03}, // RX->IDLE, CCA always, TX -> IDLE
  182. {CC2500_18_MCSM0, 0x08}, // XOSC expire 64, cal never
  183. {CC2500_06_PKTLEN, 0x0D}, // packet length 13
  184. {CC2500_07_PKTCTRL1, 0x0C}, // enable RSSI+LQI, no addr check, CRC autoflush, PQT=0
  185. {CC2500_08_PKTCTRL0, 0x44}, // fixed length mode, CRC, FIFO enable, whitening
  186. {CC2500_3E_PATABLE, 0xFF}, // initially max power
  187. {CC2500_0B_FSCTRL1, 0x0A}, // IF=253.90625kHz assuming 26MHz crystal
  188. {CC2500_0C_FSCTRL0, 0x00}, // freqoffs = 0
  189. {CC2500_0D_FREQ2, 0x5C}, // freq control high
  190. {CC2500_0E_FREQ1, 0x76}, // freq control middle
  191. {CC2500_0F_FREQ0, 0x27}, // freq control low
  192. {CC2500_10_MDMCFG4, 0x8C}, // filter bandwidth 203kHz
  193. {CC2500_11_MDMCFG3, 0x2F}, // data rate 120kbaud
  194. {CC2500_12_MDMCFG2, 0x13}, // 30/32 sync word bits, no manchester, GFSK, DC filter enabled
  195. {CC2500_13_MDMCFG1, 0xA3}, // chan spacing exponent 3, preamble 4 bytes, FEC enabled
  196. {CC2500_14_MDMCFG0, 0x7A}, // chan spacing 299.926757kHz for 26MHz crystal
  197. {CC2500_15_DEVIATN, 0x51}, // modem deviation 57kHz for 26MHz crystal
  198. {CC2500_19_FOCCFG, 0x16}, // frequency offset compensation
  199. {CC2500_1A_BSCFG, 0x6C}, // bit sync config
  200. {CC2500_1B_AGCCTRL2, 0x43}, // target amplitude 33dB
  201. {CC2500_1C_AGCCTRL1, 0x40}, // AGC control 2
  202. {CC2500_1D_AGCCTRL0, 0x91}, // AGC control 0
  203. {CC2500_21_FREND1, 0x56}, // frontend config1
  204. {CC2500_22_FREND0, 0x10}, // frontend config0
  205. {CC2500_23_FSCAL3, 0xA9}, // frequency synth cal3
  206. {CC2500_24_FSCAL2, 0x0A}, // frequency synth cal2
  207. {CC2500_25_FSCAL1, 0x00}, // frequency synth cal1
  208. {CC2500_26_FSCAL0, 0x11}, // frequency synth cal0
  209. {CC2500_29_FSTEST, 0x59}, // test bits
  210. {CC2500_2C_TEST2, 0x88}, // test settings
  211. {CC2500_2D_TEST1, 0x31}, // test settings
  212. {CC2500_2E_TEST0, 0x0B}, // test settings
  213. {CC2500_03_FIFOTHR, 0x07}, // TX fifo threashold 33, RX fifo threshold 32
  214. {CC2500_09_ADDR, 0x00}, // device address 0 (broadcast)
  215. };
  216. const AP_Radio_cc2500::config AP_Radio_cc2500::radio_config[] = {
  217. /* config for both TX and RX (from SmartRF Studio)
  218. setup for MSK at 120kbaud, FEC enabled, whitening enabled, base freq 2403.999756MHz
  219. channel spacing 299.926758, crystal 26MHz, RX filter bw 203.125kHz
  220. */
  221. {CC2500_06_PKTLEN, 0x0D},
  222. {CC2500_07_PKTCTRL1, 0x0C},
  223. {CC2500_08_PKTCTRL0, 0x44},
  224. {CC2500_0B_FSCTRL1, 0x0A},
  225. {CC2500_0D_FREQ2, 0x5C},
  226. {CC2500_0E_FREQ1, 0x76},
  227. {CC2500_0F_FREQ0, 0x27},
  228. {CC2500_11_MDMCFG3, 0x2F},
  229. {CC2500_12_MDMCFG2, 0x73},
  230. {CC2500_13_MDMCFG1, 0xA3},
  231. {CC2500_14_MDMCFG0, 0x7A},
  232. {CC2500_15_DEVIATN, 0x70},
  233. {CC2500_17_MCSM1, 0x03},
  234. {CC2500_18_MCSM0, 0x08},
  235. {CC2500_19_FOCCFG, 0x16},
  236. {CC2500_1B_AGCCTRL2, 0x43},
  237. {CC2500_23_FSCAL3, 0xEA},
  238. {CC2500_25_FSCAL1, 0x00},
  239. {CC2500_26_FSCAL0, 0x11},
  240. {CC2500_2B_AGCTEST, 0x3E},
  241. {CC2500_03_FIFOTHR, 0x07}, // TX fifo threashold 33, RX fifo threshold 32
  242. // config specific to RX
  243. {CC2500_00_IOCFG2, 0x01}, // GD2 high on RXFIFO filled or end of packet
  244. {CC2500_17_MCSM1, 0x03}, // RX->IDLE, CCA always, TX -> IDLE
  245. {CC2500_18_MCSM0, 0x08}, // XOSC expire 64, cal never
  246. {CC2500_3E_PATABLE, 0xFF}, // initially max power
  247. };
  248. const uint16_t CRCTable[] = {
  249. 0x0000,0x1189,0x2312,0x329b,0x4624,0x57ad,0x6536,0x74bf,
  250. 0x8c48,0x9dc1,0xaf5a,0xbed3,0xca6c,0xdbe5,0xe97e,0xf8f7,
  251. 0x1081,0x0108,0x3393,0x221a,0x56a5,0x472c,0x75b7,0x643e,
  252. 0x9cc9,0x8d40,0xbfdb,0xae52,0xdaed,0xcb64,0xf9ff,0xe876,
  253. 0x2102,0x308b,0x0210,0x1399,0x6726,0x76af,0x4434,0x55bd,
  254. 0xad4a,0xbcc3,0x8e58,0x9fd1,0xeb6e,0xfae7,0xc87c,0xd9f5,
  255. 0x3183,0x200a,0x1291,0x0318,0x77a7,0x662e,0x54b5,0x453c,
  256. 0xbdcb,0xac42,0x9ed9,0x8f50,0xfbef,0xea66,0xd8fd,0xc974,
  257. 0x4204,0x538d,0x6116,0x709f,0x0420,0x15a9,0x2732,0x36bb,
  258. 0xce4c,0xdfc5,0xed5e,0xfcd7,0x8868,0x99e1,0xab7a,0xbaf3,
  259. 0x5285,0x430c,0x7197,0x601e,0x14a1,0x0528,0x37b3,0x263a,
  260. 0xdecd,0xcf44,0xfddf,0xec56,0x98e9,0x8960,0xbbfb,0xaa72,
  261. 0x6306,0x728f,0x4014,0x519d,0x2522,0x34ab,0x0630,0x17b9,
  262. 0xef4e,0xfec7,0xcc5c,0xddd5,0xa96a,0xb8e3,0x8a78,0x9bf1,
  263. 0x7387,0x620e,0x5095,0x411c,0x35a3,0x242a,0x16b1,0x0738,
  264. 0xffcf,0xee46,0xdcdd,0xcd54,0xb9eb,0xa862,0x9af9,0x8b70,
  265. 0x8408,0x9581,0xa71a,0xb693,0xc22c,0xd3a5,0xe13e,0xf0b7,
  266. 0x0840,0x19c9,0x2b52,0x3adb,0x4e64,0x5fed,0x6d76,0x7cff,
  267. 0x9489,0x8500,0xb79b,0xa612,0xd2ad,0xc324,0xf1bf,0xe036,
  268. 0x18c1,0x0948,0x3bd3,0x2a5a,0x5ee5,0x4f6c,0x7df7,0x6c7e,
  269. 0xa50a,0xb483,0x8618,0x9791,0xe32e,0xf2a7,0xc03c,0xd1b5,
  270. 0x2942,0x38cb,0x0a50,0x1bd9,0x6f66,0x7eef,0x4c74,0x5dfd,
  271. 0xb58b,0xa402,0x9699,0x8710,0xf3af,0xe226,0xd0bd,0xc134,
  272. 0x39c3,0x284a,0x1ad1,0x0b58,0x7fe7,0x6e6e,0x5cf5,0x4d7c,
  273. 0xc60c,0xd785,0xe51e,0xf497,0x8028,0x91a1,0xa33a,0xb2b3,
  274. 0x4a44,0x5bcd,0x6956,0x78df,0x0c60,0x1de9,0x2f72,0x3efb,
  275. 0xd68d,0xc704,0xf59f,0xe416,0x90a9,0x8120,0xb3bb,0xa232,
  276. 0x5ac5,0x4b4c,0x79d7,0x685e,0x1ce1,0x0d68,0x3ff3,0x2e7a,
  277. 0xe70e,0xf687,0xc41c,0xd595,0xa12a,0xb0a3,0x8238,0x93b1,
  278. 0x6b46,0x7acf,0x4854,0x59dd,0x2d62,0x3ceb,0x0e70,0x1ff9,
  279. 0xf78f,0xe606,0xd49d,0xc514,0xb1ab,0xa022,0x92b9,0x8330,
  280. 0x7bc7,0x6a4e,0x58d5,0x495c,0x3de3,0x2c6a,0x1ef1,0x0f78
  281. };
  282. /*
  283. static probe function for radio auto-detect
  284. */
  285. bool AP_Radio_cc2500::probe(void)
  286. {
  287. auto dev = hal.spi->get_device("cc2500");
  288. if (!dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER)) {
  289. return false;
  290. }
  291. uint8_t r1=0, r2=0;
  292. if (!dev->read_registers(CC2500_30_PARTNUM | CC2500_READ_BURST | CC2500_READ_SINGLE, &r1, 1) || r1 != 0x80 ||
  293. !dev->read_registers(CC2500_31_VERSION | CC2500_READ_BURST | CC2500_READ_SINGLE, &r2, 1) || r2 != 0x03) {
  294. dev->get_semaphore()->give();
  295. return false;
  296. }
  297. dev->get_semaphore()->give();
  298. return true;
  299. }
  300. /*
  301. initialise the radio
  302. */
  303. void AP_Radio_cc2500::radio_init(void)
  304. {
  305. if (cc2500.ReadReg(CC2500_30_PARTNUM | CC2500_READ_BURST) != 0x80 ||
  306. cc2500.ReadReg(CC2500_31_VERSION | CC2500_READ_BURST) != 0x03) {
  307. Debug(1, "cc2500: radio not found\n");
  308. return;
  309. }
  310. Debug(1, "cc2500: radio_init starting\n");
  311. cc2500.Reset();
  312. hal.scheduler->delay_microseconds(100);
  313. if (get_protocol() == AP_Radio::PROTOCOL_CC2500_GFSK) {
  314. Debug(1,"Using GFSK configuration\n");
  315. for (uint8_t i=0; i<ARRAY_SIZE(radio_config_GFSK); i++) {
  316. cc2500.WriteRegCheck(radio_config_GFSK[i].reg, radio_config_GFSK[i].value);
  317. }
  318. } else {
  319. for (uint8_t i=0; i<ARRAY_SIZE(radio_config); i++) {
  320. cc2500.WriteRegCheck(radio_config[i].reg, radio_config[i].value);
  321. }
  322. }
  323. cc2500.Strobe(CC2500_SIDLE); // Go to idle...
  324. hal.scheduler->delay_microseconds(10*1000);
  325. // setup handler for rising edge of IRQ pin
  326. hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, AP_HAL::GPIO::INTERRUPT_RISING);
  327. // fill in rxid for use in double bind prevention
  328. char sysid[40] {};
  329. hal.util->get_system_id(sysid);
  330. uint16_t sysid_crc = calc_crc((const uint8_t *)sysid, strnlen(sysid, sizeof(sysid)));
  331. if (sysid_crc == 0) {
  332. sysid_crc = 1;
  333. }
  334. t_status.rxid[0] = sysid_crc & 0xFF;
  335. t_status.rxid[1] = sysid_crc >> 8;
  336. initTuneRx();
  337. if (load_bind_info()) {
  338. Debug(3,"Loaded bind info\n");
  339. } else {
  340. listLength = NUM_CHANNELS;
  341. bindOffset = 0;
  342. setup_hopping_table_SRT();
  343. }
  344. uint8_t factory_test = get_factory_test();
  345. if (factory_test != 0) {
  346. bindTxId[0] = uint8_t(factory_test * 17);
  347. bindTxId[1] = uint8_t(~bindTxId[0]);
  348. setup_hopping_table_SRT();
  349. }
  350. // we go straight into search, and rely on autobind
  351. initialiseData(0);
  352. protocolState = STATE_SEARCH;
  353. packet_timer = AP_HAL::micros();
  354. chanskip = 1;
  355. nextChannel(1);
  356. // set default autobind power to suit the cc2500
  357. AP_Param::set_default_by_name("BRD_RADIO_ABLVL", 90);
  358. chVTSet(&timeout_vt, chTimeMS2I(INTER_PACKET_INITIAL_MS), trigger_timeout_event, nullptr);
  359. }
  360. void AP_Radio_cc2500::trigger_irq_radio_event()
  361. {
  362. //we are called from ISR context
  363. chSysLockFromISR();
  364. irq_time_us = AP_HAL::micros();
  365. chEvtSignalI(_irq_handler_ctx, EVT_IRQ);
  366. chSysUnlockFromISR();
  367. }
  368. void AP_Radio_cc2500::trigger_timeout_event(void *arg)
  369. {
  370. (void)arg;
  371. //we are called from ISR context
  372. chSysLockFromISR();
  373. chVTSetI(&timeout_vt, chTimeMS2I(INTER_PACKET_INITIAL_MS), trigger_timeout_event, nullptr);
  374. chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
  375. chSysUnlockFromISR();
  376. }
  377. void AP_Radio_cc2500::start_recv_bind(void)
  378. {
  379. chan_count = 0;
  380. packet_timer = AP_HAL::micros();
  381. chEvtSignal(_irq_handler_ctx, EVT_BIND);
  382. Debug(1,"Starting bind\n");
  383. }
  384. // handle a data96 mavlink packet for fw upload
  385. void AP_Radio_cc2500::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
  386. {
  387. uint32_t ofs=0;
  388. memcpy(&ofs, &m.data[0], 4);
  389. Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
  390. if (sem.take_nonblocking()) {
  391. fwupload.chan = chan;
  392. fwupload.need_ack = false;
  393. fwupload.offset = ofs;
  394. fwupload.length = MIN(m.len-4, 92);
  395. fwupload.acked = 0;
  396. fwupload.sequence++;
  397. if (m.type == 43) {
  398. // sending a tune to play - for development testing
  399. fwupload.fw_type = TELEM_PLAY;
  400. fwupload.length = MIN(m.len, 90);
  401. fwupload.offset = 0;
  402. memcpy(&fwupload.pending_data[0], &m.data[0], fwupload.length);
  403. } else {
  404. // sending a chunk of firmware OTA upload
  405. fwupload.fw_type = TELEM_FW;
  406. memcpy(&fwupload.pending_data[0], &m.data[4], fwupload.length);
  407. }
  408. sem.give();
  409. }
  410. }
  411. /*
  412. handle a FrSky D16 packet
  413. */
  414. bool AP_Radio_cc2500::handle_D16_packet(const uint8_t *packet)
  415. {
  416. if (packet[0] != 0x1D) {
  417. return false;
  418. }
  419. if (packet[1] != bindTxId[0] ||
  420. packet[2] != bindTxId[1]) {
  421. Debug(3, "p1=%02x p2=%02x p6=%02x\n", packet[1], packet[2], packet[6]);
  422. // not for us
  423. return false;
  424. }
  425. if (packet[7] == 0x00 ||
  426. packet[7] == 0x20 ||
  427. packet[7] == 0x10 ||
  428. packet[7] == 0x12 ||
  429. packet[7] == 0x14 ||
  430. packet[7] == 0x16 ||
  431. packet[7] == 0x18 ||
  432. packet[7] == 0x1A ||
  433. packet[7] == 0x1C ||
  434. packet[7] == 0x1E) {
  435. // channel packet or range check packet
  436. parse_frSkyX(packet);
  437. packet3 = packet[3];
  438. uint8_t hop_chan = packet[4] & 0x3F;
  439. uint8_t skip = (packet[4]>>6) | (packet[5]<<2);
  440. if (channr != hop_chan) {
  441. Debug(2, "channr=%u hop_chan=%u\n", channr, hop_chan);
  442. }
  443. channr = hop_chan;
  444. if (chanskip != skip) {
  445. Debug(2, "chanskip=%u skip=%u\n", chanskip, skip);
  446. }
  447. chanskip = skip;
  448. return true;
  449. }
  450. return false;
  451. }
  452. /*
  453. handle a SRT packet
  454. */
  455. bool AP_Radio_cc2500::handle_SRT_packet(const uint8_t *packet)
  456. {
  457. const struct srt_packet *pkt = (const struct srt_packet *)packet;
  458. if (pkt->length != sizeof(struct srt_packet)-1 ||
  459. pkt->txid[0] != bindTxId[0] ||
  460. pkt->txid[1] != bindTxId[1]) {
  461. Debug(3, "len=%u p1=%02x p2=%02x\n", pkt->length, pkt->txid[0], pkt->txid[1]);
  462. // not for us
  463. return false;
  464. }
  465. if (pkt->version != 1) {
  466. // only support version 1 so far
  467. return false;
  468. }
  469. uint16_t chan_new[CC2500_MAX_PWM_CHANNELS];
  470. memcpy(chan_new, pwm_channels, sizeof(pwm_channels));
  471. chan_new[0] = pkt->chan1 + 1000 + ((pkt->chan_high&0xC0)<<2);
  472. chan_new[1] = pkt->chan2 + 1000 + ((pkt->chan_high&0x30)<<4);
  473. chan_new[2] = pkt->chan3 + 1000 + ((pkt->chan_high&0x0C)<<6);
  474. chan_new[3] = pkt->chan4 + 1000 + ((pkt->chan_high&0x03)<<8);
  475. // we map the buttons onto two PWM channels for ease of integration with ArduPilot
  476. chan_new[4] = 1000 + (pkt->buttons & 0x7) * 100;
  477. chan_new[5] = 1000 + (pkt->buttons >> 3) * 100;
  478. // cope with mode1/mode2
  479. map_stick_mode(chan_new);
  480. memcpy(pwm_channels, chan_new, sizeof(pwm_channels));
  481. uint8_t data = pkt->data;
  482. /*
  483. decode special data field
  484. */
  485. switch (pkt->pkt_type) {
  486. case PKTYPE_VOLTAGE:
  487. // voltage from TX is in 0.025 volt units. Convert to 0.01 volt units for easier display
  488. pwm_channels[6] = data * 4;
  489. break;
  490. case PKTYPE_YEAR:
  491. tx_date.firmware_year = data;
  492. break;
  493. case PKTYPE_MONTH:
  494. tx_date.firmware_month = data;
  495. break;
  496. case PKTYPE_DAY:
  497. tx_date.firmware_day = data;
  498. break;
  499. case PKTYPE_TELEM_RSSI:
  500. tx_rssi = data;
  501. break;
  502. case PKTYPE_TELEM_PPS:
  503. tx_pps = data;
  504. if (!have_tx_pps) {
  505. check_double_bind();
  506. }
  507. have_tx_pps = true;
  508. break;
  509. case PKTYPE_BL_VERSION:
  510. // unused so far for cc2500
  511. break;
  512. case PKTYPE_RXID1:
  513. if (data != t_status.rxid[0]) {
  514. Debug(4, "Double bind1 - disconnecting\n");
  515. start_recv_bind();
  516. }
  517. break;
  518. case PKTYPE_RXID2:
  519. if (data != t_status.rxid[1]) {
  520. Debug(4, "Double bind2 - disconnecting\n");
  521. start_recv_bind();
  522. }
  523. break;
  524. case PKTYPE_FW_ACK: {
  525. // got an fw upload ack
  526. Debug(4, "ack %u seq=%u acked=%u length=%u len=%u\n",
  527. data, fwupload.sequence, unsigned(fwupload.acked), unsigned(fwupload.length), fwupload.len);
  528. if (fwupload.sequence == data && sem.take_nonblocking()) {
  529. fwupload.sequence++;
  530. fwupload.acked += fwupload.len;
  531. if (fwupload.acked == fwupload.length) {
  532. // trigger send of DATA16 ack to client
  533. fwupload.need_ack = true;
  534. }
  535. sem.give();
  536. }
  537. break;
  538. }
  539. }
  540. if (chan_count < 7) {
  541. chan_count = 7;
  542. }
  543. if (pkt->channr != channr) {
  544. Debug(2, "channr=%u hop_chan=%u\n", channr, pkt->channr);
  545. channr = pkt->channr;
  546. }
  547. if (pkt->chanskip != chanskip) {
  548. Debug(2, "chanskip=%u skip=%u\n", chanskip, pkt->chanskip);
  549. chanskip = pkt->chanskip;
  550. }
  551. return true;
  552. }
  553. /*
  554. see if we have already assigned a channel
  555. */
  556. bool AP_Radio_cc2500::have_channel(uint8_t channel, uint8_t count, uint8_t loop)
  557. {
  558. uint8_t i;
  559. for (i=0; i<count; i++) {
  560. if (bindHopData[i] == channel) {
  561. return true;
  562. }
  563. if (loop < 5) {
  564. int separation = ((int)bindHopData[i]) - (int)channel;
  565. if (separation < 0) {
  566. separation = -separation;
  567. }
  568. if (separation < 4) {
  569. // try if possible to stay at least 4 channels from existing channels
  570. return true;
  571. }
  572. }
  573. }
  574. return false;
  575. }
  576. /*
  577. mapping from WiFi channel number minus 1 to cc2500 channel
  578. number. WiFi channels are separated by 5MHz starting at 2412 MHz,
  579. except for channel 14, which has a 12MHz separation. We represent
  580. channel 14 as 255 as we want to keep this table 8 bit.
  581. */
  582. static const uint8_t wifi_chan_map[14] = {
  583. 28, 44, 61, 78, 94, 111, 128, 144, 161, 178, 194, 211, 228, 255
  584. };
  585. /*
  586. create hopping table for SRT protocol
  587. */
  588. void AP_Radio_cc2500::setup_hopping_table_SRT(void)
  589. {
  590. uint8_t val;
  591. uint8_t channel = bindTxId[0] % 127;
  592. uint8_t channel_spacing = bindTxId[1] % 127;
  593. uint8_t i;
  594. uint8_t wifi_chan = t_status.wifi_chan;
  595. uint8_t cc_wifi_mid, cc_wifi_low, cc_wifi_high;
  596. const uint8_t wifi_separation = 65;
  597. if (wifi_chan == 0 || wifi_chan > 14) {
  598. wifi_chan = 9;
  599. }
  600. cc_wifi_mid = wifi_chan_map[wifi_chan-1];
  601. if (cc_wifi_mid < wifi_separation) {
  602. cc_wifi_low = 0;
  603. } else {
  604. cc_wifi_low = cc_wifi_mid - wifi_separation;
  605. }
  606. if (cc_wifi_mid > 225) {
  607. cc_wifi_high = 255;
  608. } else {
  609. cc_wifi_high = cc_wifi_mid + wifi_separation;
  610. }
  611. if (channel_spacing < 7) {
  612. channel_spacing += 7;
  613. }
  614. for (i=0; i<NUM_CHANNELS; i++) {
  615. // loop is to prevent any possibility of non-completion
  616. uint8_t loop = 0;
  617. do {
  618. channel = (channel+channel_spacing) % MAX_CHANNEL_NUMBER;
  619. if ((channel <= cc_wifi_low || channel >= cc_wifi_high) && !have_channel(channel, i, loop)) {
  620. // accept if not in wifi range and not already allocated
  621. break;
  622. }
  623. } while (loop++ < 100);
  624. val=channel;
  625. // channels to avoid from D16 code, not properly understood
  626. if ((val==0x00) || (val==0x5A) || (val==0xDC)) {
  627. val++;
  628. }
  629. bindHopData[i] = val;
  630. }
  631. if (get_protocol() != AP_Radio::PROTOCOL_CC2500_GFSK) {
  632. // additional loop to fix any close channels
  633. for (i=0; i<NUM_CHANNELS; i++) {
  634. // first loop only accepts channels that are outside wifi band
  635. if (have_channel(bindHopData[i], i, 0)) {
  636. uint8_t c;
  637. for (c = 0; c<MAX_CHANNEL_NUMBER; c++) {
  638. if ((channel <= cc_wifi_low || channel >= cc_wifi_high) && !have_channel(c, i, 0)) {
  639. bindHopData[i] = c;
  640. break;
  641. }
  642. }
  643. }
  644. // if that fails then accept channels within the wifi band
  645. if (have_channel(bindHopData[i], i, 0)) {
  646. uint8_t c;
  647. for (c = 0; c<MAX_CHANNEL_NUMBER; c++) {
  648. if (!have_channel(c, i, 0)) {
  649. bindHopData[i] = c;
  650. break;
  651. }
  652. }
  653. }
  654. }
  655. }
  656. for (i=0; i<NUM_CHANNELS; i++) {
  657. Debug(3, "%u ", bindHopData[i]);
  658. }
  659. Debug(3, "\n");
  660. last_wifi_channel = t_status.wifi_chan;
  661. Debug(2, "Setup hopping for 0x%x:0x%0x WiFi %u %u-%u spc:%u\n",
  662. bindTxId[0], bindTxId[1],
  663. wifi_chan, cc_wifi_low, cc_wifi_high, channel_spacing);
  664. }
  665. /*
  666. handle a autobind packet
  667. */
  668. bool AP_Radio_cc2500::handle_autobind_packet(const uint8_t *packet, uint8_t lqi)
  669. {
  670. if (get_factory_test() != 0) {
  671. // no autobind in factory test mode
  672. return false;
  673. }
  674. const struct autobind_packet_cc2500 *pkt = (const struct autobind_packet_cc2500 *)packet;
  675. if (stats.recv_packets != 0) {
  676. // don't process autobind packets once we're connected
  677. Debug(4,"autobind discard\n");
  678. return false;
  679. }
  680. if (pkt->length != sizeof(struct autobind_packet_cc2500)-1 ||
  681. pkt->magic1 != 0xC5 ||
  682. pkt->magic2 != 0xA2 ||
  683. pkt->txid[0] != uint8_t(~pkt->txid_inverse[0]) ||
  684. pkt->txid[1] != uint8_t(~pkt->txid_inverse[1])) {
  685. Debug(3, "AB l=%u el=%u m1=%02x m2=%02x %02x:%02x %02x:%02x %02x:%02x\n",
  686. pkt->length, sizeof(struct autobind_packet_cc2500)-1, pkt->magic1, pkt->magic2,
  687. pkt->txid[0], pkt->txid[1], uint8_t(~pkt->txid_inverse[0]), uint8_t(~pkt->txid_inverse[1]),
  688. pkt->crc[0], pkt->crc[1]);
  689. // not a valid autobind packet
  690. return false;
  691. }
  692. for (uint8_t i=0; i<sizeof(pkt->pad); i++) {
  693. if (pkt->pad[i] != i+1) {
  694. Debug(3, "AB pad[%u]=%u\n", i, pkt->pad[i]);
  695. return false;
  696. }
  697. }
  698. uint16_t lcrc = calc_crc(packet,sizeof(*pkt)-2);
  699. if ((lcrc>>8)!=pkt->crc[0] || (lcrc&0x00FF)!=pkt->crc[1]) {
  700. Debug(3, "AB bad CRC\n");
  701. return false;
  702. }
  703. uint8_t rssi_raw = packet[sizeof(struct autobind_packet_cc2500)];
  704. uint8_t rssi_dbm = map_RSSI_to_dBm(rssi_raw);
  705. if (lqi >= 50) {
  706. Debug(3,"autobind bad LQI %u\n", lqi);
  707. return false;
  708. }
  709. if (rssi_dbm < get_autobind_rssi()) {
  710. Debug(1,"autobind RSSI %u needs %u\n", (unsigned)rssi_dbm, (unsigned)get_autobind_rssi());
  711. return false;
  712. }
  713. Debug(1,"autobind RSSI %u above %u lqi=%u bofs=%d\n", (unsigned)rssi_dbm, (unsigned)get_autobind_rssi(), lqi, auto_bindOffset);
  714. bindOffset = auto_bindOffset;
  715. bindTxId[0] = pkt->txid[0];
  716. bindTxId[1] = pkt->txid[1];
  717. listLength = NUM_CHANNELS;
  718. t_status.wifi_chan = pkt->wifi_chan;
  719. setup_hopping_table_SRT();
  720. Debug(1,"Saved bind data\n");
  721. save_bind_info();
  722. return true;
  723. }
  724. /*
  725. map a raw RSSI value to a dBm value
  726. */
  727. uint8_t AP_Radio_cc2500::map_RSSI_to_dBm(uint8_t rssi_raw)
  728. {
  729. float rssi_dbm;
  730. if (rssi_raw >= 128) {
  731. rssi_dbm = ((((uint16_t)rssi_raw) * 18) >> 5) - 82;
  732. } else {
  733. rssi_dbm = ((((uint16_t)rssi_raw) * 18) >> 5) + 65;
  734. }
  735. return rssi_dbm;
  736. }
  737. // main IRQ handler
  738. void AP_Radio_cc2500::irq_handler(void)
  739. {
  740. uint8_t ccLen;
  741. bool matched = false;
  742. do {
  743. ccLen = cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST);
  744. hal.scheduler->delay_microseconds(20);
  745. uint8_t ccLen2 = cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST);
  746. matched = (ccLen == ccLen2);
  747. } while (!matched);
  748. if (ccLen & 0x80) {
  749. Debug(6,"Fifo overflow %02x\n", ccLen);
  750. // RX FIFO overflow
  751. cc2500.Strobe(CC2500_SFRX);
  752. cc2500.Strobe(CC2500_SRX);
  753. return;
  754. }
  755. uint8_t packet[ccLen];
  756. cc2500.ReadFifo(packet, ccLen);
  757. if (get_fcc_test() != 0) {
  758. // don't process interrupts in FCCTEST mode
  759. return;
  760. }
  761. if (ccLen != 32 &&
  762. ccLen != sizeof(srt_packet)+2 &&
  763. ccLen != sizeof(autobind_packet_cc2500)+2) {
  764. cc2500.Strobe(CC2500_SFRX);
  765. cc2500.Strobe(CC2500_SRX);
  766. Debug(4, "bad len %u SRT=%u AB=%u\n", ccLen,
  767. sizeof(srt_packet)+2,
  768. sizeof(autobind_packet_cc2500)+2);
  769. return;
  770. }
  771. if (get_debug_level() > 6) {
  772. Debug(6, "CC2500 IRQ state=%u\n", unsigned(protocolState));
  773. Debug(6,"len=%u\n", ccLen);
  774. for (uint8_t i=0; i<ccLen; i++) {
  775. Debug(6, "%02x:%02x ", i, packet[i]);
  776. if ((i+1) % 16 == 0) {
  777. Debug(6, "\n");
  778. }
  779. }
  780. if (ccLen % 16 != 0) {
  781. Debug(6, "\n");
  782. }
  783. }
  784. if (!check_crc(ccLen, packet)) {
  785. Debug(4, "bad CRC ccLen=%u\n", ccLen);
  786. return;
  787. }
  788. switch (protocolState) {
  789. case STATE_BIND_TUNING:
  790. tuneRx(ccLen, packet);
  791. break;
  792. case STATE_BIND_BINDING:
  793. if (getBindData(ccLen, packet)) {
  794. Debug(2,"Bind complete\n");
  795. protocolState = STATE_BIND_COMPLETE;
  796. }
  797. break;
  798. case STATE_BIND_COMPLETE:
  799. protocolState = STATE_STARTING;
  800. save_bind_info();
  801. Debug(3,"listLength=%u\n", listLength);
  802. Debug(3,"Saved bind info\n");
  803. break;
  804. case STATE_STARTING:
  805. listLength = NUM_CHANNELS;
  806. initialiseData(0);
  807. protocolState = STATE_SEARCH;
  808. chanskip = 1;
  809. nextChannel(1);
  810. break;
  811. case STATE_SEARCH:
  812. protocolState = STATE_DATA;
  813. // fallthrough
  814. case STATE_DATA: {
  815. bool ok = false;
  816. if (ccLen == 32) {
  817. ok = handle_D16_packet(packet);
  818. } else if (ccLen == sizeof(srt_packet)+2) {
  819. ok = handle_SRT_packet(packet);
  820. if (!ok) {
  821. uint8_t Lqi = packet[ccLen - 1] & 0x7F;
  822. ok = handle_autobind_packet(packet, Lqi);
  823. }
  824. }
  825. if (ok) {
  826. // get RSSI value from status byte
  827. uint8_t rssi_raw = packet[ccLen-2];
  828. float rssi_dbm = map_RSSI_to_dBm(rssi_raw);
  829. rssi_filtered = 0.95 * rssi_filtered + 0.05 * rssi_dbm;
  830. t_status.rssi = uint8_t(MAX(rssi_filtered, 1));
  831. if (stats.recv_packets == 0) {
  832. Debug(3,"cc2500: got 1st packet\n");
  833. }
  834. stats.recv_packets++;
  835. packet_timer = irq_time_us;
  836. chVTSet(&timeout_vt, chTimeMS2I(INTER_PACKET_INITIAL_MS), trigger_timeout_event, nullptr);
  837. cc2500.Strobe(CC2500_SIDLE);
  838. if (get_telem_enable()) {
  839. cc2500.SetPower(get_transmit_power());
  840. if (ccLen == 32 || get_protocol() == AP_Radio::PROTOCOL_D16) {
  841. send_D16_telemetry();
  842. } else {
  843. if (have_tx_pps) {
  844. /* we don't start sending telemetry until we have the tx_pps rate. This allows us
  845. to reliably detect double-bind, where one TX is bound to multiple RX
  846. */
  847. send_SRT_telemetry();
  848. }
  849. }
  850. // now we sleep for enough time for the packet to be
  851. // transmitted. We can safely sleep here as we have a
  852. // dedicated thread for radio processing.
  853. cc2500.unlock_bus();
  854. hal.scheduler->delay_microseconds(PACKET_SENT_DELAY_US);
  855. cc2500.lock_bus();
  856. }
  857. nextChannel(chanskip);
  858. }
  859. break;
  860. }
  861. case STATE_FCCTEST:
  862. // nothing to do, all done in timeout code
  863. Debug(3,"IRQ in FCCTEST state\n");
  864. break;
  865. default:
  866. Debug(2,"state %u\n", (unsigned)protocolState);
  867. break;
  868. }
  869. }
  870. /*
  871. setup for the 6 possible FCC channel values (3 normal, 3 CW)
  872. */
  873. void AP_Radio_cc2500::set_fcc_channel(void)
  874. {
  875. uint8_t chan = MAX_CHANNEL_NUMBER/2;
  876. switch (get_fcc_test()) {
  877. case 1:
  878. case 4:
  879. chan = 0;
  880. break;
  881. case 2:
  882. case 5:
  883. chan = MAX_CHANNEL_NUMBER/2;
  884. break;
  885. case 3:
  886. case 6:
  887. chan = MAX_CHANNEL_NUMBER-1;
  888. break;
  889. }
  890. setChannel(chan);
  891. }
  892. // handle timeout IRQ
  893. void AP_Radio_cc2500::irq_timeout(void)
  894. {
  895. if (get_fcc_test() != 0 && protocolState != STATE_FCCTEST) {
  896. protocolState = STATE_FCCTEST;
  897. last_fcc_chan = 0;
  898. set_fcc_channel();
  899. send_SRT_telemetry();
  900. }
  901. switch (protocolState) {
  902. case STATE_BIND_TUNING: {
  903. if (bindOffset >= 126) {
  904. if (check_best_LQI()) {
  905. return;
  906. }
  907. bindOffset = -126;
  908. }
  909. uint32_t now = AP_HAL::millis();
  910. if (now - timeTunedMs > 20) {
  911. timeTunedMs = now;
  912. bindOffset += 5;
  913. Debug(6,"bindOffset=%d\n", int(bindOffset));
  914. cc2500.Strobe(CC2500_SIDLE);
  915. cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
  916. cc2500.Strobe(CC2500_SFRX);
  917. cc2500.Strobe(CC2500_SRX);
  918. }
  919. break;
  920. }
  921. case STATE_DATA: {
  922. uint32_t now = AP_HAL::micros();
  923. if (now - packet_timer > SEARCH_START_PKTS*INTER_PACKET_MS*1000UL) {
  924. Debug(3,"searching %u\n", unsigned(now - packet_timer));
  925. cc2500.Strobe(CC2500_SIDLE);
  926. cc2500.Strobe(CC2500_SFRX);
  927. nextChannel(1);
  928. cc2500.Strobe(CC2500_SRX);
  929. timeouts++;
  930. protocolState = STATE_SEARCH;
  931. search_count = 0;
  932. } else {
  933. // to keep the timeouts a constant time behind the
  934. // expected time we need to set the timeout to the
  935. // inter-packet delay again now
  936. chVTSet(&timeout_vt, chTimeMS2I(INTER_PACKET_MS), trigger_timeout_event, nullptr);
  937. nextChannel(chanskip);
  938. lost++;
  939. }
  940. break;
  941. }
  942. case STATE_SEARCH: {
  943. uint32_t now = AP_HAL::millis();
  944. search_count++;
  945. if (stats.recv_packets == 0 &&
  946. get_autobind_time() != 0 &&
  947. get_factory_test() == 0 &&
  948. (AP_HAL::micros() - packet_timer) > get_autobind_time() * 1000UL*1000UL &&
  949. (search_count & 1) == 0) {
  950. // try for an autobind packet every 2nd packet, waiting 3 packet delays
  951. static uint32_t cc;
  952. auto_bindOffset += 5;
  953. if (auto_bindOffset >= 126) {
  954. auto_bindOffset = -126;
  955. }
  956. Debug(4,"ab recv %u boffset=%d", unsigned(cc), int(auto_bindOffset));
  957. cc++;
  958. cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, (uint8_t)auto_bindOffset);
  959. setChannelRX(AUTOBIND_CHANNEL);
  960. autobind_start_recv_ms = now;
  961. chVTSet(&timeout_vt, chTimeMS2I(60), trigger_timeout_event, nullptr);
  962. } else {
  963. // shift by one channel at a time when searching
  964. if (autobind_start_recv_ms == 0 || now - autobind_start_recv_ms > 50) {
  965. autobind_start_recv_ms = 0;
  966. cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
  967. nextChannel(1);
  968. }
  969. }
  970. break;
  971. }
  972. case STATE_FCCTEST: {
  973. if (get_fcc_test() == 0) {
  974. protocolState = STATE_DATA;
  975. Debug(1,"Ending FCCTEST\n");
  976. }
  977. // send every 9ms
  978. chVTSet(&timeout_vt, chTimeMS2I(INTER_PACKET_MS), trigger_timeout_event, nullptr);
  979. cc2500.SetPower(get_transmit_power());
  980. if (get_fcc_test() < 4 || last_fcc_chan != get_fcc_test()) {
  981. set_fcc_channel();
  982. send_SRT_telemetry();
  983. }
  984. if (last_fcc_chan != get_fcc_test() && get_fcc_test() != 0) {
  985. Debug(1,"Starting FCCTEST %u at power %u\n", unsigned(get_fcc_test()), unsigned(get_transmit_power()));
  986. }
  987. last_fcc_chan = get_fcc_test();
  988. break;
  989. }
  990. default:
  991. break;
  992. }
  993. }
  994. void AP_Radio_cc2500::irq_handler_thd(void *arg)
  995. {
  996. (void)arg;
  997. while (true) {
  998. eventmask_t evt = chEvtWaitAny(ALL_EVENTS);
  999. radio_singleton->cc2500.lock_bus();
  1000. switch (evt) {
  1001. case EVT_IRQ:
  1002. if (radio_singleton->protocolState == STATE_FCCTEST) {
  1003. hal.console->printf("IRQ FCC\n");
  1004. }
  1005. radio_singleton->irq_handler();
  1006. break;
  1007. case EVT_TIMEOUT:
  1008. if (radio_singleton->cc2500.ReadReg(CC2500_3B_RXBYTES | CC2500_READ_BURST) & 0x80) {
  1009. irq_time_us = AP_HAL::micros();
  1010. radio_singleton->irq_handler();
  1011. } else {
  1012. radio_singleton->irq_timeout();
  1013. }
  1014. break;
  1015. case EVT_BIND:
  1016. // clear the current bind information
  1017. radio_singleton->bindTxId[0] = 1;
  1018. radio_singleton->bindTxId[1] = 1;
  1019. radio_singleton->setup_hopping_table_SRT();
  1020. radio_singleton->protocolState = STATE_SEARCH;
  1021. radio_singleton->packet_timer = AP_HAL::micros();
  1022. radio_singleton->stats.recv_packets = 0;
  1023. radio_singleton->chanskip = 1;
  1024. radio_singleton->nextChannel(1);
  1025. radio_singleton->save_bind_info();
  1026. break;
  1027. default:
  1028. break;
  1029. }
  1030. radio_singleton->cc2500.unlock_bus();
  1031. }
  1032. }
  1033. void AP_Radio_cc2500::initTuneRx(void)
  1034. {
  1035. cc2500.WriteReg(CC2500_19_FOCCFG, 0x14);
  1036. timeTunedMs = AP_HAL::millis();
  1037. bindOffset = -126;
  1038. best_lqi = 255;
  1039. best_bindOffset = bindOffset;
  1040. cc2500.WriteReg(CC2500_0C_FSCTRL0, (uint8_t)bindOffset);
  1041. //cc2500.WriteReg(CC2500_07_PKTCTRL1, 0x0C);
  1042. //cc2500.WriteReg(CC2500_18_MCSM0, 0x8);
  1043. setChannelRX(0);
  1044. }
  1045. void AP_Radio_cc2500::initialiseData(uint8_t adr)
  1046. {
  1047. cc2500.WriteRegCheck(CC2500_0C_FSCTRL0, bindOffset);
  1048. //cc2500.WriteRegCheck(CC2500_18_MCSM0, 0x8);
  1049. //cc2500.WriteRegCheck(CC2500_07_PKTCTRL1, 0x0D); // address check, no broadcast, autoflush, status enable
  1050. cc2500.WriteRegCheck(CC2500_19_FOCCFG, 0x16);
  1051. hal.scheduler->delay_microseconds(10*1000);
  1052. }
  1053. void AP_Radio_cc2500::initGetBind(void)
  1054. {
  1055. setChannelRX(0);
  1056. hal.scheduler->delay_microseconds(20); // waiting flush FIFO
  1057. cc2500.Strobe(CC2500_SRX);
  1058. listLength = 0;
  1059. }
  1060. /*
  1061. we've wrapped in the search for the best bind offset. Accept the
  1062. best so far if its good enough
  1063. */
  1064. bool AP_Radio_cc2500::check_best_LQI(void)
  1065. {
  1066. if (best_lqi >= 50) {
  1067. return false;
  1068. }
  1069. bindOffset = best_bindOffset;
  1070. initGetBind();
  1071. initialiseData(1);
  1072. protocolState = STATE_BIND_BINDING;
  1073. bind_mask = 0;
  1074. listLength = 0;
  1075. Debug(2,"Bind tuning %d with Lqi %u\n", best_bindOffset, best_lqi);
  1076. return true;
  1077. }
  1078. /*
  1079. check if we have received a packet with sufficiently good link
  1080. quality to start binding
  1081. */
  1082. bool AP_Radio_cc2500::tuneRx(uint8_t ccLen, uint8_t *packet)
  1083. {
  1084. if (bindOffset >= 126) {
  1085. // we've scanned the whole range, if any were below 50 then
  1086. // accept it
  1087. if (check_best_LQI()) {
  1088. return true;
  1089. }
  1090. bindOffset = -126;
  1091. }
  1092. if ((packet[ccLen - 1] & 0x80) && packet[2] == 0x01) {
  1093. uint8_t Lqi = packet[ccLen - 1] & 0x7F;
  1094. if (Lqi < best_lqi) {
  1095. best_lqi = Lqi;
  1096. best_bindOffset = bindOffset;
  1097. }
  1098. }
  1099. return false;
  1100. }
  1101. /*
  1102. get a block of hopping data from a bind packet
  1103. */
  1104. bool AP_Radio_cc2500::getBindData(uint8_t ccLen, uint8_t *packet)
  1105. {
  1106. // parse a bind data packet */
  1107. if ((packet[ccLen - 1] & 0x80) && packet[2] == 0x01) {
  1108. if (bind_mask == 0) {
  1109. bindTxId[0] = packet[3];
  1110. bindTxId[1] = packet[4];
  1111. } else if (bindTxId[0] != packet[3] ||
  1112. bindTxId[1] != packet[4]) {
  1113. Debug(2,"Bind restart\n");
  1114. bind_mask = 0;
  1115. listLength = 0;
  1116. }
  1117. for (uint8_t n = 0; n < 5; n++) {
  1118. uint8_t c = packet[5] + n;
  1119. if (c < sizeof(bindHopData)) {
  1120. bindHopData[c] = packet[6 + n];
  1121. bind_mask |= (uint64_t(1)<<c);
  1122. listLength = MAX(listLength, c+1);
  1123. }
  1124. }
  1125. // bind has finished when we have hopping data for all channels
  1126. return (listLength == NUM_CHANNELS && bind_mask == ((uint64_t(1)<<NUM_CHANNELS)-1));
  1127. }
  1128. return false;
  1129. }
  1130. void AP_Radio_cc2500::setChannel(uint8_t channel)
  1131. {
  1132. cc2500.Strobe(CC2500_SIDLE);
  1133. cc2500.WriteReg(CC2500_0A_CHANNR, channel);
  1134. // manually recalibrate the PLL for the new channel. This
  1135. // allows for temperature change and voltage fluctuation on
  1136. // the flight board
  1137. cc2500.Strobe(CC2500_SCAL);
  1138. hal.scheduler->delay_microseconds(730);
  1139. }
  1140. void AP_Radio_cc2500::setChannelRX(uint8_t channel)
  1141. {
  1142. setChannel(channel);
  1143. cc2500.Strobe(CC2500_SFRX);
  1144. cc2500.Strobe(CC2500_SRX);
  1145. }
  1146. void AP_Radio_cc2500::nextChannel(uint8_t skip)
  1147. {
  1148. channr = (channr + skip) % listLength;
  1149. setChannelRX(bindHopData[channr]);
  1150. }
  1151. void AP_Radio_cc2500::parse_frSkyX(const uint8_t *packet)
  1152. {
  1153. uint16_t c[8];
  1154. c[0] = (uint16_t)((packet[10] <<8)& 0xF00) | packet[9];
  1155. c[1] = (uint16_t)((packet[11]<<4)&0xFF0) | (packet[10]>>4);
  1156. c[2] = (uint16_t)((packet[13] <<8)& 0xF00) | packet[12];
  1157. c[3] = (uint16_t)((packet[14]<<4)&0xFF0) | (packet[13]>>4);
  1158. c[4] = (uint16_t)((packet[16] <<8)& 0xF00) | packet[15];
  1159. c[5] = (uint16_t)((packet[17]<<4)&0xFF0) | (packet[16]>>4);
  1160. c[6] = (uint16_t)((packet[19] <<8)& 0xF00) | packet[18];
  1161. c[7] = (uint16_t)((packet[20]<<4)&0xFF0) | (packet[19]>>4);
  1162. uint8_t j;
  1163. for (uint8_t i=0; i<8; i++) {
  1164. if (c[i] > 2047) {
  1165. j = 8;
  1166. c[i] = c[i] - 2048;
  1167. } else {
  1168. j = 0;
  1169. }
  1170. if (c[i] == 0) {
  1171. continue;
  1172. }
  1173. uint16_t word_temp = (((c[i]-64)<<1)/3+860);
  1174. if ((word_temp > 800) && (word_temp < 2200)) {
  1175. uint8_t chan = i+j;
  1176. if (chan < CC2500_MAX_PWM_CHANNELS) {
  1177. pwm_channels[chan] = word_temp;
  1178. if (chan >= chan_count) {
  1179. chan_count = chan+1;
  1180. }
  1181. }
  1182. }
  1183. }
  1184. }
  1185. uint16_t AP_Radio_cc2500::calc_crc(const uint8_t *data, uint8_t len)
  1186. {
  1187. uint16_t crc = 0;
  1188. for (uint8_t i=0; i < len; i++) {
  1189. crc = (crc<<8) ^ (CRCTable[((uint8_t)(crc>>8) ^ *data++) & 0xFF]);
  1190. }
  1191. return crc;
  1192. }
  1193. bool AP_Radio_cc2500::check_crc(uint8_t ccLen, uint8_t *packet)
  1194. {
  1195. if (ccLen == sizeof(srt_packet)+2 ||
  1196. ccLen == sizeof(autobind_packet_cc2500)+2) {
  1197. // using hardware CRC
  1198. return true;
  1199. } else if (ccLen == 32) {
  1200. // D16 packet
  1201. uint16_t lcrc = calc_crc(&packet[3],(ccLen-7));
  1202. return ((lcrc >>8)==packet[ccLen-4] && (lcrc&0x00FF)==packet[ccLen-3]);
  1203. }
  1204. return false;
  1205. }
  1206. /*
  1207. save bind info
  1208. */
  1209. void AP_Radio_cc2500::save_bind_info(void)
  1210. {
  1211. // access to storage for bind information
  1212. StorageAccess bind_storage(StorageManager::StorageBindInfo);
  1213. struct bind_info info;
  1214. info.magic = bind_magic;
  1215. info.bindTxId[0] = bindTxId[0];
  1216. info.bindTxId[1] = bindTxId[1];
  1217. info.bindOffset = bindOffset;
  1218. info.wifi_chan = t_status.wifi_chan;
  1219. memcpy(info.bindHopData, bindHopData, sizeof(info.bindHopData));
  1220. bind_storage.write_block(0, &info, sizeof(info));
  1221. }
  1222. /*
  1223. load bind info
  1224. */
  1225. bool AP_Radio_cc2500::load_bind_info(void)
  1226. {
  1227. // access to storage for bind information
  1228. StorageAccess bind_storage(StorageManager::StorageBindInfo);
  1229. struct bind_info info;
  1230. if (!bind_storage.read_block(&info, 0, sizeof(info)) || info.magic != bind_magic) {
  1231. return false;
  1232. }
  1233. bindTxId[0] = info.bindTxId[0];
  1234. bindTxId[1] = info.bindTxId[1];
  1235. bindOffset = info.bindOffset;
  1236. listLength = NUM_CHANNELS;
  1237. t_status.wifi_chan = info.wifi_chan;
  1238. memcpy(bindHopData, info.bindHopData, sizeof(bindHopData));
  1239. setup_hopping_table_SRT();
  1240. return true;
  1241. }
  1242. /*
  1243. send a D16 telemetry packet
  1244. */
  1245. void AP_Radio_cc2500::send_D16_telemetry(void)
  1246. {
  1247. uint8_t frame[15];
  1248. memset(frame, 0, sizeof(frame));
  1249. frame[0] = sizeof(frame)-1;
  1250. frame[1] = bindTxId[0];
  1251. frame[2] = bindTxId[1];
  1252. frame[3] = packet3;
  1253. if (telem_send_rssi) {
  1254. frame[4] = MAX(MIN(t_status.rssi, 0x7f),1) | 0x80;
  1255. } else {
  1256. frame[4] = uint8_t(hal.analogin->board_voltage() * 10) & 0x7F;
  1257. }
  1258. telem_send_rssi = !telem_send_rssi;
  1259. uint16_t lcrc = calc_crc(&frame[3], 10);
  1260. frame[13] = lcrc>>8;
  1261. frame[14] = lcrc;
  1262. cc2500.Strobe(CC2500_SIDLE);
  1263. cc2500.Strobe(CC2500_SFTX);
  1264. if (get_fcc_test() <= 3) {
  1265. // in CW FCC test modes we don't write to the FIFO, which
  1266. // gives continuous transmission
  1267. cc2500.WriteFifo(frame, sizeof(frame));
  1268. }
  1269. cc2500.Strobe(CC2500_STX);
  1270. }
  1271. /*
  1272. send a SRT telemetry packet
  1273. */
  1274. void AP_Radio_cc2500::send_SRT_telemetry(void)
  1275. {
  1276. struct telem_packet_cc2500 pkt {};
  1277. pkt.length = sizeof(pkt)-1;
  1278. t_status.flags = 0;
  1279. t_status.flags |= AP_Notify::flags.gps_status >= 3?TELEM_FLAG_GPS_OK:0;
  1280. t_status.flags |= AP_Notify::flags.pre_arm_check?TELEM_FLAG_ARM_OK:0;
  1281. t_status.flags |= AP_Notify::flags.failsafe_battery?0:TELEM_FLAG_BATT_OK;
  1282. t_status.flags |= hal.util->get_soft_armed()?TELEM_FLAG_ARMED:0;
  1283. t_status.flags |= AP_Notify::flags.have_pos_abs?TELEM_FLAG_POS_OK:0;
  1284. t_status.flags |= AP_Notify::flags.video_recording?TELEM_FLAG_VIDEO:0;
  1285. t_status.flight_mode = AP_Notify::flags.flight_mode;
  1286. t_status.tx_max = get_tx_max_power();
  1287. t_status.note_adjust = get_tx_buzzer_adjust();
  1288. // send fw update packet for 7/8 of packets if any data pending
  1289. if (fwupload.length != 0 &&
  1290. fwupload.length > fwupload.acked &&
  1291. ((fwupload.counter++ & 0x07) != 0) &&
  1292. sem.take_nonblocking()) {
  1293. pkt.type = fwupload.fw_type;
  1294. pkt.payload.fw.seq = fwupload.sequence;
  1295. uint32_t len = fwupload.length>fwupload.acked?fwupload.length - fwupload.acked:0;
  1296. const uint8_t maxlen = sizeof(pkt.payload.fw.data);
  1297. pkt.payload.fw.len = len<=maxlen?len:maxlen;
  1298. pkt.payload.fw.offset = fwupload.offset+fwupload.acked;
  1299. memcpy(&pkt.payload.fw.data[0], &fwupload.pending_data[fwupload.acked], pkt.payload.fw.len);
  1300. fwupload.len = pkt.payload.fw.len;
  1301. Debug(4, "sent fw seq=%u offset=%u len=%u type=%u\n",
  1302. pkt.payload.fw.seq,
  1303. pkt.payload.fw.offset,
  1304. pkt.payload.fw.len,
  1305. pkt.type);
  1306. sem.give();
  1307. } else {
  1308. pkt.type = TELEM_STATUS;
  1309. pkt.payload.status = t_status;
  1310. }
  1311. pkt.txid[0] = bindTxId[0];
  1312. pkt.txid[1] = bindTxId[1];
  1313. cc2500.Strobe(CC2500_SIDLE);
  1314. cc2500.Strobe(CC2500_SFTX);
  1315. if (get_fcc_test() <= 3) {
  1316. // in CW FCC test modes we don't write to the FIFO, which gives
  1317. // continuous transmission
  1318. cc2500.WriteFifo((const uint8_t *)&pkt, sizeof(pkt));
  1319. }
  1320. cc2500.Strobe(CC2500_STX);
  1321. if (last_wifi_channel != t_status.wifi_chan) {
  1322. setup_hopping_table_SRT();
  1323. save_bind_info();
  1324. }
  1325. telem_send_count++;
  1326. }
  1327. /*
  1328. send a fwupload ack if needed
  1329. */
  1330. void AP_Radio_cc2500::check_fw_ack(void)
  1331. {
  1332. if (fwupload.need_ack && sem.take_nonblocking()) {
  1333. // ack the send of a DATA96 fw packet to TX
  1334. fwupload.need_ack = false;
  1335. uint8_t data16[16] {};
  1336. uint32_t ack_to = fwupload.offset + fwupload.acked;
  1337. memcpy(&data16[0], &ack_to, 4);
  1338. mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
  1339. Debug(4,"sent ack DATA16\n");
  1340. sem.give();
  1341. }
  1342. }
  1343. /*
  1344. support all 4 rc input modes by swapping channels.
  1345. */
  1346. void AP_Radio_cc2500::map_stick_mode(uint16_t *channels)
  1347. {
  1348. switch (get_stick_mode()) {
  1349. case 1: {
  1350. // mode1
  1351. uint16_t tmp = channels[1];
  1352. channels[1] = 3000 - channels[2];
  1353. channels[2] = 3000 - tmp;
  1354. break;
  1355. }
  1356. case 3: {
  1357. // mode3
  1358. uint16_t tmp = channels[1];
  1359. channels[1] = 3000 - channels[2];
  1360. channels[2] = 3000 - tmp;
  1361. tmp = channels[0];
  1362. channels[0] = channels[3];
  1363. channels[3] = tmp;
  1364. break;
  1365. }
  1366. case 4: {
  1367. // mode4
  1368. uint16_t tmp = channels[0];
  1369. channels[0] = channels[3];
  1370. channels[3] = tmp;
  1371. break;
  1372. }
  1373. case 2:
  1374. default:
  1375. // nothing to do, transmitter is natively mode2
  1376. break;
  1377. }
  1378. }
  1379. /*
  1380. check if we are the 2nd RX bound to this TX
  1381. */
  1382. void AP_Radio_cc2500::check_double_bind(void)
  1383. {
  1384. if (tx_pps <= telem_send_count ||
  1385. get_autobind_time() == 0) {
  1386. return;
  1387. }
  1388. // the TX has received more telemetry packets in the last second
  1389. // than we have ever sent. There must be another RX sending
  1390. // telemetry packets. We will reset our mfg_id and go back waiting
  1391. // for a new bind packet, hopefully with the right TX
  1392. Debug(1,"Double-bind detected\n");
  1393. // clear the current bind information
  1394. radio_singleton->bindTxId[0] = 1;
  1395. radio_singleton->bindTxId[1] = 1;
  1396. radio_singleton->setup_hopping_table_SRT();
  1397. radio_singleton->protocolState = STATE_SEARCH;
  1398. radio_singleton->packet_timer = AP_HAL::micros();
  1399. radio_singleton->stats.recv_packets = 0;
  1400. radio_singleton->chanskip = 1;
  1401. radio_singleton->nextChannel(1);
  1402. }
  1403. #endif // HAL_RCINPUT_WITH_AP_RADIO
  1404. #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS