AP_Radio.h 3.2 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131
  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. * base class for direct attached radios
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include <AP_Param/AP_Param.h>
  19. #include <GCS_MAVLink/GCS.h>
  20. class AP_Radio_backend;
  21. class AP_Radio
  22. {
  23. public:
  24. friend class AP_Radio_backend;
  25. // constructor
  26. AP_Radio(void);
  27. // init - initialise radio
  28. bool init(void);
  29. // reset the radio
  30. bool reset(void);
  31. // send a packet
  32. bool send(const uint8_t *pkt, uint16_t len);
  33. // start bind process as a receiver
  34. void start_recv_bind(void);
  35. // return time in microseconds of last received R/C packet
  36. uint32_t last_recv_us(void);
  37. // return number of input channels
  38. uint8_t num_channels(void);
  39. // return current PWM of a channel
  40. uint16_t read(uint8_t chan);
  41. // update status, should be called from main thread
  42. void update(void);
  43. // get transmitter firmware version
  44. uint32_t get_tx_version(void);
  45. struct stats {
  46. uint32_t bad_packets;
  47. uint32_t recv_errors;
  48. uint32_t recv_packets;
  49. uint32_t lost_packets;
  50. uint32_t timeouts;
  51. };
  52. enum ap_radio_type {
  53. RADIO_TYPE_NONE=0,
  54. RADIO_TYPE_CYRF6936=1,
  55. RADIO_TYPE_CC2500=2,
  56. RADIO_TYPE_BK2425=3,
  57. RADIO_TYPE_AUTO=100,
  58. };
  59. enum ap_radio_protocol {
  60. PROTOCOL_AUTO=0,
  61. PROTOCOL_DSM2=1,
  62. PROTOCOL_DSMX=2,
  63. PROTOCOL_D16=3,
  64. PROTOCOL_CC2500_GFSK=4, // deviation 57kHz for update of cc2500 with GFSK
  65. };
  66. // get packet statistics
  67. const struct stats &get_stats(void);
  68. static const struct AP_Param::GroupInfo var_info[];
  69. // get singleton instance
  70. static AP_Radio *get_singleton(void)
  71. {
  72. return _singleton;
  73. }
  74. // handle a data96 mavlink packet for fw upload
  75. void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m);
  76. // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
  77. void set_wifi_channel(uint8_t channel);
  78. // play a tune on the TX
  79. void play_tune(const char *tune_str);
  80. // change TX mode
  81. void change_txmode(void);
  82. private:
  83. AP_Radio_backend *driver;
  84. AP_Int8 radio_type;
  85. AP_Int8 protocol;
  86. AP_Int8 debug_level;
  87. AP_Int8 disable_crc;
  88. AP_Int8 rssi_chan;
  89. AP_Int8 pps_chan;
  90. AP_Int8 tx_rssi_chan;
  91. AP_Int8 tx_pps_chan;
  92. AP_Int8 telem_enable;
  93. AP_Int8 transmit_power;
  94. AP_Int8 tx_max_power;
  95. AP_Int8 fcc_test;
  96. AP_Int8 stick_mode;
  97. AP_Int8 factory_test;
  98. AP_Int8 tx_buzzer_adjust;
  99. AP_Int8 auto_bind_time;
  100. AP_Int8 auto_bind_rssi;
  101. static AP_Radio *_singleton;
  102. };