AP_Radio_cc2500.h 6.1 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230
  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. /*
  15. AP_Radio implementation for CC2500 2.4GHz radio.
  16. With thanks to cleanflight and betaflight projects
  17. */
  18. #include "AP_Radio_backend.h"
  19. #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
  20. #include "hal.h"
  21. #include "telem_structure.h"
  22. #include "driver_cc2500.h"
  23. #define CC2500_MAX_PWM_CHANNELS 16
  24. class AP_Radio_cc2500 : public AP_Radio_backend
  25. {
  26. public:
  27. AP_Radio_cc2500(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(tx_date.firmware_year)<<12) + (uint16_t(tx_date.firmware_month)<<8) + tx_date.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. // static probe function for device detection
  60. static bool probe(void);
  61. private:
  62. AP_HAL::OwnPtr<AP_HAL::SPIDevice> dev;
  63. static AP_Radio_cc2500 *radio_singleton;
  64. static thread_t *_irq_handler_ctx;
  65. static virtual_timer_t timeout_vt;
  66. static void irq_handler_thd(void* arg);
  67. static void trigger_irq_radio_event(void);
  68. static void trigger_timeout_event(void *arg);
  69. void radio_init(void);
  70. // semaphore between ISR and main thread
  71. HAL_Semaphore sem;
  72. AP_Radio::stats stats;
  73. AP_Radio::stats last_stats;
  74. uint16_t pwm_channels[CC2500_MAX_PWM_CHANNELS];
  75. Radio_CC2500 cc2500;
  76. uint8_t bindTxId[2];
  77. int8_t bindOffset;
  78. uint8_t bindHopData[47];
  79. uint8_t rxNum;
  80. uint8_t listLength;
  81. uint8_t channr;
  82. uint8_t chanskip;
  83. int8_t fcc_chan;
  84. uint32_t packet_timer;
  85. static uint32_t irq_time_us;
  86. uint8_t chan_count;
  87. uint32_t lost;
  88. uint32_t timeouts;
  89. bool have_bind_info;
  90. uint8_t packet3;
  91. bool telem_send_rssi;
  92. float rssi_filtered;
  93. uint64_t bind_mask;
  94. uint8_t best_lqi;
  95. int8_t best_bindOffset;
  96. int8_t auto_bindOffset;
  97. uint8_t search_count;
  98. uint8_t last_wifi_channel;
  99. uint32_t timeTunedMs;
  100. uint32_t autobind_start_recv_ms;
  101. void initTuneRx(void);
  102. void initialiseData(uint8_t adr);
  103. void initGetBind(void);
  104. bool tuneRx(uint8_t ccLen, uint8_t *packet);
  105. bool getBindData(uint8_t ccLen, uint8_t *packet);
  106. bool check_best_LQI(void);
  107. void setChannel(uint8_t channel);
  108. void setChannelRX(uint8_t channel);
  109. void nextChannel(uint8_t skip);
  110. void parse_frSkyX(const uint8_t *packet);
  111. uint16_t calc_crc(const uint8_t *data, uint8_t len);
  112. bool check_crc(uint8_t ccLen, uint8_t *packet);
  113. void send_D16_telemetry(void);
  114. void send_SRT_telemetry(void);
  115. void irq_handler(void);
  116. void irq_timeout(void);
  117. // bind structure saved to storage
  118. static const uint16_t bind_magic = 0x120c;
  119. struct PACKED bind_info {
  120. uint16_t magic;
  121. uint8_t bindTxId[2];
  122. int8_t bindOffset;
  123. uint8_t wifi_chan;
  124. uint8_t bindHopData[47];
  125. };
  126. void save_bind_info(void);
  127. bool load_bind_info(void);
  128. enum {
  129. STATE_INIT = 0,
  130. STATE_BIND,
  131. STATE_BIND_TUNING,
  132. STATE_BIND_BINDING,
  133. STATE_BIND_COMPLETE,
  134. STATE_STARTING,
  135. STATE_DATA,
  136. STATE_TELEMETRY,
  137. STATE_RESUME,
  138. STATE_FCCTEST,
  139. STATE_SEARCH,
  140. } protocolState;
  141. struct config {
  142. uint8_t reg;
  143. uint8_t value;
  144. };
  145. static const config radio_config_GFSK[];
  146. static const config radio_config[];
  147. struct {
  148. mavlink_channel_t chan;
  149. bool need_ack;
  150. uint8_t counter;
  151. uint8_t sequence;
  152. uint32_t offset;
  153. uint32_t length;
  154. uint32_t acked;
  155. uint8_t len;
  156. enum telem_type fw_type;
  157. uint8_t pending_data[92];
  158. } fwupload;
  159. struct {
  160. uint8_t firmware_year;
  161. uint8_t firmware_month;
  162. uint8_t firmware_day;
  163. } tx_date;
  164. struct telem_status_cc2500 t_status;
  165. uint32_t last_pps_ms;
  166. uint8_t tx_rssi;
  167. uint8_t tx_pps;
  168. bool have_tx_pps;
  169. uint8_t last_fcc_chan;
  170. uint32_t telem_send_count;
  171. bool handle_D16_packet(const uint8_t *packet);
  172. bool handle_SRT_packet(const uint8_t *packet);
  173. bool handle_autobind_packet(const uint8_t *packet, uint8_t lqi);
  174. bool have_channel(uint8_t channel, uint8_t count, uint8_t loop);
  175. void setup_hopping_table_SRT(void);
  176. uint8_t map_RSSI_to_dBm(uint8_t rssi_raw);
  177. // check sending of fw upload ack
  178. void check_fw_ack(void);
  179. void map_stick_mode(uint16_t *channels);
  180. void set_fcc_channel(void);
  181. // check for double binding
  182. void check_double_bind(void);
  183. };
  184. #endif // CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS