AP_Radio_cypress.h 7.6 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282
  1. /*
  2. This program is free software: you can redistribute it and/or modify
  3. it under the terms of the GNU General Public License as published by
  4. the Free Software Foundation, either version 3 of the License, or
  5. (at your option) any later version.
  6. This program is distributed in the hope that it will be useful,
  7. but WITHOUT ANY WARRANTY; without even the implied warranty of
  8. MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
  9. GNU General Public License for more details.
  10. You should have received a copy of the GNU General Public License
  11. along with this program. If not, see <http://www.gnu.org/licenses/>.
  12. */
  13. #pragma once
  14. #if HAL_RCINPUT_WITH_AP_RADIO
  15. /*
  16. AP_Radio implementation for Cypress 2.4GHz radio.
  17. With thanks to the SuperBitRF project
  18. See http://wiki.paparazziuav.org/wiki/SuperbitRF
  19. This implementation uses the DSMX protocol on a CYRF6936
  20. */
  21. #include "AP_Radio_backend.h"
  22. #include "hal.h"
  23. #include "telem_structure.h"
  24. class AP_Radio_cypress : public AP_Radio_backend
  25. {
  26. public:
  27. AP_Radio_cypress(AP_Radio &radio);
  28. // init - initialise radio
  29. bool init(void) override;
  30. // rest radio
  31. bool reset(void) override;
  32. // send a packet
  33. bool send(const uint8_t *pkt, uint16_t len) override;
  34. // start bind process as a receiver
  35. void start_recv_bind(void) override;
  36. // return time in microseconds of last received R/C packet
  37. uint32_t last_recv_us(void) override;
  38. // return number of input channels
  39. uint8_t num_channels(void) override;
  40. // return current PWM of a channel
  41. uint16_t read(uint8_t chan) override;
  42. // handle a data96 mavlink packet for fw upload
  43. void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) override;
  44. // update status
  45. void update(void) override;
  46. // get TX fw version
  47. uint32_t get_tx_version(void) override
  48. {
  49. // pack date into 16 bits for vendor_id in AUTOPILOT_VERSION
  50. return (uint16_t(dsm.tx_firmware_year)<<12) + (uint16_t(dsm.tx_firmware_month)<<8) + dsm.tx_firmware_day;
  51. }
  52. // get radio statistics structure
  53. const AP_Radio::stats &get_stats(void) override;
  54. // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
  55. void set_wifi_channel(uint8_t channel) override
  56. {
  57. t_status.wifi_chan = channel;
  58. }
  59. private:
  60. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
  61. static AP_Radio_cypress *radio_singleton;
  62. void radio_init(void);
  63. void dump_registers(uint8_t n);
  64. void force_initial_state(void);
  65. void set_channel(uint8_t channel);
  66. uint8_t read_status_debounced(uint8_t adr);
  67. uint8_t read_register(uint8_t reg);
  68. void write_register(uint8_t reg, uint8_t value);
  69. void write_multiple(uint8_t reg, uint8_t n, const uint8_t *data);
  70. enum {
  71. STATE_RECV,
  72. STATE_BIND,
  73. STATE_AUTOBIND,
  74. STATE_SEND_TELEM,
  75. STATE_SEND_TELEM_WAIT,
  76. STATE_SEND_FCC
  77. } state;
  78. struct config {
  79. uint8_t reg;
  80. uint8_t value;
  81. };
  82. static const uint8_t pn_codes[5][9][8];
  83. static const uint8_t pn_bind[];
  84. static const config cyrf_config[];
  85. static const config cyrf_bind_config[];
  86. static const config cyrf_transfer_config[];
  87. virtual_timer_t timeout_vt;
  88. static thread_t *_irq_handler_ctx;
  89. void radio_set_config(const struct config *config, uint8_t size);
  90. void start_receive(void);
  91. // main IRQ handler
  92. void irq_handler(void);
  93. // IRQ handler for packet receive
  94. void irq_handler_recv(uint8_t rx_status);
  95. // handle timeout IRQ
  96. void irq_timeout(void);
  97. // trampoline functions to take us from static IRQ function to class functions
  98. static void irq_handler_thd(void* arg);
  99. static void trigger_irq_radio_event(void);
  100. static void trigger_timeout_event(void *arg);
  101. static const uint8_t max_channels = 16;
  102. uint32_t last_debug_print_ms;
  103. void print_debug_info(void);
  104. AP_Radio::stats stats;
  105. AP_Radio::stats last_stats;
  106. enum dsm_protocol {
  107. DSM_NONE = 0, // not bound yet
  108. DSM_DSM2_1 = 0x01, // The original DSM2 protocol with 1 packet of data
  109. DSM_DSM2_2 = 0x02, // The original DSM2 protocol with 2 packets of data
  110. DSM_DSMX_1 = 0xA2, // The original DSMX protocol with 1 packet of data
  111. DSM_DSMX_2 = 0xB2, // The original DSMX protocol with 2 packets of data
  112. };
  113. enum dsm2_sync {
  114. DSM2_SYNC_A,
  115. DSM2_SYNC_B,
  116. DSM2_OK
  117. };
  118. // semaphore between ISR and main thread
  119. HAL_Semaphore sem;
  120. // dsm config data and status
  121. struct {
  122. uint8_t channels[23];
  123. enum dsm_protocol protocol;
  124. uint8_t mfg_id[4];
  125. uint8_t current_channel;
  126. uint8_t current_rf_channel;
  127. uint16_t crc_seed;
  128. uint8_t sop_col;
  129. uint8_t data_col;
  130. uint8_t last_sop_code[8];
  131. uint8_t last_data_code[16];
  132. uint32_t receive_start_us;
  133. uint32_t receive_timeout_msec;
  134. uint32_t last_recv_us;
  135. uint32_t last_parse_us;
  136. uint32_t last_recv_chan;
  137. uint32_t last_chan_change_us;
  138. uint16_t num_channels;
  139. uint16_t pwm_channels[max_channels];
  140. bool need_bind_save;
  141. enum dsm2_sync sync;
  142. uint32_t crc_errors;
  143. float rssi;
  144. bool last_discrc;
  145. uint8_t last_transmit_power;
  146. uint32_t send_irq_count;
  147. uint32_t send_count;
  148. uint16_t pkt_time1 = 3000;
  149. uint16_t pkt_time2 = 7000;
  150. uint8_t tx_firmware_year;
  151. uint8_t tx_firmware_month;
  152. uint8_t tx_firmware_day;
  153. int8_t forced_channel = -1;
  154. uint8_t tx_rssi;
  155. uint8_t tx_pps;
  156. uint32_t last_autobind_send;
  157. bool have_tx_pps;
  158. uint32_t telem_send_count;
  159. uint8_t tx_bl_version;
  160. } dsm;
  161. struct {
  162. mavlink_channel_t chan;
  163. bool need_ack;
  164. uint8_t counter;
  165. uint8_t sequence;
  166. uint32_t offset;
  167. uint32_t length;
  168. uint32_t acked;
  169. uint8_t len;
  170. enum telem_type fw_type;
  171. uint8_t pending_data[92];
  172. } fwupload;
  173. // bind structure saved to storage
  174. static const uint16_t bind_magic = 0x43F6;
  175. struct PACKED bind_info {
  176. uint16_t magic;
  177. uint8_t mfg_id[4];
  178. enum dsm_protocol protocol;
  179. };
  180. struct telem_status t_status;
  181. // DSM specific functions
  182. void dsm_set_channel(uint8_t channel, bool is_dsm2, uint8_t sop_col, uint8_t data_col, uint16_t crc_seed);
  183. // generate DSMX channels
  184. void dsm_generate_channels_dsmx(uint8_t mfg_id[4], uint8_t channels[23]);
  185. // setup for DSMX transfers
  186. void dsm_setup_transfer_dsmx(void);
  187. // choose channel to receive on
  188. void dsm_choose_channel(void);
  189. // map for mode1/mode2
  190. void map_stick_mode(uint16_t *channels);
  191. // parse DSM channels from a packet
  192. bool parse_dsm_channels(const uint8_t *data);
  193. // process an incoming packet
  194. void process_packet(const uint8_t *pkt, uint8_t len);
  195. // process an incoming bind packet
  196. void process_bind(const uint8_t *pkt, uint8_t len);
  197. // load bind info from storage
  198. void load_bind_info(void);
  199. // save bind info to storage
  200. void save_bind_info(void);
  201. bool is_DSM2(void);
  202. // send a 16 byte packet
  203. void transmit16(const uint8_t data[16]);
  204. void send_telem_packet(void);
  205. void irq_handler_send(uint8_t tx_status);
  206. void send_FCC_test_packet(void);
  207. // check sending of fw upload ack
  208. void check_fw_ack(void);
  209. // re-sync DSM2
  210. void dsm2_start_sync(void);
  211. // check for double binding
  212. void check_double_bind(void);
  213. // setup a timeout handler
  214. void setup_timeout(uint32_t timeout_ms);
  215. };
  216. #endif