AP_Radio_backend.h 3.8 KB

123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156
  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. * backend class for direct attached radios
  16. */
  17. #include <AP_HAL/AP_HAL.h>
  18. #include "AP_Radio.h"
  19. class AP_Radio_backend
  20. {
  21. public:
  22. AP_Radio_backend(AP_Radio &radio);
  23. virtual ~AP_Radio_backend();
  24. // init - initialise radio
  25. virtual bool init(void) = 0;
  26. // init - reset radio
  27. virtual bool reset(void) = 0;
  28. // send a packet
  29. virtual bool send(const uint8_t *pkt, uint16_t len) = 0;
  30. // start bind process as a receiver
  31. virtual void start_recv_bind(void) = 0;
  32. // return time in microseconds of last received R/C packet
  33. virtual uint32_t last_recv_us(void) = 0;
  34. // return number of input channels
  35. virtual uint8_t num_channels(void) = 0;
  36. // return current PWM of a channel
  37. virtual uint16_t read(uint8_t chan) = 0;
  38. // handle a data96 mavlink packet for fw upload
  39. virtual void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) {}
  40. // update status
  41. virtual void update(void) = 0;
  42. // get TX fw version
  43. virtual uint32_t get_tx_version(void) = 0;
  44. // get radio statistics structure
  45. virtual const AP_Radio::stats &get_stats(void) = 0;
  46. // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
  47. virtual void set_wifi_channel(uint8_t channel) = 0;
  48. protected:
  49. // These functions are for the radio code to access the parameters
  50. // that the user can set using the web interface.
  51. AP_Radio::ap_radio_protocol get_protocol(void) const
  52. {
  53. return (AP_Radio::ap_radio_protocol)radio.protocol.get();
  54. }
  55. uint8_t get_debug_level(void) const
  56. {
  57. return (uint8_t)radio.debug_level.get();
  58. }
  59. bool get_disable_crc(void) const
  60. {
  61. return (bool)radio.disable_crc.get();
  62. }
  63. uint8_t get_rssi_chan(void) const
  64. {
  65. return (uint8_t)radio.rssi_chan.get();
  66. }
  67. uint8_t get_pps_chan(void) const
  68. {
  69. return (uint8_t)radio.pps_chan.get();
  70. }
  71. uint8_t get_tx_rssi_chan(void) const
  72. {
  73. return (uint8_t)radio.tx_rssi_chan.get();
  74. }
  75. uint8_t get_tx_pps_chan(void) const
  76. {
  77. return (uint8_t)radio.tx_pps_chan.get();
  78. }
  79. bool get_telem_enable(void) const
  80. {
  81. return radio.telem_enable.get() > 0;
  82. }
  83. uint8_t get_transmit_power(void) const
  84. {
  85. return constrain_int16(radio.transmit_power.get(), 1, 8);
  86. }
  87. uint8_t get_tx_max_power(void) const
  88. {
  89. return constrain_int16(radio.tx_max_power.get(), 1, 8);
  90. }
  91. void set_tx_max_power_default(uint8_t v)
  92. {
  93. return radio.tx_max_power.set_default(v);
  94. }
  95. int8_t get_fcc_test(void) const
  96. {
  97. return radio.fcc_test.get();
  98. }
  99. uint8_t get_stick_mode(void) const
  100. {
  101. return radio.stick_mode.get();
  102. }
  103. uint8_t get_factory_test(void) const
  104. {
  105. return radio.factory_test.get();
  106. }
  107. uint8_t get_tx_buzzer_adjust(void) const
  108. {
  109. return radio.tx_buzzer_adjust.get();
  110. }
  111. uint8_t get_autobind_time(void) const
  112. {
  113. return radio.auto_bind_time.get();
  114. }
  115. uint8_t get_autobind_rssi(void) const
  116. {
  117. return radio.auto_bind_rssi.get();
  118. }
  119. AP_Radio &radio;
  120. };