APM:Libraries
AP_Radio.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  * base class for direct attached radios
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Param/AP_Param.h>
23 #include <GCS_MAVLink/GCS.h>
24 
25 class AP_Radio_backend;
26 
27 class AP_Radio
28 {
29 public:
30  friend class AP_Radio_backend;
31 
32  // constructor
33  AP_Radio(void);
34 
35  // init - initialise radio
36  bool init(void);
37 
38  // reset the radio
39  bool reset(void);
40 
41  // send a packet
42  bool send(const uint8_t *pkt, uint16_t len);
43 
44  // start bind process as a receiver
45  void start_recv_bind(void);
46 
47  // return time in microseconds of last received R/C packet
48  uint32_t last_recv_us(void);
49 
50  // return number of input channels
51  uint8_t num_channels(void);
52 
53  // return current PWM of a channel
54  uint16_t read(uint8_t chan);
55 
56  // update status, should be called from main thread
57  void update(void);
58 
59  // get transmitter firmware version
60  uint32_t get_tx_version(void);
61 
62  struct stats {
63  uint32_t bad_packets;
64  uint32_t recv_errors;
65  uint32_t recv_packets;
66  uint32_t lost_packets;
67  uint32_t timeouts;
68  };
69 
74  };
75 
81  };
82 
83  // get packet statistics
84  const struct stats &get_stats(void);
85 
86  static const struct AP_Param::GroupInfo var_info[];
87 
88  // get singleton instance
89  static AP_Radio *instance(void) {
90  return _instance;
91  }
92 
93  // handle a data96 mavlink packet for fw upload
94  void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m);
95 
96  // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
97  void set_wifi_channel(uint8_t channel);
98 
99 private:
101 
102  AP_Int8 radio_type;
103  AP_Int8 protocol;
104  AP_Int8 debug_level;
105  AP_Int8 disable_crc;
106  AP_Int8 rssi_chan;
107  AP_Int8 pps_chan;
108  AP_Int8 tx_rssi_chan;
109  AP_Int8 tx_pps_chan;
110  AP_Int8 telem_enable;
111  AP_Int8 transmit_power;
112  AP_Int8 tx_max_power;
113  AP_Int8 fcc_test;
114  AP_Int8 stick_mode;
115  AP_Int8 factory_test;
117  AP_Int8 auto_bind_time;
118  AP_Int8 auto_bind_rssi;
119 
121 };
AP_Int8 disable_crc
Definition: AP_Radio.h:105
AP_Int8 protocol
Definition: AP_Radio.h:103
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Radio.h:86
void start_recv_bind(void)
AP_Int8 rssi_chan
Definition: AP_Radio.h:106
AP_Radio(void)
uint32_t recv_errors
Definition: AP_Radio.h:64
Interface definition for the various Ground Control System.
AP_Int8 fcc_test
Definition: AP_Radio.h:113
AP_Int8 factory_test
Definition: AP_Radio.h:115
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
AP_Int8 auto_bind_rssi
Definition: AP_Radio.h:118
const struct stats & get_stats(void)
uint32_t timeouts
Definition: AP_Radio.h:67
A system for managing and storing variables that are of general interest to the system.
static AP_Radio * instance(void)
Definition: AP_Radio.h:89
uint32_t recv_packets
Definition: AP_Radio.h:65
uint32_t lost_packets
Definition: AP_Radio.h:66
AP_Int8 tx_max_power
Definition: AP_Radio.h:112
ap_radio_type
Definition: AP_Radio.h:70
AP_Int8 stick_mode
Definition: AP_Radio.h:114
bool send(const uint8_t *pkt, uint16_t len)
AP_Int8 debug_level
Definition: AP_Radio.h:104
AP_Int8 transmit_power
Definition: AP_Radio.h:111
uint32_t last_recv_us(void)
void set_wifi_channel(uint8_t channel)
AP_Int8 telem_enable
Definition: AP_Radio.h:110
AP_Int8 pps_chan
Definition: AP_Radio.h:107
AP_Int8 radio_type
Definition: AP_Radio.h:102
uint16_t read(uint8_t chan)
bool reset(void)
uint32_t bad_packets
Definition: AP_Radio.h:63
void update(void)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
uint8_t num_channels(void)
AP_Int8 tx_buzzer_adjust
Definition: AP_Radio.h:116
bool init(void)
AP_Int8 auto_bind_time
Definition: AP_Radio.h:117
AP_Int8 tx_pps_chan
Definition: AP_Radio.h:109
AP_Radio_backend * driver
Definition: AP_Radio.h:100
uint32_t get_tx_version(void)
ap_radio_protocol
Definition: AP_Radio.h:76
AP_Int8 tx_rssi_chan
Definition: AP_Radio.h:108
static AP_Radio * _instance
Definition: AP_Radio.h:120