driver_bk2425.cpp 24 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698
  1. // --------------------------------------------------------------------
  2. // low level driver for the beken radio on SPI
  3. // --------------------------------------------------------------------
  4. #include "driver_bk2425.h"
  5. #if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
  6. #include <utility>
  7. #include <AP_HAL_ChibiOS/AP_HAL_ChibiOS.h>
  8. using namespace ChibiOS;
  9. //#pragma GCC optimize("O0")
  10. extern const AP_HAL::HAL& hal;
  11. // --------------------------------------------------------------------
  12. // Radio initialisation tables
  13. // --------------------------------------------------------------------
  14. #if (TX_SPEED==250)
  15. ITX_SPEED Radio_Beken::gTxSpeed = ITX_250;
  16. #elif (TX_SPEED==100)
  17. ITX_SPEED Radio_Beken::gTxSpeed = ITX_1000;
  18. #elif (TX_SPEED==2000)
  19. ITX_SPEED Radio_Beken::gTxSpeed = ITX_2000;
  20. #endif
  21. // --------------------------------------------------------------------
  22. static const uint8_t Bank1_RegTable[ITX_MAX][IREG_MAX][5]= {
  23. // (TX_SPEED == 250u) // [ITX_250]
  24. {
  25. { BK2425_R1_4, 0xf9,0x96,0x8a,0xdb }, // 0xDB8A96f9ul, // [IREG1_4] REG4 250kbps
  26. { BK2425_R1_5, 0x24,0x06,0x0f,0xb6 }, // 0xB60F0624ul, // [IREG1_5] REG5 250kbps
  27. PLL_SPEED, // [IREG1_12] REG12
  28. { BK2425_R1_13, 0x36,0xb4,0x80,0x00 }, // 0x36B48000ul, // [IREG1_13] REG13
  29. { BK2425_R1_4, 0xff,0x96,0x8a,0xdb }, // 0xDB8A96f9ul, // [IREG1_4A] REG4 250kbps
  30. },
  31. // (TX_SPEED == 1000u) [ITX_1000]
  32. {
  33. { BK2425_R1_4, 0xf9,0x96,0x82,0x1b }, // 0x1B8296f9ul, // [IREG1_4] REG4 1Mbps
  34. { BK2425_R1_5, 0x24,0x06,0x0f,0xa6 }, // 0xA60F0624ul, // [IREG1_5] REG5 1Mbps
  35. PLL_SPEED, // [IREG1_12] REG12
  36. { BK2425_R1_13, 0x36,0xb4,0x80,0x00 }, // 0x36B48000ul, // [IREG1_13] REG13
  37. { BK2425_R1_4, 0xff,0x96,0x82,0x1b }, // 0x1B8296f9ul, // [IREG1_4A] REG4 1Mbps
  38. },
  39. // (TX_SPEED == 2000u) [ITX_2000]
  40. {
  41. { BK2425_R1_4, 0xf9,0x96,0x82,0xdb }, // 0xdb8296f9ul, // [IREG1_4] REG4 2Mbps
  42. { BK2425_R1_5, 0x24,0x06,0x0f,0xb6 }, // 0xb60f0624ul, // [IREG1_5] REG5 2Mbps
  43. PLL_SPEED, // [IREG1_12] REG12
  44. { BK2425_R1_13, 0x36,0xb4,0x80,0x00 }, // 0x36B48000ul, // [IREG1_13] REG13
  45. { BK2425_R1_4, 0xff,0x96,0x82,0xdb }, // 0xdb8296f9ul, // [IREG1_4A] REG4 2Mbps
  46. },
  47. // (TX_SPEED == 0u) // [ITX_CARRIER]
  48. {
  49. { BK2425_R1_4, 0xf9,0x96,0x82,0x21 }, // 0xF9968221ul, // [IREG1_4] REG4 carrier
  50. { BK2425_R1_5, 0x24,0x06,0x0f,0xb6 }, // 0xB60F0624ul, // [IREG1_5] REG5 250kbps
  51. PLL_SPEED, // [IREG1_12] REG12
  52. { BK2425_R1_13, 0x36,0xb4,0x80,0x00 }, // 0x36B48000ul, // [IREG1_13] REG13
  53. { BK2425_R1_4, 0xff,0x96,0x82,0x21 }, // 0xDB8A96f9ul, // [IREG1_4A] REG4 250kbps
  54. }
  55. };
  56. // --------------------------------------------------------------------
  57. static const uint8_t Bank0_Reg6[ITX_MAX][2] = {
  58. {BK_RF_SETUP, 0x27}, // 250kbps (6) 0x27=250kbps
  59. {BK_RF_SETUP, 0x07}, // 1000kbps (6) 0x07=1Mbps, high gain, high txpower
  60. {BK_RF_SETUP, 0x2F}, // 2000kbps (6) 0x2F=2Mbps, high gain, high txpower
  61. {BK_RF_SETUP, 0x37}, // 250kbps (6) 0x10=carrier
  62. };
  63. // --------------------------------------------------------------------
  64. static const uint8_t Bank1_Reg14[]= {
  65. 0x41,0x20,0x08,0x04,0x81,0x20,0xcf,0xF7,0xfe,0xff,0xff
  66. };
  67. // --------------------------------------------------------------------
  68. // Bank0 register initialization value
  69. static const uint8_t Bank0_Reg[][2]= {
  70. #if 0
  71. {BK_CONFIG, BK_CONFIG_PWR_UP | BK_CONFIG_PRIM_RX }, // (0) 0x0F=Rx, PowerUp, no crc, all interrupts enabled
  72. {BK_EN_AA, 0x00}, // (1) 0x00=No auto acknowledge packets on all 6 data pipes (0..5)
  73. {BK_EN_RXADDR, 0x02}, // (2) 0x01=1 or 2 out of 6 data pipes enabled (pairing heartbeat and my tx)
  74. {BK_SETUP_AW, 0x03}, // (3) 0x01=3 byte address width
  75. #else
  76. {BK_CONFIG, BK_CONFIG_EN_CRC | BK_CONFIG_CRCO | BK_CONFIG_PWR_UP | BK_CONFIG_PRIM_RX }, // (0) 0x0F=Rx, PowerUp, crc16, all interrupts enabled
  77. {BK_EN_AA, 0x00}, // (1) 0x00=No auto acknowledge packets on all 6 data pipes (0..5)
  78. {BK_EN_RXADDR, 0x03}, // (2) 0x01=1 or 2 out of 6 data pipes enabled (pairing heartbeat and my tx)
  79. {BK_SETUP_AW, 0x03}, // (3) 0x03=5 byte address width
  80. #endif
  81. {BK_SETUP_RETR, 0x00}, // (4) 0x00=No retransmissions
  82. {BK_RF_CH, 0x17}, // (5) 0x17=2423Mhz default frequency
  83. // Comment in Beken code says that 0x0F or 0x2F=2Mbps; 0x07=1Mbps; 0x27=250Kbps
  84. #if (TX_SPEED == 2000)
  85. {BK_RF_SETUP, 0x2F}, // (6) 0x2F=2Mbps, high gain, high txpower
  86. #elif (TX_SPEED == 1000)
  87. {BK_RF_SETUP, 0x07}, // (6) 0x07=1Mbps, high gain, high txpower
  88. #elif (TX_SPEED == 250)
  89. {BK_RF_SETUP, 0x27}, // (6) 0x27=250kbps
  90. //{BK_RF_SETUP, 0x21}, // (6) 0x27=250kbps, lowest txpower
  91. #endif
  92. {BK_STATUS, 0x07}, // (7) 7=no effect
  93. {BK_OBSERVE_TX, 0x00}, // (8) (no effect)
  94. {BK_CD, 0x00}, // (9) Carrier detect (no effect)
  95. // (10) = 5 byte register
  96. // (11) = 5 byte register
  97. {BK_RX_ADDR_P2, 0xc3}, // (12) rx address for data pipe 2
  98. {BK_RX_ADDR_P3, 0xc4}, // (13) rx address for data pipe 3
  99. {BK_RX_ADDR_P4, 0xc5}, // (14) rx address for data pipe 4
  100. {BK_RX_ADDR_P5, 0xc6}, // (15) rx address for data pipe 5
  101. // (16) = 5 byte register
  102. {BK_RX_PW_P0, PACKET_LENGTH_RX_CTRL}, // (17) size of rx data pipe 0
  103. {BK_RX_PW_P1, PACKET_LENGTH_RX_BIND}, // (18) size of rx data pipe 1
  104. {BK_RX_PW_P2, 0x20}, // (19) size of rx data pipe 2
  105. {BK_RX_PW_P3, 0x20}, // (20) size of rx data pipe 3
  106. {BK_RX_PW_P4, 0x20}, // (21) size of rx data pipe 4
  107. {BK_RX_PW_P5, 0x20}, // (22) size of rx data pipe 5
  108. {BK_FIFO_STATUS,0x00}, // (23) fifo status
  109. // (24,25,26,27)
  110. {BK_DYNPD, 0x3F}, // (28) 0x3f=enable dynamic payload length for all 6 data pipes
  111. {BK_FEATURE, BK_FEATURE_EN_DPL | BK_FEATURE_EN_ACK_PAY | BK_FEATURE_EN_DYN_ACK } // (29) 7=enable ack, no ack, dynamic payload length
  112. };
  113. // ----------------------------------------------------------------------------
  114. const uint8_t RegPower[8][2] = {
  115. { OUTPUT_POWER_REG4_0, OUTPUT_POWER_REG6_0 },
  116. { OUTPUT_POWER_REG4_1, OUTPUT_POWER_REG6_1 },
  117. { OUTPUT_POWER_REG4_2, OUTPUT_POWER_REG6_2 },
  118. { OUTPUT_POWER_REG4_3, OUTPUT_POWER_REG6_3 },
  119. { OUTPUT_POWER_REG4_4, OUTPUT_POWER_REG6_4 },
  120. { OUTPUT_POWER_REG4_5, OUTPUT_POWER_REG6_5 },
  121. { OUTPUT_POWER_REG4_6, OUTPUT_POWER_REG6_6 },
  122. { OUTPUT_POWER_REG4_7, OUTPUT_POWER_REG6_7 },
  123. };
  124. // --------------------------------------------------------------------
  125. // Generic functions
  126. // --------------------------------------------------------------------
  127. // --------------------------------------------------------------------
  128. // constructor
  129. Radio_Beken::Radio_Beken(AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev) :
  130. dev(std::move(_dev))
  131. {
  132. ResetAddress();
  133. }
  134. // --------------------------------------------------------------------
  135. // Use the default addresses
  136. void Radio_Beken::ResetAddress(void)
  137. {
  138. // Set the default address
  139. TX_Address[0] = 0x33;
  140. TX_Address[1] = RX0_Address[1] = 0x00;
  141. TX_Address[2] = RX0_Address[2] = 0x59;
  142. TX_Address[3] = RX0_Address[3] = 0x00;
  143. TX_Address[4] = RX0_Address[4] = 0x00;
  144. RX0_Address[0] = 0x31;
  145. RX1_Address[0] = 0x32;
  146. RX1_Address[1] = 0x99;
  147. RX1_Address[2] = 0x59;
  148. RX1_Address[3] = 0xC6;
  149. RX1_Address[4] = 0x2D;
  150. }
  151. // --------------------------------------------------------------------
  152. // Raw SPI access functions
  153. // --------------------------------------------------------------------
  154. // --------------------------------------------------------------------
  155. void Radio_Beken::ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t len)
  156. {
  157. uint8_t tx[len+1];
  158. uint8_t rx[len+1];
  159. memset(tx, 0, len+1);
  160. memset(rx, 0, len+1);
  161. tx[0] = address;
  162. DEBUG2_HIGH();
  163. (void)dev->transfer_fullduplex(tx, rx, len+1);
  164. DEBUG2_LOW();
  165. memcpy(data, &rx[1], len);
  166. }
  167. // --------------------------------------------------------------------
  168. void Radio_Beken::WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t len)
  169. {
  170. uint8_t tx[len+1];
  171. uint8_t rx[len+1];
  172. memset(rx, 0, len+1);
  173. tx[0] = address;
  174. memcpy(&tx[1], data, len);
  175. DEBUG2_HIGH();
  176. (void)dev->transfer_fullduplex(tx, rx, len+1);
  177. DEBUG2_LOW();
  178. }
  179. // --------------------------------------------------------------------
  180. // Low-level Beken functions
  181. // --------------------------------------------------------------------
  182. // --------------------------------------------------------------------
  183. uint8_t Radio_Beken::ReadStatus(void)
  184. {
  185. uint8_t tx = BK_NOP;
  186. uint8_t rx = 0;
  187. DEBUG2_HIGH();
  188. (void)dev->transfer_fullduplex(&tx, &rx, 1);
  189. DEBUG2_LOW();
  190. return rx; // Status
  191. }
  192. // --------------------------------------------------------------------
  193. uint8_t Radio_Beken::ReadReg(uint8_t reg)
  194. {
  195. uint8_t tx[2];
  196. uint8_t rx[2];
  197. memset(tx, 0, 2);
  198. memset(rx, 0, 2);
  199. tx[0] = reg | BK_READ_REG;
  200. DEBUG2_HIGH();
  201. (void)dev->transfer_fullduplex(tx, rx, 2);
  202. DEBUG2_LOW();
  203. return rx[1];
  204. }
  205. // --------------------------------------------------------------------
  206. uint8_t Radio_Beken::Strobe(uint8_t address)
  207. {
  208. uint8_t tx = address;
  209. uint8_t rx = 0;
  210. DEBUG2_HIGH();
  211. (void)dev->transfer_fullduplex(&tx, &rx, 1);
  212. DEBUG2_LOW();
  213. return rx; // Status
  214. }
  215. // --------------------------------------------------------------------
  216. // Set which register bank we are accessing
  217. void Radio_Beken::SetRBank(uint8_t bank) // 1:Bank1 0:Bank0
  218. {
  219. uint8_t lastbank = ReadStatus() & BK_STATUS_RBANK;
  220. if (!lastbank != !bank) {
  221. uint8_t tx[2];
  222. uint8_t rx[2];
  223. tx[0] = BK_ACTIVATE_CMD;
  224. tx[1] = 0x53;
  225. DEBUG2_HIGH();
  226. (void)dev->transfer_fullduplex(&tx[0], &rx[0], 2);
  227. DEBUG2_LOW();
  228. }
  229. }
  230. // --------------------------------------------------------------------
  231. void Radio_Beken::WriteReg(uint8_t address, uint8_t data)
  232. {
  233. uint8_t tx[2];
  234. uint8_t rx[2];
  235. memset(rx, 0, 2);
  236. tx[0] = address; // done by caller | BK_WRITE_REG;
  237. tx[1] = data;
  238. DEBUG2_HIGH();
  239. (void)dev->transfer_fullduplex(tx, rx, 2);
  240. DEBUG2_LOW();
  241. }
  242. // --------------------------------------------------------------------
  243. void Radio_Beken::WriteRegisterMultiBank1(uint8_t address, const uint8_t *data, uint8_t length)
  244. {
  245. SetRBank(1);
  246. WriteRegisterMulti(address, data, length);
  247. SetRBank(0);
  248. }
  249. // --------------------------------------------------------------------
  250. // High-level Beken functions
  251. // --------------------------------------------------------------------
  252. // --------------------------------------------------------------------
  253. // Set the radio transmission power of the beken
  254. // Prerequisite: We should be in idle mode before calling this function
  255. void Radio_Beken::SetPower(uint8_t power)
  256. {
  257. if (power > 7) {
  258. power = 7;
  259. }
  260. uint8_t oldready = bkReady;
  261. bkReady = 0;
  262. hal.scheduler->delay(100); // delay more than 50ms.
  263. SetRBank(1);
  264. {
  265. const uint8_t* p = &Bank1_RegTable[fcc.CW_mode ? ITX_CARRIER : gTxSpeed][IREG1_4][0];
  266. uint8_t idx = *p++;
  267. uint8_t buf[4];
  268. buf[0] = *p++;
  269. buf[1] = *p++;
  270. buf[2] = *p++;
  271. buf[3] = *p++;
  272. buf[0] &= ~0x38;
  273. buf[0] |= (RegPower[power][0] << 3); // Bits 27..29
  274. WriteRegisterMulti((BK_WRITE_REG|idx), buf, 4);
  275. }
  276. hal.scheduler->delay(100); // delay more than 50ms.
  277. SetRBank(0);
  278. hal.scheduler->delay(100);
  279. uint8_t setup = ReadReg(BK_RF_SETUP);
  280. setup &= ~(3 << 1);
  281. setup |= (RegPower[power][1] << 1); // Bits 1..2
  282. if (fcc.CW_mode) {
  283. setup |= 0x10;
  284. }
  285. WriteReg(BK_WRITE_REG|BK_RF_SETUP, setup);
  286. bkReady = oldready;
  287. fcc.power = power;
  288. }
  289. // --------------------------------------------------------------------
  290. // Set the physical radio transmission frequency of the beken
  291. void Radio_Beken::SetChannel(uint8_t freq)
  292. {
  293. lastTxChannel = freq;
  294. WriteReg(BK_WRITE_REG|BK_RF_CH, freq);
  295. }
  296. // --------------------------------------------------------------------
  297. // Set the radio transmission mode of the beken
  298. // Enable/disable the carrier sending mode
  299. // Prerequisite: We should be in idle mode before calling this function
  300. void Radio_Beken::SetCwMode(uint8_t cw)
  301. {
  302. uint8_t oldready = bkReady;
  303. bkReady = 0;
  304. hal.scheduler->delay(100); // delay more than 50ms.
  305. SetRBank(1);
  306. {
  307. const uint8_t* p = &Bank1_RegTable[cw ? ITX_CARRIER : gTxSpeed][IREG1_4][0];
  308. uint8_t idx = *p++;
  309. uint8_t buf[4];
  310. buf[0] = *p++;
  311. buf[1] = *p++;
  312. buf[2] = *p++;
  313. buf[3] = *p++;
  314. buf[0] &= ~0x38;
  315. buf[0] |= (RegPower[fcc.power & 7][0] << 3); // Bits 27..29
  316. WriteRegisterMulti((BK_WRITE_REG|idx), buf, 4);
  317. }
  318. hal.scheduler->delay(100); // delay more than 50ms.
  319. SetRBank(0);
  320. hal.scheduler->delay(100); // delay more than 50ms.
  321. uint8_t setup = ReadReg(BK_RF_SETUP);
  322. setup &= ~(3 << 1);
  323. setup |= (RegPower[fcc.power & 7][1] << 1); // Bits 1..2
  324. if (cw) {
  325. setup |= 0x10;
  326. }
  327. WriteReg((BK_WRITE_REG|BK_RF_SETUP), setup);
  328. fcc.CW_mode = cw != 0;
  329. bkReady = oldready;
  330. }
  331. // --------------------------------------------------------------------
  332. // Enable/disable the CRC receive mode
  333. // Prerequisite: We should be in idle mode before calling this function
  334. void Radio_Beken::SetCrcMode(uint8_t disable_crc)
  335. {
  336. uint8_t oldready = bkReady;
  337. bkReady = 0;
  338. uint8_t config = ReadReg(BK_CONFIG);
  339. if (disable_crc) {
  340. config &= ~(BK_CONFIG_EN_CRC | BK_CONFIG_CRCO); // Disable CRC
  341. } else {
  342. config |= (BK_CONFIG_EN_CRC | BK_CONFIG_CRCO); // Enable CRC
  343. }
  344. WriteReg((BK_WRITE_REG|BK_CONFIG), config);
  345. fcc.disable_crc = (disable_crc != 0);
  346. bkReady = oldready;
  347. }
  348. // ----------------------------------------------------------------------------
  349. // Enable the carrier detect feature: Bank1 Reg5 Bit 18
  350. void Radio_Beken::EnableCarrierDetect(bool bEnable)
  351. {
  352. if (bEnable == fcc.enable_cd) {
  353. return;
  354. }
  355. uint8_t oldready = bkReady;
  356. bkReady = 0;
  357. SetRBank(1);
  358. {
  359. const uint8_t* p = &Bank1_RegTable[gTxSpeed][IREG1_5][0];
  360. uint8_t idx = *p++;
  361. uint8_t buf[4];
  362. buf[0] = *p++;
  363. buf[1] = *p++;
  364. buf[2] = *p++;
  365. buf[3] = *p++;
  366. if (bEnable) {
  367. buf[1] &= ~0x04;
  368. }
  369. WriteRegisterMulti((BK_WRITE_REG|idx), buf, 4);
  370. }
  371. SetRBank(0);
  372. bkReady = oldready;
  373. fcc.enable_cd = bEnable;
  374. }
  375. // ----------------------------------------------------------------------------
  376. // Returns true if a carrier is detected
  377. bool Radio_Beken::CarrierDetect(void)
  378. {
  379. if (fcc.enable_cd) {
  380. if (ReadReg(BK_CD) & 0x01) {
  381. return true;
  382. }
  383. }
  384. return false;
  385. }
  386. // ----------------------------------------------------------------------------
  387. void Radio_Beken::SetFactoryMode(uint8_t factory)
  388. {
  389. uint8_t oldready = bkReady;
  390. bkReady = 0;
  391. // Set receive/transmit addresses
  392. if (factory) {
  393. // For factory modes, use fixed addresses
  394. TX_Address[0] = 0x35;
  395. TX_Address[1] = RX1_Address[1] = RX0_Address[1] = 0x99;
  396. TX_Address[2] = RX1_Address[2] = RX0_Address[2] = 0x59;
  397. TX_Address[3] = RX1_Address[3] = RX0_Address[3] = 0xC6;
  398. TX_Address[4] = RX1_Address[4] = RX0_Address[4] = factory;
  399. RX0_Address[0] = 0x34;
  400. RX1_Address[0] = 0x43;
  401. } else {
  402. // For normal modes, use the default addresses
  403. ResetAddress();
  404. }
  405. // Write the addresses to the registers
  406. WriteRegisterMulti((BK_WRITE_REG|BK_RX_ADDR_P0), RX0_Address, 5);
  407. WriteRegisterMulti((BK_WRITE_REG|BK_RX_ADDR_P1), RX1_Address, 5);
  408. WriteRegisterMulti((BK_WRITE_REG|BK_TX_ADDR), TX_Address, 5);
  409. WriteReg(BK_WRITE_REG|BK_EN_RXADDR, 0x03);
  410. // Frequency is set by the caller
  411. fcc.factory_mode = factory;
  412. bkReady = oldready;
  413. }
  414. // ----------------------------------------------------------------------------
  415. bool Radio_Beken::Reset(void)
  416. {
  417. //...
  418. hal.scheduler->delay_microseconds(1000);
  419. return 0;
  420. }
  421. // ----------------------------------------------------------------------------
  422. // Delay after changing chip-enable
  423. // This can be called from within the interrupt response thread
  424. void Radio_Beken::DelayCE(void)
  425. {
  426. DEBUG1_LOW();
  427. hal.scheduler->delay_microseconds(50);
  428. DEBUG1_HIGH();
  429. }
  430. // ----------------------------------------------------------------------------
  431. bool Radio_Beken::WasTxMode(void)
  432. {
  433. // Were we transmitting something?
  434. return bkMode == BKRADIO_TX;
  435. }
  436. // ----------------------------------------------------------------------------
  437. bool Radio_Beken::WasRxMode(void)
  438. {
  439. // Were we receiving something?
  440. return bkMode == BKRADIO_RX;
  441. }
  442. // ----------------------------------------------------------------------------
  443. // Switch to Rx mode
  444. void Radio_Beken::SwitchToRxMode(void)
  445. {
  446. uint8_t value;
  447. Strobe(BK_FLUSH_RX); // flush Rx
  448. value = ReadStatus(); // read register STATUS's value
  449. WriteReg(BK_WRITE_REG|BK_STATUS, value); // clear RX_DR or TX_DS or MAX_RT interrupt flag
  450. BEKEN_CE_LOW();
  451. DelayCE();
  452. value = ReadReg(BK_CONFIG); // read register CONFIG's value
  453. value |= BK_CONFIG_PRIM_RX; // set bit 0
  454. value |= BK_CONFIG_PWR_UP;
  455. WriteReg(BK_WRITE_REG | BK_CONFIG, value); // Set PWR_UP bit, enable CRC(2 length) & Prim:RX. RX_DR enabled..
  456. BEKEN_CE_HIGH();
  457. //BEKEN_PA_LOW(); // we dont have a PA on the RX side
  458. bkMode = BKRADIO_RX;
  459. }
  460. // ----------------------------------------------------------------------------
  461. // switch to Tx mode
  462. void Radio_Beken::SwitchToTxMode(void)
  463. {
  464. uint8_t value;
  465. Strobe(BK_FLUSH_TX); // flush half-sent Tx
  466. Strobe(BK_FLUSH_RX); // flush half-received rx
  467. // BEKEN_PA_HIGH();
  468. BEKEN_CE_LOW();
  469. DelayCE();
  470. value = ReadReg(BK_CONFIG); // read register CONFIG's value
  471. value &= ~BK_CONFIG_PRIM_RX; // Clear bit 0 (PTX)
  472. value |= BK_CONFIG_PWR_UP;
  473. WriteReg(BK_WRITE_REG | BK_CONFIG, value); // Set PWR_UP bit, enable CRC(2 length) & Prim:RX. RX_DR enabled.
  474. // BEKEN_CE_HIGH();
  475. bkMode = BKRADIO_TX;
  476. }
  477. // ----------------------------------------------------------------------------
  478. // switch to Idle mode
  479. void Radio_Beken::SwitchToIdleMode(void)
  480. {
  481. Strobe(BK_FLUSH_TX); // flush Tx
  482. Strobe(BK_FLUSH_RX); // flush Rx
  483. BEKEN_PA_LOW();
  484. BEKEN_CE_LOW();
  485. DelayCE();
  486. bkMode = BKRADIO_IDLE;
  487. }
  488. // ----------------------------------------------------------------------------
  489. // Switch to Sleep mode
  490. void Radio_Beken::SwitchToSleepMode(void)
  491. {
  492. uint8_t value;
  493. Strobe(BK_FLUSH_RX); // flush Rx
  494. Strobe(BK_FLUSH_TX); // flush Tx
  495. value = ReadStatus(); // read register STATUS's value
  496. WriteReg(BK_WRITE_REG|BK_STATUS, value); // clear RX_DR or TX_DS or MAX_RT interrupt flag
  497. BEKEN_PA_LOW();
  498. BEKEN_CE_LOW();
  499. DelayCE();
  500. value = ReadReg(BK_CONFIG); // read register CONFIG's value
  501. value |= BK_CONFIG_PRIM_RX; // Receive mode
  502. value &= ~BK_CONFIG_PWR_UP; // Power down
  503. WriteReg(BK_WRITE_REG | BK_CONFIG, value); // Clear PWR_UP bit, enable CRC(2 length) & Prim:RX. RX_DR enabled..
  504. // Stay low
  505. BEKEN_CE_LOW();
  506. bkMode = BKRADIO_SLEEP;
  507. }
  508. // ----------------------------------------------------------------------------
  509. void Radio_Beken::InitBank0Registers(ITX_SPEED spd)
  510. {
  511. int8_t i;
  512. //********************Write Bank0 register******************
  513. for (i=20; i >= 0; i--) { // From BK_FIFO_STATUS back to beginning of table
  514. uint8_t idx = Bank0_Reg[i][0];
  515. uint8_t value = Bank0_Reg[i][1];
  516. if (idx == BK_RF_SETUP) { // Adjust for speed
  517. value = Bank0_Reg6[spd][1];
  518. }
  519. WriteReg((BK_WRITE_REG|idx), value);
  520. }
  521. // Enable features
  522. i = ReadReg(BK_FEATURE);
  523. if (i == 0) { // i!=0 showed that chip has been actived. So do not active again (as that would toggle these features off again).
  524. WriteReg(BK_ACTIVATE_CMD,0x73); // Activate the BK_FEATURE register. (This command must NOT have BK_WRITE_REG set)
  525. }
  526. for (i = 22; i >= 21; i--) {
  527. WriteReg((BK_WRITE_REG|Bank0_Reg[i][0]),Bank0_Reg[i][1]);
  528. }
  529. // Set the various 5 byte addresses
  530. WriteRegisterMulti((BK_WRITE_REG|BK_RX_ADDR_P0),RX0_Address,5); // reg 10 - Rx0 addr
  531. WriteRegisterMulti((BK_WRITE_REG|BK_RX_ADDR_P1),RX1_Address,5); // REG 11 - Rx1 addr
  532. WriteRegisterMulti((BK_WRITE_REG|BK_TX_ADDR),TX_Address,5); // REG 16 - TX addr
  533. WriteReg(BK_WRITE_REG|BK_EN_RXADDR, 0x03);
  534. }
  535. // ----------------------------------------------------------------------------
  536. void Radio_Beken::InitBank1Registers(ITX_SPEED spd)
  537. {
  538. int16_t i;
  539. for (i = IREG1_4; i <= IREG1_13; i++) {
  540. const uint8_t* p = &Bank1_RegTable[spd][i][0];
  541. uint8_t idx = *p++;
  542. WriteRegisterMulti((BK_WRITE_REG|idx), p, 4);
  543. }
  544. WriteRegisterMulti((BK_WRITE_REG|BK2425_R1_14),&(Bank1_Reg14[0]),11);
  545. //toggle REG4<25,26>
  546. {
  547. const uint8_t* p = &Bank1_RegTable[spd][IREG1_4A][0];
  548. uint8_t idx = *p++;
  549. WriteRegisterMulti((BK_WRITE_REG|idx), p, 4);
  550. }
  551. {
  552. const uint8_t* p = &Bank1_RegTable[spd][IREG1_4][0];
  553. uint8_t idx = *p++;
  554. WriteRegisterMulti((BK_WRITE_REG|idx), p, 4);
  555. }
  556. }
  557. // ----------------------------------------------------------------------------
  558. // Set the rx and tx addresses
  559. void Radio_Beken::SetAddresses(const uint8_t* txaddr)
  560. {
  561. TX_Address[1] = RX0_Address[1] = txaddr[1];
  562. TX_Address[3] = RX0_Address[3] = txaddr[3];
  563. TX_Address[4] = RX0_Address[4] = txaddr[4];
  564. WriteRegisterMulti((BK_WRITE_REG|BK_RX_ADDR_P0), RX0_Address, 5);
  565. WriteRegisterMulti((BK_WRITE_REG|BK_TX_ADDR), TX_Address, 5);
  566. WriteReg(BK_WRITE_REG|BK_EN_RXADDR, 0x03);
  567. }
  568. // ----------------------------------------------------------------------------
  569. bool Radio_Beken::ClearAckOverflow(void)
  570. {
  571. uint8_t status = ReadStatus();
  572. if ((BK_STATUS_MAX_RT & status) == 0) {
  573. return false;
  574. } else {
  575. WriteReg((BK_WRITE_REG|BK_STATUS), BK_STATUS_MAX_RT);
  576. return true;
  577. }
  578. }
  579. // ----------------------------------------------------------------------------
  580. // Write a data packet
  581. bool Radio_Beken::SendPacket(uint8_t type, ///< WR_TX_PLOAD or W_TX_PAYLOAD_NOACK_CMD
  582. const uint8_t* pbuf, ///< a buffer pointer
  583. uint8_t len) ///< packet length in bytes
  584. {
  585. uint8_t fifo_sta = ReadReg(BK_FIFO_STATUS); // read register FIFO_STATUS's value
  586. bool returnValue = ClearAckOverflow();
  587. if (!(fifo_sta & BK_FIFO_STATUS_TX_FULL)) { // if not full, send data
  588. numTxPackets++;
  589. WriteRegisterMulti(type, pbuf, len); // Writes data to buffer A0,B0,A8
  590. BEKEN_CE_HIGH(); // Wait until FIFO has the data before sending it.
  591. }
  592. return returnValue;
  593. }
  594. // ----------------------------------------------------------------------------
  595. // For debugging - tell us the current beken register values (from bank 0)
  596. // This just prints it to the UART rather than to the console over WiFi
  597. void Radio_Beken::DumpRegisters(void)
  598. {
  599. uint8_t i;
  600. for (i = 0; i <= BK_FEATURE; ++i) {
  601. uint8_t len = 1;
  602. switch (i) {
  603. case 10: case 11: case 16: len = 5; break;
  604. case 24: case 25: case 26: case 27: len = 0; break;
  605. default: len = 1; break;
  606. };
  607. if (len == 1) {
  608. //printf("Bank0reg%d : %x\r\n", i, ReadReg(i));
  609. } else if (len == 5) {
  610. uint8_t data[5];
  611. ReadRegisterMulti(i, &data[0], len);
  612. //printf("Bank0reg%d : %x %x %x %x %x\r\n", i, data[0], data[1], data[2], data[3], data[4]);
  613. }
  614. }
  615. SetRBank(1);
  616. for (i = IREG1_4; i <= IREG1_13; ++i) {
  617. uint8_t len = 4;
  618. uint8_t data[4];
  619. ReadRegisterMulti(i, &data[0], len);
  620. //uint8_t idx = Bank1_RegTable[0][i][0];
  621. //printf("Bank1reg%d : %x %x %x %x\r\n", idx, data[0], data[1], data[2], data[3]);
  622. }
  623. SetRBank(0);
  624. }
  625. #endif // HAL_RCINPUT_WITH_AP_RADIO