driver_bk2425.h 19 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439
  1. //----------------------------------------------------------------------------------
  2. // low level driver for the Beken BK2425 radio on SPI
  3. // Note: Under ChiBios the knowledge of which pins are which is not in the driver.
  4. // But ultimately comes from hwdef.dat
  5. //----------------------------------------------------------------------------------
  6. #pragma once
  7. #include <AP_HAL/AP_HAL.h>
  8. #if defined(HAL_RCINPUT_WITH_AP_RADIO) && CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
  9. #define SUPPORT_BK_DEBUG_PINS 0 // 0=UART6 is for GPS, 1=UART6 is debug gpio
  10. #define TX_SPEED 250u // Default transmit speed in kilobits per second.
  11. /** Channel hopping parameters. Values are in MHz from 2400Mhz. */
  12. enum CHANNEL_MHZ_e {
  13. CHANNEL_MIN_PHYSICAL = 0, ///< Minimum physical channel that is possible
  14. CHANNEL_MAX_PHYSICAL = 83, ///< Maximum physical channel that is possible
  15. CHANNEL_FCC_LOW = 10, ///< Minimum physical channel that will pass the FCC tests
  16. CHANNEL_FCC_HIGH = 72, ///< Maximum physical channel that will pass the FCC tests
  17. CHANNEL_FCC_MID = 41, ///< A representative physical channel
  18. };
  19. enum {
  20. CHANNEL_COUNT_LOGICAL = 16, ///< The maximum number of entries in each frequency table
  21. CHANNEL_BASE_TABLE = 0, ///< The table used for non wifi boards
  22. CHANNEL_SAFE_TABLE = 3, ///< A table that will receive packets even if wrong
  23. CHANNEL_NUM_TABLES = 6, ///< The number of tables
  24. CHANNEL_COUNT_TEST = 16, ///< The number of test mode tables
  25. };
  26. // ----------------------------------------------------------------------------
  27. // Packet format definition
  28. // ----------------------------------------------------------------------------
  29. /** The type of packets being sent between controller and drone */
  30. enum BK_PKT_TYPE_E {
  31. BK_PKT_TYPE_INVALID = 0, ///< Invalid packet from empty packets or bad CRC
  32. BK_PKT_TYPE_CTRL_FOUND = 0x10, ///< (Tx->Drone) User control - known receiver
  33. BK_PKT_TYPE_CTRL_LOST = 0x11, ///< (Tx->Drone) User control - unknown receiver
  34. BK_PKT_TYPE_BIND_AUTO = 0x12, ///< (Tx->Drone) Tell drones this tx is broadcasting
  35. BK_PKT_TYPE_TELEMETRY = 0x13, ///< (Drone->Tx) Send telemetry to tx
  36. BK_PKT_TYPE_DFU = 0x14, ///< (Drone->Tx) Send new firmware to tx
  37. BK_PKT_TYPE_BIND_MANUAL = 0x15, ///< (Tx->Drone) Tell drones this tx is broadcasting
  38. BK_PKT_TYPE_TUNE = 0x16, ///< (Drone->Tx) Send musical tune to tx
  39. };
  40. typedef uint8_t BK_PKT_TYPE;
  41. /** A bitset of the buttons on this controller. */
  42. enum button_bits {
  43. BUTTON_NONE = 0x00, ///< No buttons are held
  44. BUTTON_RIGHT = 0x01, ///< SW1 = The right button (mode)
  45. BUTTON_LEFT = 0x02, ///< SW2 = The left button (launch/land)
  46. BUTTON_MIDDLE = 0x04, ///< SW3 = The middle button (GPS)
  47. BUTTON_LEFT_SHOULDER = 0x08, ///< SW4 = The left shoulder button (stunt)
  48. BUTTON_RIGHT_SHOULDER = 0x10, ///< SW5 = The right shoulder button (video)
  49. BUTTON_POWER = 0x20, ///< SW6 = The top button (POWER)
  50. };
  51. /** The type of info being sent in control packets */
  52. enum BK_INFO_TYPE_E {
  53. BK_INFO_MIN = 1,
  54. BK_INFO_FW_VER = 1,
  55. BK_INFO_DFU_RX = 2,
  56. BK_INFO_FW_CRC_LO = 3,
  57. BK_INFO_FW_CRC_HI = 4,
  58. BK_INFO_FW_YM = 5,
  59. BK_INFO_FW_DAY = 6,
  60. BK_INFO_MODEL = 7,
  61. BK_INFO_PPS = 8,
  62. BK_INFO_BATTERY = 9,
  63. BK_INFO_COUNTDOWN = 10,
  64. BK_INFO_HOPPING0 = 11,
  65. BK_INFO_HOPPING1 = 12,
  66. BK_INFO_DRONEID0 = 13,
  67. BK_INFO_DRONEID1 = 14,
  68. BK_INFO_MAX
  69. };
  70. typedef uint8_t BK_INFO_TYPE;
  71. /** Data for packets that are not droneid packets
  72. Onair order = little-endian */
  73. typedef struct packetDataDeviceCtrl_s {
  74. uint8_t roll; ///< 2: Low 8 bits of the roll joystick
  75. uint8_t pitch; ///< 3: Low 8 bits of the pitch joystick
  76. uint8_t throttle; ///< 4: Low 8 bits of the throttle joystick
  77. uint8_t yaw; ///< 5: Low 8 bits of the yaw joystick
  78. uint8_t msb; ///< 6: High 2 bits of roll (7..6), pitch (5..4), throttle (3..2), yaw (1..0)
  79. uint8_t buttons_held; ///< 7: The buttons
  80. uint8_t buttons_toggled; ///< 8: The buttons
  81. uint8_t data_type; ///< 9: Type of extra data being sent
  82. uint8_t data_value_lo; ///< 10: Value of extra data being sent
  83. uint8_t data_value_hi; ///< 11: Value of extra data being sent
  84. } packetDataDeviceCtrl;
  85. enum { SZ_ADDRESS = 5 }; ///< Size of address for transmission packets (40 bits)
  86. enum { SZ_CRC_GUID = 4 }; ///< Size of UUID for drone (32 bits)
  87. enum { SZ_DFU = 16 }; ///< Size of DFU packets
  88. /** Data for packets that are binding packets
  89. Onair order = little-endian */
  90. typedef struct packetDataDeviceBind_s {
  91. uint8_t bind_address[SZ_ADDRESS]; ///< The address being used by control packets
  92. uint8_t hopping; ///< The hopping table in use for this connection
  93. uint8_t droneid[SZ_CRC_GUID]; ///<
  94. } packetDataDeviceBind;
  95. /** Data structure for data packet transmitted from device (controller) to host (drone) */
  96. typedef struct packetDataDevice_s {
  97. BK_PKT_TYPE packetType; ///< 0: The packet type
  98. uint8_t channel; ///< 1: Next channel I will broadcast on
  99. union packetDataDevice_u { ///< The variant part of the packets
  100. packetDataDeviceCtrl ctrl; ///< Control packets
  101. packetDataDeviceBind bind; ///< Binding packets
  102. } u;
  103. } packetFormatRx;
  104. /** Data structure for data packet transmitted from host (drone) to device (controller) */
  105. typedef struct packetDataDrone_s {
  106. BK_PKT_TYPE packetType; ///< 0: The packet type
  107. uint8_t channel; ///< 1: Next channel I will broadcast on
  108. uint8_t pps; ///< 2: Packets per second the drone received
  109. uint8_t flags; ///< 3: Flags
  110. uint8_t droneid[SZ_CRC_GUID]; ///< 4...7: CRC of the drone
  111. uint8_t flight_mode; ///< 8:
  112. uint8_t wifi; ///< 9: Wifi channel + 24 * tx power.
  113. uint8_t note_adjust; ///< 10: note adjust for the tx buzzer (should this be sent so often?)
  114. uint8_t hopping; ///< 11: The adapative hopping byte we want to use
  115. } packetFormatTx;
  116. typedef struct packetDataDfu_s {
  117. BK_PKT_TYPE packetType; ///< 0: The packet type
  118. uint8_t channel; ///< 1: Next channel I will broadcast on
  119. uint8_t address_lo; ///< 2:
  120. uint8_t address_hi; ///< 3:
  121. uint8_t data[SZ_DFU]; ///< 4...19:
  122. } packetFormatDfu;
  123. // ----------------------------------------------------------------------------
  124. // BK2425 chip definition
  125. // ----------------------------------------------------------------------------
  126. //----------------------------------------------------------------------------------
  127. /** SPI register commands for the BK2425 and nrf24L01+ chips */
  128. typedef enum {
  129. // General commands
  130. BK_REG_MASK = 0x1F, // The range of registers that can be read and written
  131. BK_READ_REG = 0x00, // Define read command to register (0..1F)
  132. BK_WRITE_REG = 0x20, // Define write command to register (0..1F)
  133. BK_ACTIVATE_CMD = 0x50,
  134. BK_R_RX_PL_WID_CMD = 0x60,
  135. BK_RD_RX_PLOAD = 0x61, // Define RX payload register address
  136. BK_WR_TX_PLOAD = 0xA0, // Define TX payload register address
  137. BK_W_ACK_PAYLOAD_CMD = 0xA8, // (nrf: +pipe 0..7)
  138. BK_W_TX_PAYLOAD_NOACK_CMD = 0xB0,
  139. BK_FLUSH_TX = 0xE1, // Define flush TX register command
  140. BK_FLUSH_RX = 0xE2, // Define flush RX register command
  141. BK_REUSE_TX_PL = 0xE3, // Define reuse TX payload register command
  142. BK_NOP = 0xFF, // Define No Operation, might be used to read status register
  143. // BK2425 bank 0 register addresses
  144. BK_CONFIG = 0x00, // 'Config' register address
  145. BK_EN_AA = 0x01, // 'Enable Auto Acknowledgment' register address
  146. BK_EN_RXADDR = 0x02, // 'Enabled RX addresses' register address
  147. BK_SETUP_AW = 0x03, // 'Setup address width' register address
  148. BK_SETUP_RETR = 0x04, // 'Setup Auto. Retrans' register address
  149. BK_RF_CH = 0x05, // 'RF channel' register address
  150. BK_RF_SETUP = 0x06, // 'RF setup' register address
  151. BK_STATUS = 0x07, // 'Status' register address
  152. BK_OBSERVE_TX = 0x08, // 'Observe TX' register address (lost packets, retransmitted packets on this frequency)
  153. BK_CD = 0x09, // 'Carrier Detect' register address
  154. BK_RX_ADDR_P0 = 0x0A, // 'RX address pipe0' register address (5 bytes)
  155. BK_RX_ADDR_P1 = 0x0B, // 'RX address pipe1' register address (5 bytes)
  156. BK_RX_ADDR_P2 = 0x0C, // 'RX address pipe2' register address (1 byte)
  157. BK_RX_ADDR_P3 = 0x0D, // 'RX address pipe3' register address (1 byte)
  158. BK_RX_ADDR_P4 = 0x0E, // 'RX address pipe4' register address (1 byte)
  159. BK_RX_ADDR_P5 = 0x0F, // 'RX address pipe5' register address (1 byte)
  160. BK_TX_ADDR = 0x10, // 'TX address' register address (5 bytes)
  161. BK_RX_PW_P0 = 0x11, // 'RX payload width, pipe0' register address
  162. BK_RX_PW_P1 = 0x12, // 'RX payload width, pipe1' register address
  163. BK_RX_PW_P2 = 0x13, // 'RX payload width, pipe2' register address
  164. BK_RX_PW_P3 = 0x14, // 'RX payload width, pipe3' register address
  165. BK_RX_PW_P4 = 0x15, // 'RX payload width, pipe4' register address
  166. BK_RX_PW_P5 = 0x16, // 'RX payload width, pipe5' register address
  167. BK_FIFO_STATUS = 0x17, // 'FIFO Status Register' register address
  168. BK_DYNPD = 0x1c, // 'Enable dynamic payload length' register address
  169. BK_FEATURE = 0x1d, // 'Feature' register address
  170. BK_PAYLOAD_WIDTH = 0x1f, // 'payload length of 256 bytes modes register address
  171. // BK2425 bank 1 register addresses
  172. BK2425_R1_4 = 0x04,
  173. BK2425_R1_5 = 0x05,
  174. BK2425_R1_WHOAMI = 0x08, // Register to read that contains the chip id
  175. BK2425_R1_12 = 0x0C, // PLL speed 120 or 130us
  176. BK2425_R1_13 = 0x0D,
  177. BK2425_R1_14 = 0x0E,
  178. } BK_SPI_CMD;
  179. //----------------------------------------------------------------------------------
  180. // Chip Status Byte
  181. //----------------------------------------------------------------------------------
  182. enum {
  183. BK_CHIP_ID_BK2425 = 0x63, // The expected value of reading BK2425_R1_WHOAMI
  184. };
  185. // Meanings of the BK_STATUS register
  186. enum {
  187. BK_STATUS_RBANK = 0x80, // Register bank 1 is in use
  188. BK_STATUS_RX_DR = 0x40, // Data ready
  189. BK_STATUS_TX_DS = 0x20, // Data sent
  190. BK_STATUS_MAX_RT = 0x10, // Max retries failed
  191. BK_STATUS_RX_MASK = 0x0E, // Mask for the receptions bit
  192. BK_STATUS_RX_EMPTY = 0x0E,
  193. BK_STATUS_RX_P_5 = 0x0A, // Data pipe 5 has some data ready
  194. BK_STATUS_RX_P_4 = 0x08, // Data pipe 4 has some data ready
  195. BK_STATUS_RX_P_3 = 0x06, // Data pipe 3 has some data ready
  196. BK_STATUS_RX_P_2 = 0x04, // Data pipe 2 has some data ready
  197. BK_STATUS_RX_P_1 = 0x02, // Data pipe 1 has some data ready
  198. BK_STATUS_RX_P_0 = 0x00, // Data pipe 0 has some data ready
  199. BK_STATUS_TX_FULL = 0x01 // Tx buffer full
  200. };
  201. // Meanings of the FIFO_STATUS register
  202. enum {
  203. BK_FIFO_STATUS_TX_REUSE = 0x40,
  204. BK_FIFO_STATUS_TX_FULL = 0x20,
  205. BK_FIFO_STATUS_TX_EMPTY = 0x10,
  206. BK_FIFO_STATUS_RX_FULL = 0x02,
  207. BK_FIFO_STATUS_RX_EMPTY = 0x01
  208. };
  209. // Meanings of the BK_CONFIG register
  210. enum {
  211. BK_CONFIG_MASK_RX_DR = 0x40, // Mask interrupt caused by RX_DR
  212. BK_CONFIG_MASK_TX_DS = 0x20, // Mask interrupt caused by TX_DS
  213. BK_CONFIG_MASK_MAX_RT = 0x10, // Mask interrupt caused by MAX_RT
  214. BK_CONFIG_EN_CRC = 0x08, // Enable CRC. Forced high if one of the bits in the EN_AA is high
  215. BK_CONFIG_CRCO = 0x04, // CRC encoding scheme (0=8 bits, 1=16 bits)
  216. BK_CONFIG_PWR_UP = 0x02, // POWER UP
  217. BK_CONFIG_PRIM_RX = 0x01, // Receive/transmit
  218. };
  219. enum {
  220. BK_FEATURE_EN_DPL = 0x04, //
  221. BK_FEATURE_EN_ACK_PAY = 0x02, //
  222. BK_FEATURE_EN_DYN_ACK = 0x01, //
  223. };
  224. // (Lets make it one radio interface for both projects)
  225. /** The baud rate of the GFSK modulation */
  226. typedef enum ITX_SPEED_e {
  227. ITX_250, ///< 250kbps (slowest but furthest range)
  228. ITX_1000, ///< 1000kbps (balanced)
  229. ITX_2000, ///< 2000kbps (fastest hence least congested)
  230. ITX_CARRIER, ///< 0kbps (constant carrier wave)
  231. ITX_MAX
  232. } ITX_SPEED;
  233. enum {
  234. PACKET_LENGTH_RX_CTRL = 12,
  235. PACKET_LENGTH_RX_BIND = 12,
  236. PACKET_LENGTH_RX_MAX = 12,
  237. PACKET_LENGTH_TX_TELEMETRY = 12,
  238. PACKET_LENGTH_TX_DFU = 20,
  239. PACKET_LENGTH_TX_MAX = 20,
  240. };
  241. // Note that bank 1 registers 0...8 are MSB first; others are LSB first
  242. #define PLL_SPEED { BK2425_R1_12, 0x00,0x12,0x73,0x05 } // 0x00127305ul, // PLL locking time 130us compatible with nRF24L01;
  243. // In the array Bank1_Reg0_13[],all the register values are the byte reversed!
  244. enum {
  245. IREG1_4,
  246. IREG1_5,
  247. IREG1_12,
  248. IREG1_13,
  249. IREG1_4A,
  250. IREG_MAX
  251. };
  252. #define BK_MAX_PACKET_LEN 32 // max value is 32 bytes
  253. #define BK_RCV_TIMEOUT 30
  254. //----------------------------------------------------------------------------------
  255. // Translate output power into a number
  256. // must match up with the table RegPower[]
  257. #define OUTPUT_POWER_REG6_0 0 // -25dB
  258. #define OUTPUT_POWER_REG6_1 0 // -18dB
  259. #define OUTPUT_POWER_REG6_2 1 // -18dB
  260. #define OUTPUT_POWER_REG6_3 1 // -12dB
  261. #define OUTPUT_POWER_REG6_4 1 // -12dB
  262. #define OUTPUT_POWER_REG6_5 2 // -7dB
  263. #define OUTPUT_POWER_REG6_6 3 // -1dB
  264. #define OUTPUT_POWER_REG6_7 3 // +4dB
  265. // Register 4 in bank 1 only applies to Beken chip
  266. #define OUTPUT_POWER_REG4_0 0 // -25dB
  267. #define OUTPUT_POWER_REG4_1 3 // -18dB
  268. #define OUTPUT_POWER_REG4_2 0 // -18dB
  269. #define OUTPUT_POWER_REG4_3 3 // -12dB
  270. #define OUTPUT_POWER_REG4_4 2 // -12dB
  271. #define OUTPUT_POWER_REG4_5 0 // -7dB
  272. #define OUTPUT_POWER_REG4_6 0 // -1dB
  273. #define OUTPUT_POWER_REG4_7 7 // +4dB
  274. // Generic support
  275. #define TOKENPASTE(x, y) x ## y
  276. #define TOKENPASTE2(x, y) TOKENPASTE(x, y)
  277. // The default register values that are for the default power setting
  278. #define DEFAULT_OUTPUT_REG6 TOKENPASTE2(OUTPUT_POWER_REG6_,DEFAULT_OUTPUT_POWER)
  279. #define DEFAULT_OUTPUT_REG4 TOKENPASTE2(OUTPUT_POWER_REG4_,DEFAULT_OUTPUT_POWER)
  280. // This assumes we are using ChiBios instead of the pixhawk o/s for accessing GPIO
  281. #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_CHIBIOS_SKYVIPER_F412
  282. #define BEKEN_SELECT() (dev->set_chip_select(true))
  283. #define BEKEN_DESELECT() (dev->set_chip_select(false))
  284. #define BEKEN_CE_HIGH() (palSetLine(HAL_GPIO_PIN_RADIO_CE)) // (hal.gpio->write(HAL_CHIBIOS_GPIO_RADIO_CE, 1))
  285. #define BEKEN_CE_LOW() (palClearLine(HAL_GPIO_PIN_RADIO_CE)) // (hal.gpio->write(HAL_CHIBIOS_GPIO_RADIO_CE, 0))
  286. #define BEKEN_PA_HIGH() (palSetLine(HAL_GPIO_PIN_RADIO_PA_CTL)) // (hal.gpio->write(HAL_CHIBIOS_GPIO_RADIO_PA_CTL, 1))
  287. #define BEKEN_PA_LOW() (palClearLine(HAL_GPIO_PIN_RADIO_PA_CTL)) // (hal.gpio->write(HAL_CHIBIOS_GPIO_RADIO_PA_CTL, 0))
  288. #if SUPPORT_BK_DEBUG_PINS
  289. #define DEBUG1_HIGH() (palSetLine(HAL_GPIO_PIN_DEBUG1))
  290. #define DEBUG1_LOW() (palClearLine(HAL_GPIO_PIN_DEBUG1))
  291. #define DEBUG2_HIGH() (palSetLine(HAL_GPIO_PIN_DEBUG2))
  292. #define DEBUG2_LOW() (palClearLine(HAL_GPIO_PIN_DEBUG2))
  293. #else
  294. #define DEBUG1_HIGH() do {} while (0)
  295. #define DEBUG1_LOW() do {} while (0)
  296. #define DEBUG2_HIGH() do {} while (0)
  297. #define DEBUG2_LOW() do {} while (0)
  298. #endif
  299. #else
  300. #error This configuration is not supported.
  301. #endif
  302. /** Parameters used by the fcc pretests */
  303. typedef struct FccParams_s {
  304. uint8_t fcc_mode; ///< The value (0..6) last set by the user that we are using. Non-zero iff we are sending test signals
  305. bool scan_mode; ///< true for scanning, false for fixed frequencies
  306. bool CW_mode; ///< true for carrier wave, false for packets
  307. bool disable_crc_mode; ///< false for CRCs enabled, true for CRCs ignored on reception
  308. uint8_t scan_count; ///< In scan mode, packet count before incrementing scan
  309. uint8_t channel; ///< Current frequency 8..70
  310. uint8_t power; ///< Current power 1..8
  311. bool disable_crc; ///< true=crc is physically disabled
  312. uint8_t factory_mode; ///< factory test mode 0..8
  313. bool enable_cd; ///< enable carrier detect
  314. bool last_cd; ///< last carrier detect on a packet received
  315. } FccParams;
  316. typedef enum BkRadioMode_e {
  317. BKRADIO_SLEEP,
  318. BKRADIO_IDLE,
  319. BKRADIO_TX,
  320. BKRADIO_RX,
  321. BKRADIO_STANDBY1, // Not visible to the code yet
  322. BKRADIO_STANDBY2, // Not visible to the code yet
  323. } BkRadioMode;
  324. //----------------------------------------------------------------------------------
  325. // BEKEN driver class
  326. class Radio_Beken
  327. {
  328. public:
  329. // Generic functions
  330. Radio_Beken(AP_HAL::OwnPtr<AP_HAL::SPIDevice> _dev);
  331. bool lock_bus(void)
  332. {
  333. return dev->get_semaphore()->take(HAL_SEMAPHORE_BLOCK_FOREVER);
  334. }
  335. void unlock_bus(void)
  336. {
  337. dev->get_semaphore()->give();
  338. }
  339. // Raw SPI access functions
  340. void ReadRegisterMulti(uint8_t address, uint8_t *data, uint8_t len);
  341. void WriteRegisterMulti(uint8_t address, const uint8_t *data, uint8_t len);
  342. // Low-level Beken functions
  343. uint8_t ReadStatus(void);
  344. uint8_t ReadReg(uint8_t reg);
  345. uint8_t Strobe(uint8_t address);
  346. void SetRBank(uint8_t bank);
  347. void WriteReg(uint8_t address, uint8_t data);
  348. void WriteRegisterMultiBank1(uint8_t address, const uint8_t *data, uint8_t len);
  349. // High-level Beken functions
  350. void SetPower(uint8_t power);
  351. void SetChannel(uint8_t channel); // Sets the physical channel
  352. void SetCwMode(uint8_t cw);
  353. void SetCrcMode(uint8_t disable_crc); // non-zero means crc is ignored
  354. void SetFactoryMode(uint8_t factory);
  355. bool Reset(void);
  356. void SwitchToRxMode(void);
  357. void SwitchToTxMode(void);
  358. void SwitchToIdleMode(void);
  359. void SwitchToSleepMode(void);
  360. void InitBank0Registers(ITX_SPEED spd);
  361. void InitBank1Registers(ITX_SPEED spd);
  362. void SetAddresses(const uint8_t* txaddr); // Set the rx and tx addresses
  363. bool ClearAckOverflow(void);
  364. bool SendPacket(uint8_t type, const uint8_t* pbuf, uint8_t len);
  365. void DelayCE(void);
  366. void DumpRegisters(void);
  367. bool WasTxMode(void);
  368. bool WasRxMode(void);
  369. void ResetAddress(void);
  370. void EnableCarrierDetect(bool bEnable);
  371. bool CarrierDetect(void);
  372. // Visible public variables (naughty)
  373. volatile uint8_t bkReady; // initialised in AP_Radio_bk2425.h radio_init() at the very end. Similar to a semaphore.
  374. static ITX_SPEED gTxSpeed;
  375. FccParams fcc;
  376. packetFormatTx pktDataTx; // Packet data to send (telemetry)
  377. packetFormatDfu pktDataDfu; // Packet data to send (DFU)
  378. uint8_t TX_Address[5]; // For sending telemetry and DFU
  379. private:
  380. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
  381. uint8_t bFreshData; // Have we received a packet since we last processed one
  382. uint32_t numTxPackets;
  383. packetFormatRx pktDataRx; // Last valid packet that has been received
  384. packetFormatRx pktDataRecv; // Packet data in process of being received
  385. uint8_t lastTxChannel; // 0..CHANNEL_COUNT_LOGICAL
  386. uint8_t RX0_Address[5]; // The data address
  387. uint8_t RX1_Address[5]; // The fixed binding address
  388. BkRadioMode bkMode;
  389. };
  390. #endif