APM:Libraries
AP_Radio_backend.h
Go to the documentation of this file.
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 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 #pragma once
16 
17 /*
18  * backend class for direct attached radios
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include "AP_Radio.h"
23 
25 {
26 public:
28  virtual ~AP_Radio_backend();
29 
30  // init - initialise radio
31  virtual bool init(void) = 0;
32 
33  // init - reset radio
34  virtual bool reset(void) = 0;
35 
36  // send a packet
37  virtual bool send(const uint8_t *pkt, uint16_t len) = 0;
38 
39  // start bind process as a receiver
40  virtual void start_recv_bind(void) = 0;
41 
42  // return time in microseconds of last received R/C packet
43  virtual uint32_t last_recv_us(void) = 0;
44 
45  // return number of input channels
46  virtual uint8_t num_channels(void) = 0;
47 
48  // return current PWM of a channel
49  virtual uint16_t read(uint8_t chan) = 0;
50 
51  // handle a data96 mavlink packet for fw upload
52  virtual void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m) {}
53 
54  // update status
55  virtual void update(void) = 0;
56 
57  // get TX fw version
58  virtual uint32_t get_tx_version(void) = 0;
59 
60  // get radio statistics structure
61  virtual const AP_Radio::stats &get_stats(void) = 0;
62 
63  // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
64  virtual void set_wifi_channel(uint8_t channel) = 0;
65 
66 protected:
67 
69  return (AP_Radio::ap_radio_protocol)radio.protocol.get();
70  }
71 
72  uint8_t get_debug_level(void) const {
73  return (uint8_t)radio.debug_level.get();
74  }
75 
76  bool get_disable_crc(void) const {
77  return (bool)radio.disable_crc.get();
78  }
79 
80  uint8_t get_rssi_chan(void) const {
81  return (uint8_t)radio.rssi_chan.get();
82  }
83 
84  uint8_t get_pps_chan(void) const {
85  return (uint8_t)radio.pps_chan.get();
86  }
87 
88  uint8_t get_tx_rssi_chan(void) const {
89  return (uint8_t)radio.tx_rssi_chan.get();
90  }
91 
92  uint8_t get_tx_pps_chan(void) const {
93  return (uint8_t)radio.tx_pps_chan.get();
94  }
95 
96  bool get_telem_enable(void) const {
97  return radio.telem_enable.get() > 0;
98  }
99 
100  uint8_t get_transmit_power(void) const {
101  return constrain_int16(radio.transmit_power.get(), 1, 8);
102  }
103 
104  uint8_t get_tx_max_power(void) const {
105  return constrain_int16(radio.tx_max_power.get(), 1, 8);
106  }
107 
108  void set_tx_max_power_default(uint8_t v) {
109  return radio.tx_max_power.set_default(v);
110  }
111 
112  int8_t get_fcc_test(void) const {
113  return radio.fcc_test.get();
114  }
115 
116  uint8_t get_stick_mode(void) const {
117  return radio.stick_mode.get();
118  }
119 
120  uint8_t get_factory_test(void) const {
121  return radio.factory_test.get();
122  }
123 
124  uint8_t get_tx_buzzer_adjust(void) const {
125  return radio.tx_buzzer_adjust.get();
126  }
127 
128  uint8_t get_autobind_time(void) const {
129  return radio.auto_bind_time.get();
130  }
131 
132  uint8_t get_autobind_rssi(void) const {
133  return radio.auto_bind_rssi.get();
134  }
135 
137 };
AP_Int8 disable_crc
Definition: AP_Radio.h:105
virtual const AP_Radio::stats & get_stats(void)=0
uint8_t get_tx_rssi_chan(void) const
AP_Int8 protocol
Definition: AP_Radio.h:103
AP_Int8 rssi_chan
Definition: AP_Radio.h:106
uint8_t get_debug_level(void) const
int16_t constrain_int16(const int16_t amt, const int16_t low, const int16_t high)
Definition: AP_Math.h:147
uint8_t get_rssi_chan(void) const
uint8_t get_factory_test(void) const
AP_Int8 fcc_test
Definition: AP_Radio.h:113
AP_Int8 factory_test
Definition: AP_Radio.h:115
virtual void update(void)=0
virtual bool reset(void)=0
virtual bool send(const uint8_t *pkt, uint16_t len)=0
AP_Int8 auto_bind_rssi
Definition: AP_Radio.h:118
AP_Radio_backend(AP_Radio &radio)
bool get_telem_enable(void) const
uint8_t get_autobind_rssi(void) const
AP_Int8 tx_max_power
Definition: AP_Radio.h:112
virtual uint16_t read(uint8_t chan)=0
AP_Int8 stick_mode
Definition: AP_Radio.h:114
int8_t get_fcc_test(void) const
AP_Int8 debug_level
Definition: AP_Radio.h:104
bool get_disable_crc(void) const
virtual void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
AP_Int8 transmit_power
Definition: AP_Radio.h:111
void set_tx_max_power_default(uint8_t v)
uint8_t get_stick_mode(void) const
virtual void start_recv_bind(void)=0
AP_Int8 telem_enable
Definition: AP_Radio.h:110
float v
Definition: Printf.cpp:15
AP_Int8 pps_chan
Definition: AP_Radio.h:107
virtual ~AP_Radio_backend()
uint8_t get_tx_buzzer_adjust(void) const
virtual void set_wifi_channel(uint8_t channel)=0
uint8_t get_transmit_power(void) const
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint8_t get_autobind_time(void) const
virtual bool init(void)=0
uint8_t get_tx_pps_chan(void) const
uint8_t get_tx_max_power(void) const
virtual uint32_t last_recv_us(void)=0
virtual uint8_t num_channels(void)=0
AP_Int8 tx_buzzer_adjust
Definition: AP_Radio.h:116
uint8_t get_pps_chan(void) const
virtual uint32_t get_tx_version(void)=0
AP_Int8 auto_bind_time
Definition: AP_Radio.h:117
AP_Int8 tx_pps_chan
Definition: AP_Radio.h:109
AP_Radio::ap_radio_protocol get_protocol(void) const
ap_radio_protocol
Definition: AP_Radio.h:76
AP_Int8 tx_rssi_chan
Definition: AP_Radio.h:108