AP_Radio_bk2425.cpp 54 KB

12345678910111213141516171819202122232425262728293031323334353637383940414243444546474849505152535455565758596061626364656667686970717273747576777879808182838485868788899091929394959697989910010110210310410510610710810911011111211311411511611711811912012112212312412512612712812913013113213313413513613713813914014114214314414514614714814915015115215315415515615715815916016116216316416516616716816917017117217317417517617717817918018118218318418518618718818919019119219319419519619719819920020120220320420520620720820921021121221321421521621721821922022122222322422522622722822923023123223323423523623723823924024124224324424524624724824925025125225325425525625725825926026126226326426526626726826927027127227327427527627727827928028128228328428528628728828929029129229329429529629729829930030130230330430530630730830931031131231331431531631731831932032132232332432532632732832933033133233333433533633733833934034134234334434534634734834935035135235335435535635735835936036136236336436536636736836937037137237337437537637737837938038138238338438538638738838939039139239339439539639739839940040140240340440540640740840941041141241341441541641741841942042142242342442542642742842943043143243343443543643743843944044144244344444544644744844945045145245345445545645745845946046146246346446546646746846947047147247347447547647747847948048148248348448548648748848949049149249349449549649749849950050150250350450550650750850951051151251351451551651751851952052152252352452552652752852953053153253353453553653753853954054154254354454554654754854955055155255355455555655755855956056156256356456556656756856957057157257357457557657757857958058158258358458558658758858959059159259359459559659759859960060160260360460560660760860961061161261361461561661761861962062162262362462562662762862963063163263363463563663763863964064164264364464564664764864965065165265365465565665765865966066166266366466566666766866967067167267367467567667767867968068168268368468568668768868969069169269369469569669769869970070170270370470570670770870971071171271371471571671771871972072172272372472572672772872973073173273373473573673773873974074174274374474574674774874975075175275375475575675775875976076176276376476576676776876977077177277377477577677777877978078178278378478578678778878979079179279379479579679779879980080180280380480580680780880981081181281381481581681781881982082182282382482582682782882983083183283383483583683783883984084184284384484584684784884985085185285385485585685785885986086186286386486586686786886987087187287387487587687787887988088188288388488588688788888989089189289389489589689789889990090190290390490590690790890991091191291391491591691791891992092192292392492592692792892993093193293393493593693793893994094194294394494594694794894995095195295395495595695795895996096196296396496596696796896997097197297397497597697797897998098198298398498598698798898999099199299399499599699799899910001001100210031004100510061007100810091010101110121013101410151016101710181019102010211022102310241025102610271028102910301031103210331034103510361037103810391040104110421043104410451046104710481049105010511052105310541055105610571058105910601061106210631064106510661067106810691070107110721073107410751076107710781079108010811082108310841085108610871088108910901091109210931094109510961097109810991100110111021103110411051106110711081109111011111112111311141115111611171118111911201121112211231124112511261127112811291130113111321133113411351136113711381139114011411142114311441145114611471148114911501151115211531154115511561157115811591160116111621163116411651166116711681169117011711172117311741175117611771178117911801181118211831184118511861187118811891190119111921193119411951196119711981199120012011202120312041205120612071208120912101211121212131214121512161217121812191220122112221223122412251226122712281229123012311232123312341235123612371238123912401241124212431244124512461247124812491250125112521253125412551256125712581259126012611262126312641265126612671268126912701271127212731274127512761277127812791280128112821283128412851286128712881289129012911292129312941295129612971298129913001301130213031304130513061307130813091310131113121313131413151316131713181319132013211322132313241325132613271328132913301331133213331334133513361337133813391340134113421343134413451346134713481349135013511352135313541355135613571358135913601361136213631364136513661367136813691370137113721373137413751376137713781379138013811382138313841385138613871388138913901391139213931394139513961397139813991400140114021403140414051406140714081409141014111412141314141415
  1. /*
  2. driver for Beken_2425 radio
  3. */
  4. #include <AP_HAL/AP_HAL.h>
  5. //#pragma GCC optimize("O0")
  6. #if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
  7. #include <AP_Math/AP_Math.h>
  8. #include "AP_Radio_bk2425.h"
  9. #include <utility>
  10. #include <stdio.h>
  11. #include <StorageManager/StorageManager.h>
  12. #include <AP_Notify/AP_Notify.h>
  13. #include <GCS_MAVLink/GCS_MAVLink.h>
  14. // start of 12 byte CPU ID
  15. #ifndef UDID_START
  16. #define UDID_START 0x1FFF7A10
  17. #endif
  18. #define TIMEOUT_PRIORITY 250 // Right above timer thread
  19. #define EVT_TIMEOUT EVENT_MASK(0) // Event in the irq handler thread triggered by a timeout interrupt
  20. #define EVT_IRQ EVENT_MASK(1) // Event in the irq handler thread triggered by a radio IRQ (Tx finished, Rx finished, MaxRetries limit)
  21. #define EVT_BIND EVENT_MASK(2) // (not used yet) The user has clicked on the "start bind" button in the web interface (or equivalent).
  22. extern const AP_HAL::HAL& hal;
  23. // Output debug information on the UART, wrapped in MavLink packets
  24. #define Debug(level, fmt, args...) do { if ((level) <= get_debug_level()) { hal.console->printf(fmt, ##args); }} while (0)
  25. // Output fast debug information on the UART, in raw format. MavLink should be disabled if you want to understand these messages.
  26. // This is for debugging issues with frequency hopping and synchronisation.
  27. #define DebugPrintf(level, fmt, args...) do { if (AP_Radio_beken::radio_singleton && ((level) <= AP_Radio_beken::radio_singleton->get_debug_level())) { printf(fmt, ##args); }} while (0)
  28. // Output debug information on the mavlink to the UART connected to the WiFi, wrapped in MavLink packets
  29. #define DebugMavlink(level, fmt, args...) do { if ((level) <= get_debug_level()) { gcs().send_text(MAV_SEVERITY_INFO, fmt, ##args); }} while (0)
  30. // object instance for trampoline
  31. AP_Radio_beken *AP_Radio_beken::radio_singleton;
  32. thread_t *AP_Radio_beken::_irq_handler_ctx;
  33. virtual_timer_t AP_Radio_beken::timeout_vt;
  34. // See variable definitions in AP_Radio_bk2425.h for comments
  35. uint32_t AP_Radio_beken::isr_irq_time_us;
  36. uint32_t AP_Radio_beken::isr_timeout_time_us;
  37. uint32_t AP_Radio_beken::next_switch_us;
  38. uint32_t AP_Radio_beken::bind_time_ms;
  39. SyncTiming AP_Radio_beken::synctm; // Let the IRQ see the interpacket timing
  40. // -----------------------------------------------------------------------------
  41. // We have received a packet
  42. // Sort out our timing relative to the tx to avoid clock drift
  43. void SyncTiming::Rx(uint32_t when)
  44. {
  45. uint32_t ld = delta_rx_time_us;
  46. uint32_t d = when - rx_time_us;
  47. if ((d > ld - DIFF_DELTA_RX) && (d < ld + DIFF_DELTA_RX)) { // Two deltas are similar to each other
  48. if ((d > TARGET_DELTA_RX-SLOP_DELTA_RX) && (d < TARGET_DELTA_RX+SLOP_DELTA_RX)) { // delta is within range of single packet distance
  49. // Use filter to change the estimate of the time in microseconds between the transmitters packet (according to OUR clock)
  50. sync_time_us = ((sync_time_us * (256-16)) + (d * 16)) / 256;
  51. }
  52. }
  53. rx_time_us = when;
  54. delta_rx_time_us = d;
  55. last_delta_rx_time_us = ld;
  56. }
  57. // -----------------------------------------------------------------------------
  58. // Implement queuing (a 92 byte packet) in the circular buffer
  59. void FwUpload::queue(const uint8_t *pSrc, uint8_t len)
  60. {
  61. if (len == 0 || len > free_length()) {
  62. return; // Safety check for out of space error
  63. }
  64. if (pending_head + len > SZ_BUFFER) {
  65. uint8_t n = SZ_BUFFER-pending_head;
  66. memcpy(&pending_data[pending_head], pSrc, n);
  67. memcpy(&pending_data[0], pSrc+n, len-n);
  68. } else {
  69. memcpy(&pending_data[pending_head], pSrc, len);
  70. }
  71. pending_head = (pending_head + len) & (SZ_BUFFER-1);
  72. added += len;
  73. }
  74. // -----------------------------------------------------------------------------
  75. // Implement dequeing (a 16 byte packet)
  76. void FwUpload::dequeue(uint8_t *pDst, uint8_t len)
  77. {
  78. if (len == 0 || len > pending_length()) {
  79. return; // Safety check for underflow error
  80. }
  81. if (pending_tail + len > SZ_BUFFER) {
  82. uint8_t n = SZ_BUFFER-pending_tail;
  83. memcpy(pDst, &pending_data[pending_tail], n);
  84. memcpy(pDst+n, &pending_data[0], len-n);
  85. } else {
  86. memcpy(pDst, &pending_data[pending_tail], len);
  87. }
  88. pending_tail = (pending_tail + len) & (SZ_BUFFER-1);
  89. sent += len;
  90. }
  91. // -----------------------------------------------------------------------------
  92. /*
  93. constructor
  94. */
  95. AP_Radio_beken::AP_Radio_beken(AP_Radio &_radio) :
  96. AP_Radio_backend(_radio),
  97. beken(hal.spi->get_device("beken")) // trace this later - its on libraries/AP_HAL_ChibiOS/SPIDevice.cpp:92
  98. {
  99. // link to instance for irq_trampoline
  100. // (temporary) go into test mode
  101. radio_singleton = this;
  102. beken.fcc.fcc_mode = 0;
  103. beken.fcc.channel = 23;
  104. beken.fcc.power = 7+1; // Full power
  105. }
  106. /*
  107. initialise radio
  108. */
  109. bool AP_Radio_beken::init(void)
  110. {
  111. if (_irq_handler_ctx != nullptr) {
  112. AP_HAL::panic("AP_Radio_beken: double instantiation of irq_handler\n");
  113. }
  114. chVTObjectInit(&timeout_vt);
  115. _irq_handler_ctx = chThdCreateFromHeap(NULL,
  116. THD_WORKING_AREA_SIZE(2048),
  117. "radio_bk2425",
  118. TIMEOUT_PRIORITY, /* Initial priority. */
  119. irq_handler_thd, /* Thread function. */
  120. NULL); /* Thread parameter. */
  121. return reset();
  122. }
  123. /*
  124. reset radio
  125. */
  126. bool AP_Radio_beken::reset(void)
  127. {
  128. if (!beken.lock_bus()) {
  129. return false;
  130. }
  131. radio_init();
  132. beken.unlock_bus();
  133. return true;
  134. }
  135. /*
  136. return statistics structure from radio
  137. */
  138. const AP_Radio::stats &AP_Radio_beken::get_stats(void)
  139. {
  140. return stats;
  141. }
  142. /*
  143. read one pwm channel from radio
  144. */
  145. uint16_t AP_Radio_beken::read(uint8_t chan)
  146. {
  147. if (chan >= BEKEN_MAX_CHANNELS) {
  148. return 0;
  149. }
  150. if (!valid_connection) {
  151. return (chan < 4) ? 1500u : 0u;
  152. }
  153. return pwm_channels[chan];
  154. }
  155. /*
  156. update status - called from main thread
  157. */
  158. void AP_Radio_beken::update(void)
  159. {
  160. check_fw_ack();
  161. }
  162. /*
  163. return number of active channels, and updates the data
  164. */
  165. uint8_t AP_Radio_beken::num_channels(void)
  166. {
  167. uint32_t now = AP_HAL::millis();
  168. uint8_t chan = get_rssi_chan();
  169. if ((chan > 0) && ((chan-1) < BEKEN_MAX_CHANNELS)) {
  170. uint8_t value = BK_RSSI_DEFAULT; // Fixed value that will not update (halfway in the RSSI range for Cypress chips, 0..31)
  171. if (beken.fcc.enable_cd) {
  172. if (beken.fcc.last_cd) {
  173. value += 4;
  174. } else {
  175. value -= 4;
  176. }
  177. }
  178. if (t_status.pps == 0) {
  179. value = BK_RSSI_MIN; // No packets = no RSSI
  180. }
  181. pwm_channels[chan-1] = value;
  182. chan_count = MAX(chan_count, chan);
  183. }
  184. chan = get_pps_chan();
  185. if ((chan > 0) && ((chan-1) < BEKEN_MAX_CHANNELS)) {
  186. pwm_channels[chan-1] = t_status.pps; // How many packets received per second
  187. chan_count = MAX(chan_count, chan);
  188. }
  189. chan = get_tx_rssi_chan();
  190. if ((chan > 0) && ((chan-1) < BEKEN_MAX_CHANNELS)) {
  191. pwm_channels[chan-1] = BK_RSSI_DEFAULT; // Fixed value that will not update (halfway in the RSSI range for Cypress chips, 0..31)
  192. chan_count = MAX(chan_count, chan);
  193. }
  194. chan = get_tx_pps_chan();
  195. if ((chan > 0) && ((chan-1) < BEKEN_MAX_CHANNELS)) {
  196. pwm_channels[chan-1] = tx_pps;
  197. chan_count = MAX(chan_count, chan);
  198. }
  199. // Every second, update the statistics
  200. if (now - last_pps_ms > 1000) {
  201. last_pps_ms = now;
  202. t_status.pps = stats.recv_packets - last_stats.recv_packets;
  203. last_stats = stats;
  204. if (stats.lost_packets != 0 || stats.timeouts != 0) {
  205. Debug(3,"lost=%lu timeouts=%lu\n", stats.lost_packets, stats.timeouts);
  206. }
  207. stats.lost_packets=0;
  208. stats.timeouts=0;
  209. if (have_tx_pps == 1) { // Have we had tx pps recently?
  210. tx_pps = 0;
  211. }
  212. if (have_tx_pps == 2) { // We have had it at some time
  213. have_tx_pps = 1; // Not recently
  214. }
  215. }
  216. return chan_count;
  217. }
  218. /*
  219. return time of last receive in microseconds
  220. */
  221. uint32_t AP_Radio_beken::last_recv_us(void)
  222. {
  223. return synctm.packet_timer;
  224. }
  225. /*
  226. send len bytes as a single packet
  227. */
  228. bool AP_Radio_beken::send(const uint8_t *pkt, uint16_t len)
  229. {
  230. // disabled for now
  231. return false;
  232. }
  233. // Borrow the CRC32 algorithm from AP_HAL_SITL
  234. // Not exactly fast algorithm as it is bit based
  235. #define CRC32_POLYNOMIAL 0xEDB88320L
  236. static uint32_t CRC32Value(uint32_t icrc)
  237. {
  238. int i;
  239. uint32_t crc = icrc;
  240. for ( i = 8 ; i > 0; i-- ) {
  241. if ( crc & 1 ) {
  242. crc = ( crc >> 1 ) ^ CRC32_POLYNOMIAL;
  243. } else {
  244. crc >>= 1;
  245. }
  246. }
  247. return crc;
  248. }
  249. static uint32_t CalculateBlockCRC32(uint32_t length, const uint8_t *buffer, uint32_t crc)
  250. {
  251. while ( length-- != 0 ) {
  252. crc = ((crc >> 8) & 0x00FFFFFFL) ^ (CRC32Value(((uint32_t) crc ^ *buffer++) & 0xff));
  253. }
  254. return ( crc );
  255. }
  256. /*
  257. initialise the radio
  258. */
  259. void AP_Radio_beken::radio_init(void)
  260. {
  261. DebugPrintf(1, "radio_init\r\n");
  262. beken.SetRBank(1);
  263. uint8_t id = beken.ReadReg(BK2425_R1_WHOAMI); // id is now 99
  264. beken.SetRBank(0); // Reset to default register bank.
  265. if (id != BK_CHIP_ID_BK2425) {
  266. Debug(1, "bk2425: radio not found\n"); // We have to keep trying because it takes time to initialise
  267. return; // Failure
  268. }
  269. {
  270. uint8_t serialid[12];
  271. memcpy(serialid, (const void *)UDID_START, 12); // 0x1FFF7A10ul on STM32F412 (see Util::get_system_id)
  272. uint32_t drone_crc = CalculateBlockCRC32(12, serialid, 0xfffffffful);
  273. if ((drone_crc & 0xff) == 0) {
  274. ++drone_crc; // Ensure that the first byte (LSB) is non-zero for all drone CRC, for benefit of old (buggy) tx code.
  275. }
  276. myDroneId[0] = drone_crc;
  277. myDroneId[1] = drone_crc >> 8;
  278. myDroneId[2] = drone_crc >> 16;
  279. myDroneId[3] = drone_crc >> 24;
  280. DebugPrintf(1, "DroneCrc:%08x\r\n", drone_crc);
  281. }
  282. Debug(1, "beken: radio_init starting\n");
  283. beken.bkReady = 0;
  284. spd = beken.gTxSpeed;
  285. beken.SwitchToIdleMode();
  286. hal.scheduler->delay(100); // delay more than 50ms.
  287. // Initialise Beken registers
  288. beken.SetRBank(0);
  289. beken.InitBank0Registers(beken.gTxSpeed);
  290. beken.SetRBank(1);
  291. beken.InitBank1Registers(beken.gTxSpeed);
  292. hal.scheduler->delay(100); // delay more than 50ms.
  293. beken.SetRBank(0);
  294. beken.SwitchToRxMode(); // switch to RX mode
  295. beken.bkReady = 1;
  296. hal.scheduler->delay_microseconds(10*1000); // 10ms seconds delay
  297. // setup handler for rising edge of IRQ pin
  298. hal.gpio->attach_interrupt(HAL_GPIO_RADIO_IRQ, trigger_irq_radio_event, AP_HAL::GPIO::INTERRUPT_FALLING);
  299. if (load_bind_info()) { // See if we already have bound to the address of a tx
  300. Debug(3,"Loaded bind info\n");
  301. nextChannel(1);
  302. }
  303. beken.EnableCarrierDetect(true); // For autobinding
  304. isr_irq_time_us = isr_timeout_time_us = AP_HAL::micros();
  305. next_switch_us = isr_irq_time_us + 10000;
  306. chVTSet(&timeout_vt, chTimeMS2I(10), trigger_timeout_event, nullptr); // Initial timeout?
  307. if (3 <= get_debug_level()) {
  308. beken.DumpRegisters();
  309. }
  310. }
  311. // ----------------------------------------------------------------------------
  312. void AP_Radio_beken::trigger_irq_radio_event()
  313. {
  314. //we are called from ISR context
  315. // DEBUG2_HIGH();
  316. chSysLockFromISR();
  317. isr_irq_time_us = AP_HAL::micros();
  318. chEvtSignalI(_irq_handler_ctx, EVT_IRQ);
  319. chSysUnlockFromISR();
  320. // DEBUG2_LOW();
  321. }
  322. // ----------------------------------------------------------------------------
  323. void AP_Radio_beken::trigger_timeout_event(void *arg)
  324. {
  325. (void)arg;
  326. //we are called from ISR context
  327. // DEBUG2_HIGH();
  328. // DEBUG2_LOW();
  329. // DEBUG2_HIGH();
  330. isr_timeout_time_us = AP_HAL::micros();
  331. chSysLockFromISR();
  332. chEvtSignalI(_irq_handler_ctx, EVT_TIMEOUT);
  333. chSysUnlockFromISR();
  334. // DEBUG2_LOW();
  335. }
  336. // ----------------------------------------------------------------------------
  337. // The user has clicked on the "Start Bind" button on the web interface
  338. void AP_Radio_beken::start_recv_bind(void)
  339. {
  340. chan_count = 0;
  341. synctm.packet_timer = AP_HAL::micros();
  342. radio_singleton->bind_time_ms = AP_HAL::millis();
  343. chEvtSignal(_irq_handler_ctx, EVT_BIND);
  344. Debug(1,"Starting bind\n");
  345. }
  346. // ----------------------------------------------------------------------------
  347. // handle a data96 mavlink packet for fw upload
  348. void AP_Radio_beken::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
  349. {
  350. if (sem.take_nonblocking()) {
  351. fwupload.chan = chan;
  352. fwupload.need_ack = false;
  353. if (m.type == 43) {
  354. // sending a tune to play - for development testing
  355. Debug(4, "got tune data96 of len %u from chan %u\n", m.len, chan);
  356. fwupload.reset();
  357. fwupload.fw_type = TELEM_PLAY;
  358. fwupload.file_length = MIN(m.len, 90);
  359. fwupload.file_length_round = (fwupload.file_length + 1 + 0x0f) & ~0x0f; // Round up to multiple of 16 (with nul-terminator)
  360. fwupload.queue(&m.data[0], fwupload.file_length);
  361. if (fwupload.file_length_round > fwupload.file_length) {
  362. uint8_t pad[16] = {0};
  363. fwupload.queue(&pad[0], fwupload.file_length_round - fwupload.file_length);
  364. }
  365. } else { // m.type == 42
  366. // sending DFU
  367. uint32_t ofs=0;
  368. memcpy(&ofs, &m.data[0], 4); // Assumes the endianness of the data!
  369. Debug(4, "got data96 of len %u from chan %u at offset %u\n", m.len, chan, unsigned(ofs));
  370. if (ofs == 0) {
  371. fwupload.reset();
  372. // Typically file_length = 0x3906; file_length_round = 0x3980;
  373. fwupload.file_length = ((uint16_t(m.data[4]) << 8) | (m.data[5])) + 6; // Add the header to the length
  374. fwupload.file_length_round = (fwupload.file_length + 0x7f) & ~0x7f; // Round up to multiple of 128
  375. }
  376. if (ofs != fwupload.added) {
  377. fwupload.need_ack = true; // We want more data
  378. } else {
  379. // sending a chunk of firmware OTA upload
  380. fwupload.fw_type = TELEM_FW;
  381. fwupload.queue(&m.data[4], MIN(m.len-4, 92)); // This might fail if mavlink sends it too fast to me, in which case it will retry later
  382. }
  383. }
  384. sem.give();
  385. }
  386. }
  387. // ----------------------------------------------------------------------------
  388. // Update the telemetry status variable; can be called in irq thread
  389. // since the functions it calls are lightweight
  390. void AP_Radio_beken::update_SRT_telemetry(void)
  391. {
  392. t_status.flags = 0;
  393. t_status.flags |= AP_Notify::flags.gps_status >= 3?TELEM_FLAG_GPS_OK:0;
  394. t_status.flags |= AP_Notify::flags.pre_arm_check?TELEM_FLAG_ARM_OK:0;
  395. t_status.flags |= AP_Notify::flags.failsafe_battery?0:TELEM_FLAG_BATT_OK;
  396. t_status.flags |= hal.util->get_soft_armed()?TELEM_FLAG_ARMED:0;
  397. t_status.flags |= AP_Notify::flags.have_pos_abs?TELEM_FLAG_POS_OK:0;
  398. t_status.flags |= AP_Notify::flags.video_recording?TELEM_FLAG_VIDEO:0;
  399. t_status.flight_mode = AP_Notify::flags.flight_mode;
  400. t_status.tx_max = get_tx_max_power();
  401. t_status.note_adjust = get_tx_buzzer_adjust();
  402. }
  403. // ----------------------------------------------------------------------------
  404. // Update a radio control packet
  405. // Called from IRQ context.
  406. // Returns true for DFU or TUNE, false for telemetry
  407. bool AP_Radio_beken::UpdateTxData(void)
  408. {
  409. // send reboot command if appropriate
  410. fwupload.counter++;
  411. if ((fwupload.acked >= fwupload.file_length_round) &&
  412. (fwupload.fw_type == TELEM_FW) && // Not a tune request
  413. (fwupload.rx_ack) &&
  414. (fwupload.acked >= 0x1000)) { // Sanity check
  415. fwupload.rx_reboot = true;
  416. }
  417. if (fwupload.rx_reboot && // Sanity check
  418. ((fwupload.counter & 0x01) != 0) && // Avoid starvation of telemetry
  419. sem.take_nonblocking()) { // Is the other threads busy with fwupload data?
  420. fwupload.rx_ack = false;
  421. // Tell the Tx to reboot
  422. packetFormatDfu* tx = &beken.pktDataDfu;
  423. tx->packetType = BK_PKT_TYPE_DFU;
  424. uint16_t addr = 0x0002; // Command to reboot
  425. tx->address_lo = addr & 0xff;
  426. tx->address_hi = (addr >> 8);
  427. DebugPrintf(2, "reboot %u %u\r\n", fwupload.acked, fwupload.file_length_round);
  428. sem.give();
  429. return true;
  430. } else if ((fwupload.acked >= fwupload.file_length_round) &&
  431. (fwupload.fw_type == TELEM_PLAY) && // Atune request
  432. (fwupload.rx_ack) &&
  433. ((fwupload.counter & 0x01) != 0) && // Avoid starvation of telemetry
  434. (fwupload.acked > 0) && // Sanity check
  435. sem.take_nonblocking()) { // Is the other threads busy with fwupload data?
  436. fwupload.reset();
  437. // Tell the Tx the tune is complete
  438. packetFormatDfu* tx = &beken.pktDataDfu;
  439. tx->packetType = BK_PKT_TYPE_TUNE;
  440. uint16_t addr = 0x0004; // Command to finalise the tune
  441. tx->address_lo = addr & 0xff;
  442. tx->address_hi = (addr >> 8);
  443. sem.give();
  444. return true;
  445. }
  446. // send firmware update packet for 7/8 of packets if any data pending
  447. else if ((fwupload.added >= (fwupload.acked + SZ_DFU)) && // Do we have a new packet to upload?
  448. ((fwupload.counter & 0x07) != 0) && // Avoid starvation of telemetry
  449. sem.take_nonblocking()) { // Is the other threads busy with fwupload data?
  450. // Send DFU packet
  451. packetFormatDfu* tx = &beken.pktDataDfu;
  452. if (fwupload.sent > fwupload.acked) {
  453. // Resend the last tx packet until it is acknowledged
  454. DebugPrintf(4, "resend %u %u %u\r\n", fwupload.added, fwupload.sent, fwupload.acked);
  455. } else if (fwupload.pending_length() >= SZ_DFU) { // safety check
  456. // Send firmware update packet
  457. uint16_t addr = fwupload.sent;
  458. tx->address_lo = addr & 0xff;
  459. tx->address_hi = (addr >> 8);
  460. fwupload.dequeue(&tx->data[0], SZ_DFU); // (updated sent, pending_tail)
  461. DebugPrintf(4, "send %u %u %u\r\n", fwupload.added, fwupload.sent, fwupload.acked);
  462. if (fwupload.fw_type == TELEM_PLAY) {
  463. tx->packetType = BK_PKT_TYPE_TUNE;
  464. } else if (fwupload.fw_type == TELEM_FW) {
  465. tx->packetType = BK_PKT_TYPE_DFU;
  466. if (fwupload.free_length() > 96) {
  467. fwupload.need_ack = true; // Request a new mavlink packet
  468. }
  469. }
  470. }
  471. sem.give();
  472. return true;
  473. } else {
  474. // Send telemetry packet
  475. packetFormatTx* tx = &beken.pktDataTx;
  476. update_SRT_telemetry();
  477. tx->packetType = BK_PKT_TYPE_TELEMETRY; ///< The packet type
  478. tx->pps = t_status.pps;
  479. tx->flags = t_status.flags;
  480. tx->droneid[0] = myDroneId[0];
  481. tx->droneid[1] = myDroneId[1];
  482. tx->droneid[2] = myDroneId[2];
  483. tx->droneid[3] = myDroneId[3];
  484. tx->flight_mode = t_status.flight_mode;
  485. tx->wifi = t_status.wifi_chan + (24 * t_status.tx_max);
  486. tx->note_adjust = t_status.note_adjust;
  487. // CPM bodge - use "Radio Protocol>0" to mean "Adaptive Frequency hopping disabled"
  488. // This should move to a different parameter.
  489. // Also the thresholds for swapping should move to be parameters.
  490. if (get_protocol()) {
  491. tx->hopping = 0; // Adaptive frequency hopping disabled
  492. } else {
  493. tx->hopping = adaptive.hopping; // Tell the tx what we want to use
  494. }
  495. telem_send_count++;
  496. return false;
  497. }
  498. }
  499. // ----------------------------------------------------------------------------
  500. // When (most of) a 92 byte packet has been sent to the Tx, ask for another one
  501. // called from main thread
  502. void AP_Radio_beken::check_fw_ack(void)
  503. {
  504. if (fwupload.need_ack && sem.take_nonblocking()) {
  505. // ack the send of a DATA96 fw packet to TX
  506. if (fwupload.added < fwupload.file_length) {
  507. fwupload.need_ack = false;
  508. uint8_t data16[16] {};
  509. uint32_t ack_to = fwupload.added;
  510. memcpy(&data16[0], &ack_to, 4); // Assume endianness matches
  511. mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
  512. } else if (fwupload.added & 0x7f) { // Are we on a boundary
  513. // Pad out some bytes at the end
  514. uint8_t data16[16];
  515. memset(&data16[0], 0, sizeof(data16));
  516. if (fwupload.free_length() > 16) {
  517. fwupload.queue(&data16[0], 16-(fwupload.added & 15));
  518. }
  519. DebugPrintf(4, "Pad to %d\r\n", fwupload.added);
  520. } else if (fwupload.acked < fwupload.added) {
  521. // Keep sending to the tx until it is acked
  522. DebugPrintf(4, "PadResend %u %u %u\r\n", fwupload.added, fwupload.sent, fwupload.acked);
  523. } else {
  524. fwupload.need_ack = false; // All done
  525. DebugPrintf(3, "StopUpload\r\n");
  526. uint8_t data16[16] {};
  527. uint32_t ack_to = fwupload.file_length; // Finished
  528. memcpy(&data16[0], &ack_to, 4); // Assume endianness matches
  529. mavlink_msg_data16_send(fwupload.chan, 42, 4, data16);
  530. }
  531. sem.give();
  532. }
  533. }
  534. // ----------------------------------------------------------------------------
  535. /* support all 4 rc input modes by swapping channels. */
  536. void AP_Radio_beken::map_stick_mode(void)
  537. {
  538. switch (get_stick_mode()) {
  539. case 1: {
  540. // mode1 = swap throttle and pitch
  541. uint16_t tmp = pwm_channels[1];
  542. pwm_channels[1] = pwm_channels[2];
  543. pwm_channels[2] = tmp;
  544. break;
  545. }
  546. case 3: {
  547. // mode3 = swap throttle and pitch, swap roll and yaw
  548. uint16_t tmp = pwm_channels[1];
  549. pwm_channels[1] = pwm_channels[2];
  550. pwm_channels[2] = tmp;
  551. tmp = pwm_channels[0];
  552. pwm_channels[0] = pwm_channels[3];
  553. pwm_channels[3] = tmp;
  554. break;
  555. }
  556. case 4: {
  557. // mode4 = swap roll and yaw
  558. uint16_t tmp = pwm_channels[0];
  559. pwm_channels[0] = pwm_channels[3];
  560. pwm_channels[3] = tmp;
  561. break;
  562. }
  563. case 2:
  564. default:
  565. // nothing to do, transmitter is natively mode2
  566. break;
  567. }
  568. // reverse pitch input to match ArduPilot default
  569. pwm_channels[1] = 3000 - pwm_channels[1];
  570. }
  571. // ----------------------------------------------------------------------------
  572. // This is a valid manual/auto binding packet.
  573. // The type of binding is valid now, and it came with the right address.
  574. // Lets check to see if it wants to be for another drone though
  575. // Return 1 on double binding
  576. uint8_t AP_Radio_beken::ProcessBindPacket(const packetFormatRx * rx)
  577. {
  578. // Did the tx pick a drone yet?
  579. uint32_t did = ((uint32_t)rx->u.bind.droneid[0]) | ((uint32_t)rx->u.bind.droneid[1] << 8)
  580. | ((uint32_t)rx->u.bind.droneid[2] << 16) | ((uint32_t)rx->u.bind.droneid[3] << 24);
  581. uint32_t mid = ((uint32_t)myDroneId[0]) | ((uint32_t)myDroneId[1] << 8)
  582. | ((uint32_t)myDroneId[2] << 16) | ((uint32_t)myDroneId[3] << 24);
  583. if (did & 0xff) { // If the first byte is zero, the drone id is not set (compatibility with old tx code)
  584. // Is it me or someone else?
  585. if (did != mid) {
  586. // This tx is not for us!
  587. if (!valid_connection && !already_bound) {
  588. // Keep searching!
  589. Debug(1, "WrongDroneId: %08lx vs %08lx\n", did, mid);
  590. BadDroneId();
  591. return 1;
  592. }
  593. }
  594. }
  595. // Set the address on which we are receiving the control data
  596. syncch.SetChannel(rx->channel); // Can be factory test channels if wanted
  597. if (get_factory_test() == 0) { // Final check that we are not in factory mode
  598. adaptive.Invalidate();
  599. syncch.SetHopping(0, rx->u.bind.hopping);
  600. beken.SetAddresses(&rx->u.bind.bind_address[0]);
  601. Debug(1, " Bound to %x %x %x %x %x\r\n", rx->u.bind.bind_address[0],
  602. rx->u.bind.bind_address[1], rx->u.bind.bind_address[2],
  603. rx->u.bind.bind_address[3], rx->u.bind.bind_address[4]);
  604. save_bind_info(); // May take some time
  605. }
  606. return 0;
  607. }
  608. // ----------------------------------------------------------------------------
  609. // Handle receiving a packet (we are still in an interrupt!)
  610. // Return 1 if we want to stay on the current radio frequency instead of hopping (double binding)
  611. uint8_t AP_Radio_beken::ProcessPacket(const uint8_t* packet, uint8_t rxaddr)
  612. {
  613. uint8_t result = 0;
  614. const packetFormatRx * rx = (const packetFormatRx *) packet; // Interpret the packet data
  615. switch (rx->packetType) {
  616. case BK_PKT_TYPE_CTRL_FOUND:
  617. case BK_PKT_TYPE_CTRL_LOST:
  618. // We haz data
  619. if (rxaddr == 0) {
  620. syncch.SetChannelIfSafe(rx->channel);
  621. synctm.packet_timer = AP_HAL::micros(); // This is essential for letting the channels update
  622. if (!already_bound) {
  623. already_bound = true; // Do not autobind to a different tx unless we power off
  624. // test rssi beken.EnableCarrierDetect(false); // Save 1ma of power
  625. beken.WriteReg(BK_WRITE_REG|BK_EN_RXADDR, 0x01); // Ignore the binding channel, which might be from competing siren txs.
  626. }
  627. adaptive.Get(rx->channel); // Give the good news to the adaptive logic
  628. // Put the data into the control values (assuming mode2)
  629. pwm_channels[0] = 1000 + rx->u.ctrl.roll + (uint16_t(rx->u.ctrl.msb & 0xC0) << 2); // Roll
  630. pwm_channels[1] = 1000 + rx->u.ctrl.pitch + (uint16_t(rx->u.ctrl.msb & 0x30) << 4); // Pitch
  631. pwm_channels[2] = 1000 + rx->u.ctrl.throttle + (uint16_t(rx->u.ctrl.msb & 0x0C) << 6); // Throttle
  632. pwm_channels[3] = 1000 + rx->u.ctrl.yaw + (uint16_t(rx->u.ctrl.msb & 0x03) << 8); // Yaw
  633. pwm_channels[4] = 1000 + ((rx->u.ctrl.buttons_held & 0x07) >> 0) * 100; // SW1, SW2, SW3
  634. pwm_channels[5] = 1000 + ((rx->u.ctrl.buttons_held & 0x38) >> 3) * 100; // SW4, SW5, SW6
  635. // cope with mode1/mode2/mode3/mode4
  636. map_stick_mode();
  637. chan_count = MAX(chan_count, 7);
  638. switch (rx->u.ctrl.data_type) {
  639. case BK_INFO_FW_VER: break;
  640. case BK_INFO_DFU_RX: {
  641. uint16_t ofs = rx->u.ctrl.data_value_hi;
  642. ofs <<= 8;
  643. ofs |= rx->u.ctrl.data_value_lo;
  644. if (ofs == fwupload.acked + SZ_DFU) {
  645. fwupload.acked = ofs;
  646. }
  647. if ((ofs == fwupload.acked) && (ofs > 0)) {
  648. fwupload.rx_ack = true;
  649. }
  650. if ((ofs == 0) && fwupload.rx_reboot) {
  651. fwupload.reset();
  652. }
  653. }
  654. break;
  655. case BK_INFO_FW_CRC_LO:
  656. break;
  657. case BK_INFO_FW_CRC_HI:
  658. break;
  659. case BK_INFO_FW_YM:
  660. tx_date.firmware_year = rx->u.ctrl.data_value_hi;
  661. tx_date.firmware_month = rx->u.ctrl.data_value_lo;
  662. break;
  663. case BK_INFO_FW_DAY:
  664. tx_date.firmware_day = rx->u.ctrl.data_value_hi;
  665. break;
  666. case BK_INFO_MODEL:
  667. break;
  668. case BK_INFO_PPS:
  669. tx_pps = rx->u.ctrl.data_value_lo; // Remember pps from tx
  670. if (!have_tx_pps) {
  671. have_tx_pps = 2;
  672. if (tx_pps == 0) { // Has the tx not been receiving telemetry from someone else recently?
  673. valid_connection = true;
  674. } else {
  675. // the TX has received more telemetry packets in the last second
  676. // than we have ever sent. There must be another RX sending
  677. // telemetry packets. We will reset our mfg_id and go back waiting
  678. // for a new bind packet, hopefully with the right TX
  679. Debug(1, "Double-bind detected via PPS %d\n", (int) tx_pps);
  680. BadDroneId();
  681. result = 1;
  682. }
  683. } else {
  684. have_tx_pps = 2;
  685. }
  686. break;
  687. case BK_INFO_BATTERY:
  688. // "voltage from TX is in 0.025 volt units". Convert to 0.01 volt units for easier display
  689. // The CC2500 code (and this) actually assumes it is in 0.04 volt units, hence the tx scaling by 23/156 (38/256) instead of 60/256)
  690. // Which means a maximum value is 152 units representing 6.0v rather than 240 units representing 6.0v
  691. pwm_channels[6] = rx->u.ctrl.data_value_lo * 4;
  692. break;
  693. case BK_INFO_COUNTDOWN:
  694. if (get_factory_test() == 0) {
  695. if (rx->u.ctrl.data_value_lo) {
  696. syncch.SetCountdown(rx->u.ctrl.data_value_lo+1, rx->u.ctrl.data_value_hi);
  697. adaptive.Invalidate();
  698. DebugPrintf(2, "(%d) ", rx->u.ctrl.data_value_lo);
  699. }
  700. }
  701. break;
  702. case BK_INFO_HOPPING0:
  703. if (get_factory_test() == 0) {
  704. syncch.SetHopping(rx->u.ctrl.data_value_lo, rx->u.ctrl.data_value_hi);
  705. // DebugPrintf(2, "[%d] ", rx->u.ctrl.data_value_lo);
  706. }
  707. break;
  708. case BK_INFO_HOPPING1: // Ignored so far
  709. break;
  710. case BK_INFO_DRONEID0: // Does this Tx even want to talk to me?
  711. if (rx->u.ctrl.data_value_lo || rx->u.ctrl.data_value_hi) {
  712. if ((rx->u.ctrl.data_value_lo != myDroneId[0]) ||
  713. (rx->u.ctrl.data_value_hi != myDroneId[1])) {
  714. Debug(1, "Bad DroneID0 %02x %02x\n", rx->u.ctrl.data_value_lo, rx->u.ctrl.data_value_hi);
  715. BadDroneId(); // Bad drone id - disconnect from this tx
  716. result = 1;
  717. }
  718. }
  719. break;
  720. case BK_INFO_DRONEID1: // Does this Tx even want to talk to me?
  721. if (rx->u.ctrl.data_value_lo || rx->u.ctrl.data_value_hi) {
  722. if ((rx->u.ctrl.data_value_lo != myDroneId[2]) ||
  723. (rx->u.ctrl.data_value_hi != myDroneId[3])) {
  724. Debug(1, "Bad DroneID1 %02x %02x\n", rx->u.ctrl.data_value_lo, rx->u.ctrl.data_value_hi);
  725. BadDroneId(); // Bad drone id - disconnect from this tx
  726. result = 1;
  727. }
  728. }
  729. break;
  730. default:
  731. break;
  732. };
  733. }
  734. break;
  735. case BK_PKT_TYPE_BIND_AUTO:
  736. if (rxaddr == 1) {
  737. if (get_autobind_rssi() > BK_RSSI_DEFAULT) { // Have we disabled autobind using fake RSSI parameter?
  738. Debug(2, "X0");
  739. break;
  740. }
  741. if (get_autobind_time() == 0) { // Have we disabled autobind using zero time parameter?
  742. Debug(2, "X1");
  743. break;
  744. }
  745. if (already_bound) { // Do not auto-bind (i.e. to another tx) until we reboot.
  746. Debug(2, "X2");
  747. break;
  748. }
  749. uint32_t now = AP_HAL::millis();
  750. if (now < get_autobind_time() * 1000) { // Is this too soon from rebooting/powering up to autobind?
  751. Debug(2, "X3");
  752. break;
  753. }
  754. // Check the carrier detect to see if the drone is too far away to auto-bind
  755. if (!beken.CarrierDetect()) {
  756. Debug(2, "X4");
  757. break;
  758. }
  759. result = ProcessBindPacket(rx);
  760. }
  761. break;
  762. case BK_PKT_TYPE_BIND_MANUAL: // Sent by the tx for a few seconds after power-up when a button is held down
  763. if (rxaddr == 1) {
  764. if (bind_time_ms == 0) { // We have never receiving a binding click
  765. Debug(2, "X5");
  766. break; // Do not bind
  767. }
  768. if (already_bound) { // Do not manually-bind (i.e. to another tx) until we reboot.
  769. Debug(2, "X6");
  770. break;
  771. }
  772. // if (uint32_t(AP_HAL::millis() - bind_time_ms) > 1000ul * 60u) // Have we pressed the button to bind recently? One minute timeout
  773. // break; // Do not bind
  774. result = ProcessBindPacket(rx);
  775. }
  776. break;
  777. case BK_PKT_TYPE_TELEMETRY:
  778. case BK_PKT_TYPE_DFU:
  779. default:
  780. // This is one of our packets! Ignore it.
  781. break;
  782. }
  783. return result;
  784. }
  785. // ----------------------------------------------------------------------------
  786. // Prepare to send a FCC packet
  787. void AP_Radio_beken::UpdateFccScan(void)
  788. {
  789. // Support scan mode
  790. if (beken.fcc.scan_mode) {
  791. beken.fcc.scan_count++;
  792. if (beken.fcc.scan_count >= 200) {
  793. beken.fcc.scan_count = 0;
  794. beken.fcc.channel += 2; // Go up by 2Mhz
  795. if (beken.fcc.channel >= CHANNEL_FCC_HIGH) {
  796. beken.fcc.channel = CHANNEL_FCC_LOW;
  797. }
  798. }
  799. }
  800. }
  801. // ----------------------------------------------------------------------------
  802. // main IRQ handler
  803. void AP_Radio_beken::irq_handler(uint32_t when)
  804. {
  805. if (beken.fcc.fcc_mode) {
  806. // don't process interrupts in FCCTEST mode
  807. beken.WriteReg(BK_WRITE_REG | BK_STATUS,
  808. (BK_STATUS_RX_DR | BK_STATUS_TX_DS | BK_STATUS_MAX_RT)); // clear RX_DR or TX_DS or MAX_RT interrupt flag
  809. return;
  810. }
  811. // Determine which state fired the interrupt
  812. bool bNext = false;
  813. bool bRx = false;
  814. uint8_t bk_sta = beken.ReadStatus();
  815. if (bk_sta & BK_STATUS_TX_DS) {
  816. DEBUG1_LOW();
  817. DEBUG1_HIGH();
  818. DEBUG1_LOW();
  819. DEBUG1_HIGH();
  820. DEBUG1_LOW();
  821. DEBUG1_HIGH();
  822. // Packet was sent towards the Tx board
  823. synctm.tx_time_us = when;
  824. beken.SwitchToIdleMode();
  825. if (beken.fcc.disable_crc_mode && !beken.fcc.disable_crc) {
  826. beken.SetCrcMode(true);
  827. }
  828. bNext = bRx = true;
  829. }
  830. if (bk_sta & BK_STATUS_MAX_RT) {
  831. // We have had a "max retries" error
  832. }
  833. bool bReply = false;
  834. if (bk_sta & BK_STATUS_RX_DR) {
  835. DEBUG1_LOW();
  836. DEBUG1_HIGH();
  837. DEBUG1_LOW();
  838. DEBUG1_HIGH();
  839. // We have received a packet
  840. uint8_t rxstd = 0;
  841. // Which pipe (address) have we received this packet on?
  842. if ((bk_sta & BK_STATUS_RX_MASK) == BK_STATUS_RX_P_0) {
  843. rxstd = 0;
  844. } else if ((bk_sta & BK_STATUS_RX_MASK) == BK_STATUS_RX_P_1) {
  845. rxstd = 1;
  846. } else {
  847. stats.recv_errors++;
  848. }
  849. bNext = true;
  850. uint8_t len, fifo_sta;
  851. uint8_t packet[32];
  852. do {
  853. stats.recv_packets++;
  854. len = beken.ReadReg(BK_R_RX_PL_WID_CMD); // read received packet length in bytes
  855. if (len <= PACKET_LENGTH_RX_MAX) {
  856. bReply = true;
  857. synctm.Rx(when);
  858. // printf("R%d ", when - next_switch_us);
  859. next_switch_us = when + synctm.sync_time_us + 1500; // Switch channels if we miss the next packet
  860. // This includes short packets (e.g. where no telemetry was sent)
  861. beken.ReadRegisterMulti(BK_RD_RX_PLOAD, packet, len); // read receive payload from RX_FIFO buffer
  862. // DebugPrintf(3, "Packet %d(%d) %d %d %d %d %d %d %d %d ...\r\n", rxstd, len,
  863. // packet[0], packet[1], packet[2], packet[3], packet[4], packet[5], packet[6], packet[7]);
  864. } else { // Packet was too long
  865. beken.ReadRegisterMulti(BK_RD_RX_PLOAD, packet, 32); // read receive payload from RX_FIFO buffer
  866. beken.Strobe(BK_FLUSH_RX); // flush Rx
  867. }
  868. fifo_sta = beken.ReadReg(BK_FIFO_STATUS); // read register FIFO_STATUS's value
  869. } while (!(fifo_sta & BK_FIFO_STATUS_RX_EMPTY)); // while not empty
  870. beken.WriteReg(BK_WRITE_REG | BK_STATUS,
  871. (BK_STATUS_RX_DR | BK_STATUS_TX_DS | BK_STATUS_MAX_RT)); // clear RX_DR or TX_DS or MAX_RT interrupt flag
  872. if (1 == ProcessPacket(packet, rxstd)) {
  873. bNext = false; // Because double binding detected
  874. }
  875. if (beken.fcc.enable_cd) {
  876. beken.fcc.last_cd = beken.CarrierDetect(); // Detect if close or not
  877. } else {
  878. beken.fcc.last_cd = true; // Assumed to be close
  879. }
  880. }
  881. // Clear the bits
  882. beken.WriteReg((BK_WRITE_REG|BK_STATUS), (BK_STATUS_MAX_RT | BK_STATUS_TX_DS | BK_STATUS_RX_DR));
  883. if (bReply) {
  884. uint32_t now = AP_HAL::micros();
  885. uint32_t delta = chTimeUS2I(800 + next_switch_us - now); // Do not use US2ST since that will overflow 32 bits
  886. chSysLock();
  887. chVTResetI(&timeout_vt); // Stop the normal timeout
  888. chVTSetI(&timeout_vt, delta, trigger_timeout_event, nullptr); // Timeout after 7ms
  889. chSysUnlock();
  890. if (get_telem_enable() && have_tx_pps) { // Note that the user can disable telemetry, but the transmitter will be less functional in this case.
  891. bNext = bRx = false;
  892. // Send the telemetry reply to the controller
  893. beken.Strobe(BK_FLUSH_TX); // flush Tx
  894. beken.ClearAckOverflow();
  895. bool txDfu = UpdateTxData();
  896. if (txDfu) {
  897. beken.pktDataDfu.channel = syncch.channel;
  898. } else {
  899. beken.pktDataTx.channel = syncch.channel;
  900. }
  901. if (beken.fcc.disable_crc_mode) {
  902. // Only disable the CRC on reception, not transmission, so the connection remains.
  903. beken.SwitchToIdleMode();
  904. beken.SetCrcMode(false);
  905. }
  906. beken.SwitchToTxMode();
  907. DEBUG1_LOW();
  908. hal.scheduler->delay_microseconds(200); // delay to give the (remote) tx a chance to switch to receive mode
  909. DEBUG1_HIGH();
  910. if (txDfu) {
  911. beken.SendPacket(BK_W_TX_PAYLOAD_NOACK_CMD, (uint8_t *)&beken.pktDataDfu, PACKET_LENGTH_TX_DFU);
  912. } else {
  913. beken.SendPacket(BK_W_TX_PAYLOAD_NOACK_CMD, (uint8_t *)&beken.pktDataTx, PACKET_LENGTH_TX_TELEMETRY);
  914. }
  915. } else { // Try to still work when telemetry is disabled
  916. bNext = true;
  917. }
  918. }
  919. if (bNext) {
  920. nextChannel(1);
  921. }
  922. if (bRx) {
  923. beken.SwitchToRxMode(); // Prepare to receive next packet (on the next channel)
  924. }
  925. }
  926. // ----------------------------------------------------------------------------
  927. // handle timeout IRQ (called when we need to switch channels)
  928. void AP_Radio_beken::irq_timeout(uint32_t when)
  929. {
  930. DEBUG1_LOW();
  931. DEBUG1_HIGH();
  932. DEBUG1_LOW();
  933. DEBUG1_HIGH();
  934. DEBUG1_LOW();
  935. DEBUG1_HIGH();
  936. DEBUG1_LOW();
  937. DEBUG1_HIGH();
  938. DEBUG1_LOW();
  939. DEBUG1_HIGH();
  940. if (beken.bkReady) { // We are not reinitialising the chip in the main thread
  941. static uint8_t check_params_timer = 0;
  942. if (++check_params_timer >= 10) { // We don't need to test the parameter logic every ms.
  943. // Every 50ms get here
  944. bool bOldReady = beken.bkReady;
  945. beken.bkReady = false;
  946. check_params_timer = 0;
  947. // Set the transmission power
  948. uint8_t pwr = get_transmit_power(); // 1..8
  949. if (pwr != beken.fcc.power + 1) {
  950. if ((pwr > 0) && (pwr <= 8)) {
  951. beken.SwitchToIdleMode();
  952. beken.SetPower(pwr-1); // (this will set beken.fcc.power)
  953. }
  954. }
  955. // Set CRC mode
  956. uint8_t crc = get_disable_crc();
  957. if (crc != beken.fcc.disable_crc_mode) {
  958. beken.SwitchToIdleMode();
  959. beken.SetCrcMode(crc);
  960. beken.fcc.disable_crc_mode = crc;
  961. }
  962. // Do we need to change our factory test mode?
  963. uint8_t factory = get_factory_test();
  964. if (factory != beken.fcc.factory_mode) {
  965. beken.SwitchToIdleMode();
  966. // Set frequency
  967. syncch.channel = factory ? (factory-1) + CHANNEL_COUNT_LOGICAL*CHANNEL_NUM_TABLES : 0;
  968. // Set address
  969. beken.SetFactoryMode(factory);
  970. }
  971. // Do we need to change our fcc test mode status?
  972. uint8_t fcc = get_fcc_test();
  973. if (fcc != beken.fcc.fcc_mode) {
  974. beken.Strobe(BK_FLUSH_TX);
  975. if (fcc == 0) { // Turn off fcc test mode
  976. if (beken.fcc.CW_mode) {
  977. beken.SwitchToIdleMode();
  978. beken.SetCwMode(false);
  979. }
  980. } else {
  981. if (fcc > 3) {
  982. if (!beken.fcc.CW_mode) {
  983. beken.SwitchToIdleMode();
  984. beken.SetCwMode(true);
  985. beken.DumpRegisters();
  986. }
  987. } else {
  988. if (beken.fcc.CW_mode) {
  989. beken.SwitchToIdleMode();
  990. beken.SetCwMode(false);
  991. }
  992. }
  993. switch (fcc) {
  994. case 1: case 4:
  995. default:
  996. beken.fcc.channel = CHANNEL_FCC_LOW;
  997. break;
  998. case 2: case 5:
  999. beken.fcc.channel = CHANNEL_FCC_MID;
  1000. break;
  1001. case 3: case 6:
  1002. beken.fcc.channel = CHANNEL_FCC_HIGH;
  1003. break;
  1004. };
  1005. }
  1006. beken.fcc.fcc_mode = fcc;
  1007. DebugPrintf(1, "\r\nFCC mode %d\r\n", fcc);
  1008. }
  1009. beken.bkReady = bOldReady;
  1010. }
  1011. // For fcc mode, just send packets on timeouts (every 5ms)
  1012. if (beken.fcc.fcc_mode) {
  1013. beken.SwitchToTxMode();
  1014. beken.ClearAckOverflow();
  1015. UpdateFccScan();
  1016. beken.SetChannel(beken.fcc.channel);
  1017. UpdateTxData();
  1018. beken.pktDataTx.channel = 0;
  1019. if (!beken.fcc.CW_mode) {
  1020. beken.SendPacket(BK_WR_TX_PLOAD, (uint8_t *)&beken.pktDataTx, PACKET_LENGTH_TX_TELEMETRY);
  1021. }
  1022. } else {
  1023. // Normal modes - we have timed out for channel hopping
  1024. int32_t d = synctm.sync_time_us; // Time between packets, e.g. 5100 us
  1025. uint32_t dt = when - synctm.rx_time_us;
  1026. if (dt > 50*d) { // We have lost sync (missed 50 packets) so slow down the channel hopping until we resync
  1027. d *= 5; // 3 or 5 are relatively prime to the table size of 16.
  1028. DebugPrintf(2, "C");
  1029. if (dt > 120*d) { // We have missed 3 seconds - try the safe WiFi table
  1030. DebugPrintf(2, "S");
  1031. syncch.SafeTable();
  1032. }
  1033. } else {
  1034. // DebugPrintf(2, "c%d ", AP_HAL::micros() - next_switch_us);
  1035. DebugPrintf(2, "c");
  1036. adaptive.Miss(syncch.channel);
  1037. }
  1038. {
  1039. uint8_t fifo_sta = radio_singleton->beken.ReadReg(BK_FIFO_STATUS); // read register FIFO_STATUS's value
  1040. if (!(fifo_sta & BK_FIFO_STATUS_RX_EMPTY)) { // while not empty
  1041. DEBUG1_LOW();
  1042. DEBUG1_HIGH();
  1043. DebugPrintf(2, "#"); // We have received a packet, but the interrupt was not triggered!
  1044. radio_singleton->irq_handler(next_switch_us); // Use this broken time
  1045. DEBUG1_LOW();
  1046. DEBUG1_HIGH();
  1047. } else {
  1048. next_switch_us += d; // Switch channels if we miss the next packet
  1049. }
  1050. }
  1051. int32_t ss = int32_t(next_switch_us - when);
  1052. if (ss < 1000) { // Not enough time
  1053. next_switch_us = when + d; // Switch channels if we miss the next packet
  1054. DebugPrintf(2, "j");
  1055. }
  1056. beken.SwitchToIdleMode();
  1057. nextChannel(1); // Switch to the next channel
  1058. beken.SwitchToRxMode();
  1059. beken.ClearAckOverflow();
  1060. }
  1061. }
  1062. // Ask for another timeout
  1063. uint32_t now = AP_HAL::micros();
  1064. if (int32_t(next_switch_us - when) < 300) { // Too late for that one
  1065. next_switch_us = now + synctm.sync_time_us;
  1066. }
  1067. if (int32_t(next_switch_us - now) < 250) { // Too late for this one
  1068. next_switch_us = now + synctm.sync_time_us;
  1069. }
  1070. uint32_t delta = chTimeUS2I(next_switch_us - now); // Do not use US2ST since that will overflow 32 bits.
  1071. chSysLock();
  1072. chVTSetI(&timeout_vt, delta, trigger_timeout_event, nullptr); // Timeout every 5 ms
  1073. chSysUnlock();
  1074. }
  1075. // ----------------------------------------------------------------------------
  1076. // Thread that supports Beken Radio work triggered by interrupts
  1077. // This is the only thread that should access the Beken radio chip via SPI.
  1078. void AP_Radio_beken::irq_handler_thd(void *arg)
  1079. {
  1080. (void) arg;
  1081. while (true) {
  1082. DEBUG1_LOW();
  1083. eventmask_t evt = chEvtWaitAny(ALL_EVENTS);
  1084. DEBUG1_HIGH();
  1085. if (_irq_handler_ctx != nullptr) { // Sanity check
  1086. _irq_handler_ctx->name = "RadioBeken"; // Only useful to be done once but here is done often
  1087. }
  1088. radio_singleton->beken.lock_bus();
  1089. switch (evt) {
  1090. case EVT_IRQ:
  1091. if (radio_singleton->beken.fcc.fcc_mode != 0) {
  1092. DebugPrintf(3, "IRQ FCC\n");
  1093. }
  1094. radio_singleton->irq_handler(isr_irq_time_us);
  1095. break;
  1096. case EVT_TIMEOUT:
  1097. radio_singleton->irq_timeout(isr_timeout_time_us);
  1098. break;
  1099. case EVT_BIND: // The user has clicked on the "Start Bind" button on the web interface
  1100. DebugPrintf(2, "\r\nBtnStartBind\r\n");
  1101. break;
  1102. default:
  1103. break;
  1104. }
  1105. radio_singleton->beken.unlock_bus();
  1106. }
  1107. }
  1108. void AP_Radio_beken::setChannel(uint8_t channel)
  1109. {
  1110. beken.SetChannel(channel);
  1111. }
  1112. const uint8_t bindHopData[256] = {
  1113. #if 0 // Support single frequency mode (no channel hopping)
  1114. // Normal frequencies
  1115. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Normal
  1116. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 1,2,3,4,5
  1117. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 6
  1118. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 7
  1119. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 8
  1120. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 9,10,11
  1121. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Test mode channels
  1122. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Reserved
  1123. // Alternative frequencies
  1124. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Normal
  1125. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 1,2,3,4,5
  1126. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 6
  1127. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 7
  1128. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 8
  1129. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Wifi channel 9,10,11
  1130. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Test mode channels
  1131. 23,23,23,23,23,23,23,23,23,23,23,23,23,23,23,23, // Reserved
  1132. #else // Frequency hopping
  1133. // Normal frequencies
  1134. 47,21,31,52,36,13,72,41, 69,56,16,26,61,10,45,66, // Normal
  1135. 57,62,67,72,58,63,68,59, 64,69,60,65,70,61,66,71, // Wifi channel 1,2,3,4,5 (2457..2472MHz)
  1136. 62,10,67,72,63,68,11,64, 69,60,65,70,12,61,66,71, // Wifi channel 6
  1137. 10,67,11,72,12,68,13,69, 14,65,15,70,16,66,17,71, // Wifi channel 7
  1138. 10,70,15,20,14,71,16,21, 12,17,22,72,13,18,11,19, // Wifi channel 8
  1139. 10,15,20,25,11,16,21,12, 17,22,13,18,23,14,19,24, // Wifi channel 9,10,11
  1140. 46,41,31,52,36,13,72,69, 21,56,16,26,61,66,10,43, // Test mode channels
  1141. 46,41,31,52,36,13,72,69, 21,56,16,26,61,66,10,43, // Reserved
  1142. // Alternative frequencies
  1143. 17,11,63,19,67,44,43,38, 50,54,70,58,29,35,25,14, // Normal
  1144. 18,10,23,21,33,44,41,38, 52,45,47,25,30,35,49,14, // Wifi channel 1,2,3,4,5
  1145. 18,56,23,21,33,44,41,38, 52,45,47,25,30,35,49,14, // Wifi channel 6
  1146. 18,56,23,21,33,44,41,38, 52,45,47,25,30,35,49,61, // Wifi channel 7
  1147. 68,56,24,53,33,44,41,38, 28,45,47,65,30,35,49,61, // Wifi channel 8
  1148. 68,56,72,53,33,44,41,38, 28,45,47,65,30,35,49,61, // Wifi channel 9,10,11
  1149. 46,41,31,52,36,13,72,69, 21,56,16,26,61,66,10,43, // Test mode channels (as normal)
  1150. 46,41,31,52,36,13,72,69, 21,56,16,26,61,66,10,43, // Reserved (as normal)
  1151. #endif
  1152. };
  1153. void AP_Radio_beken::nextChannel(uint8_t skip)
  1154. {
  1155. if (skip) {
  1156. syncch.NextChannel();
  1157. }
  1158. setChannel(bindHopData[syncch.channel]);
  1159. }
  1160. /*
  1161. save bind info
  1162. */
  1163. void AP_Radio_beken::save_bind_info(void)
  1164. {
  1165. // access to storage for bind information
  1166. StorageAccess bind_storage(StorageManager::StorageBindInfo);
  1167. struct bind_info info;
  1168. info.magic = bind_magic;
  1169. info.bindTxId[0] = beken.TX_Address[0];
  1170. info.bindTxId[1] = beken.TX_Address[1];
  1171. info.bindTxId[2] = beken.TX_Address[2];
  1172. info.bindTxId[3] = beken.TX_Address[3];
  1173. info.bindTxId[4] = beken.TX_Address[4];
  1174. bind_storage.write_block(0, &info, sizeof(info));
  1175. }
  1176. /*
  1177. load bind info
  1178. */
  1179. bool AP_Radio_beken::load_bind_info(void)
  1180. {
  1181. // access to storage for bind information
  1182. StorageAccess bind_storage(StorageManager::StorageBindInfo);
  1183. struct bind_info info;
  1184. if (!bind_storage.read_block(&info, 0, sizeof(info)) || info.magic != bind_magic) {
  1185. return false;
  1186. }
  1187. beken.SetAddresses(&info.bindTxId[0]);
  1188. return true;
  1189. }
  1190. // ----------------------------------------------------------------------------
  1191. void AP_Radio_beken::BadDroneId(void)
  1192. {
  1193. if (stats.recv_packets >= 1000) { // We are already chatting to this TX for some time.
  1194. return; // Do not disconnect from it.
  1195. }
  1196. // clear the current bind information
  1197. valid_connection = false;
  1198. // with luck we will connect to another tx
  1199. beken.SwitchToIdleMode();
  1200. beken.SetFactoryMode(0); // Reset the tx address
  1201. adaptive.Invalidate();
  1202. syncch.SetHopping(0,0);
  1203. already_bound = false; // Not already solidly bound to a drone
  1204. stats.recv_packets = 0;
  1205. beken.WriteReg(BK_WRITE_REG|BK_EN_RXADDR, 0x02);
  1206. have_tx_pps = false;
  1207. }
  1208. // ----------------------------------------------------------------------------
  1209. // Which bits correspond to each channel within a table, for adaptive frequencies
  1210. static const uint8_t channel_bit_table[CHANNEL_COUNT_LOGICAL] = {
  1211. 0x01, 0, 0x02, 0, 0x04, 0, 0x08, 0,
  1212. 0x10, 0, 0x20, 0, 0x40, 0, 0x80, 0
  1213. };
  1214. // Step through the channels
  1215. void SyncChannel::NextChannel(void)
  1216. {
  1217. channel &= 0x7f;
  1218. if (channel >= CHANNEL_COUNT_LOGICAL*CHANNEL_NUM_TABLES) {
  1219. // We are in the factory test modes. Keep the channel as is.
  1220. } else {
  1221. if (countdown != countdown_invalid) {
  1222. if (--countdown == 0) {
  1223. channel = countdown_chan;
  1224. countdown = countdown_invalid;
  1225. hopping_current = hopping_wanted = 0;
  1226. return;
  1227. }
  1228. } else if (hopping_countdown != countdown_invalid) {
  1229. if (--hopping_countdown == 0) {
  1230. hopping_current = hopping_wanted;
  1231. hopping_countdown = countdown_invalid;
  1232. // printf("{Use %d} ", hopping_current);
  1233. }
  1234. }
  1235. uint8_t table = channel / CHANNEL_COUNT_LOGICAL;
  1236. channel = (channel + 1) % CHANNEL_COUNT_LOGICAL;
  1237. channel += table * CHANNEL_COUNT_LOGICAL;
  1238. // Support adaptive frequency hopping
  1239. if (hopping_current & channel_bit_table[channel % CHANNEL_COUNT_LOGICAL]) {
  1240. channel |= 0x80;
  1241. }
  1242. }
  1243. }
  1244. // If we have not received any packets for ages, try a WiFi table that covers all frequencies
  1245. void SyncChannel::SafeTable(void)
  1246. {
  1247. channel &= 0x7f;
  1248. if (channel >= CHANNEL_COUNT_LOGICAL*CHANNEL_NUM_TABLES) {
  1249. // We are in the factory test modes. Reset to default table.
  1250. channel = 0;
  1251. } else {
  1252. uint8_t table = channel / CHANNEL_COUNT_LOGICAL;
  1253. if ((table != CHANNEL_BASE_TABLE) && (table != CHANNEL_SAFE_TABLE)) { // Are we using a table that is high end or low end only?
  1254. channel %= CHANNEL_COUNT_LOGICAL;
  1255. channel += CHANNEL_SAFE_TABLE * CHANNEL_COUNT_LOGICAL;
  1256. }
  1257. }
  1258. }
  1259. // Check if valid channel index; we have received a packet describing the current channel index
  1260. void SyncChannel::SetChannelIfSafe(uint8_t chan)
  1261. {
  1262. if (channel != chan) {
  1263. DebugPrintf(2, "{{%d}} ", chan);
  1264. }
  1265. chan &= 0x7f; // Disregard hopping
  1266. if (chan >= CHANNEL_COUNT_LOGICAL*CHANNEL_NUM_TABLES) {
  1267. if (chan == lastchan) {
  1268. channel = chan; // Allow test mode channels if two in a row
  1269. } else {
  1270. chan = 0; // Disallow test mode tables unless followed by each other
  1271. }
  1272. lastchan = chan;
  1273. } else {
  1274. lastchan = 0;
  1275. }
  1276. channel = chan;
  1277. }
  1278. // We have received a packet on this channel
  1279. void SyncAdaptive::Get(uint8_t channel)
  1280. {
  1281. uint8_t f = bindHopData[channel];
  1282. rx[f]++;
  1283. }
  1284. enum { ADAPT_THRESHOLD = 50 }; // Missed packets threshold for adapting the hopping
  1285. // We have missed a packet on this channel. Consider adapting.
  1286. void SyncAdaptive::Miss(uint8_t channel)
  1287. {
  1288. uint8_t f1 = bindHopData[channel];
  1289. missed[f1]++;
  1290. uint8_t f2 = bindHopData[channel ^ 0x80];
  1291. int32_t delta1 = missed[f1] - rx[f1];
  1292. int32_t delta2 = missed[f2] - rx[f2];
  1293. if ((delta1 > ADAPT_THRESHOLD) && // Worse than 50% reception on this channel
  1294. (delta1 > delta2)) {
  1295. // Ok consider swapping this channel
  1296. uint8_t bit = channel_bit_table[channel % CHANNEL_COUNT_LOGICAL];
  1297. if (bit) { // Is an even packet
  1298. uint8_t oh = hopping;
  1299. if (channel & 0x80) { // Swap back from alternative
  1300. hopping &= ~bit;
  1301. } else { // Swap to alternative
  1302. hopping |= bit;
  1303. }
  1304. if (hopping != oh) { // Have we changed?
  1305. missed[f2] = rx[f2] = 0; // Reset the values
  1306. // printf("{%d->%d:%d} ", f1+2400, f2+2400, hopping);
  1307. }
  1308. }
  1309. }
  1310. }
  1311. #endif // HAL_RCINPUT_WITH_AP_RADIO