APM:Libraries
AP_Radio.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if HAL_RCINPUT_WITH_AP_RADIO
4 
5 #include "AP_Radio.h"
6 #include "AP_Radio_backend.h"
7 #include "AP_Radio_cypress.h"
8 #include "AP_Radio_cc2500.h"
9 
10 extern const AP_HAL::HAL& hal;
11 
12 // table of user settable parameters
14 
15  // @Param: _TYPE
16  // @DisplayName: Set type of direct attached radio
17  // @Description: This enables support for direct attached radio receivers
18  // @Values: 0:None,1:CYRF6936
19  // @User: Advanced
20  AP_GROUPINFO("_TYPE", 1, AP_Radio, radio_type, 0),
21 
22  // @Param: _PROT
23  // @DisplayName: protocol
24  // @Description: Select air protocol
25  // @Values: 0:Auto,1:DSM2,2:DSMX
26  // @User: Advanced
27  AP_GROUPINFO("_PROT", 2, AP_Radio, protocol, PROTOCOL_AUTO),
28 
29  // @Param: _DEBUG
30  // @DisplayName: debug level
31  // @Description: radio debug level
32  // @Range: 0 4
33  // @User: Advanced
34  AP_GROUPINFO("_DEBUG", 3, AP_Radio, debug_level, 0),
35 
36  // @Param: _DISCRC
37  // @DisplayName: disable receive CRC
38  // @Description: disable receive CRC (for debug)
39  // @Values: 0:NotDisabled,1:Disabled
40  // @User: Advanced
41  AP_GROUPINFO("_DISCRC", 4, AP_Radio, disable_crc, 0),
42 
43  // @Param: _SIGCH
44  // @DisplayName: RSSI signal strength
45  // @Description: Channel to show receive RSSI signal strength, or zero for disabled
46  // @Range: 0 16
47  // @User: Advanced
48  AP_GROUPINFO("_SIGCH", 5, AP_Radio, rssi_chan, 0),
49 
50  // @Param: _PPSCH
51  // @DisplayName: Packet rate channel
52  // @Description: Channel to show received packet-per-second rate, or zero for disabled
53  // @Range: 0 16
54  // @User: Advanced
55  AP_GROUPINFO("_PPSCH", 6, AP_Radio, pps_chan, 0),
56 
57  // @Param: _TELEM
58  // @DisplayName: Enable telemetry
59  // @Description: If this is non-zero then telemetry packets will be sent over DSM
60  // @Values: 0:Disabled,1:Enabled
61  // @User: Advanced
62  AP_GROUPINFO("_TELEM", 7, AP_Radio, telem_enable, 0),
63 
64  // @Param: _TXPOW
65  // @DisplayName: Telemetry Transmit power
66  // @Description: Set telemetry transmit power. This is the power level (from 1 to 8) for telemetry packets sent from the RX to the TX
67  // @Range: 1 8
68  // @User: Advanced
69  AP_GROUPINFO("_TXPOW", 8, AP_Radio, transmit_power, 8),
70 
71  // @Param: _FCCTST
72  // @DisplayName: Put radio into FCC test mode
73  // @Description: If this is enabled then the radio will continuously transmit as required for FCC testing. The transmit channel is set by the value of the parameter. The radio will not work for RC input while this is enabled
74  // @Values: 0:Disabled,1:MinChannel,2:MidChannel,3:MaxChannel,4:MinChannelCW,5:MidChannelCW,6:MaxChannelCW
75  // @User: Advanced
76  AP_GROUPINFO("_FCCTST", 9, AP_Radio, fcc_test, 0),
77 
78  // @Param: _STKMD
79  // @DisplayName: Stick input mode
80  // @Description: This selects between different stick input modes. The default is mode2, which has throttle on the left stick and pitch on the right stick. You can instead set mode1, which has throttle on the right stick and pitch on the left stick.
81  // @Values: 1:Mode1,2:Mode2
82  // @User: Advanced
83  AP_GROUPINFO("_STKMD", 10, AP_Radio, stick_mode, 2),
84 
85  // @Param: _TESTCH
86  // @DisplayName: Set radio to factory test channel
87  // @Description: This sets the radio to a fixed test channel for factory testing. Using a fixed channel avoids the need for binding in factory testing.
88  // @Values: 0:Disabled,1:TestChan1,2:TestChan2,3:TestChan3,4:TestChan4,5:TestChan5,6:TestChan6,7:TestChan7,8:TestChan8
89  // @User: Advanced
90  AP_GROUPINFO("_TESTCH", 11, AP_Radio, factory_test, 0),
91 
92  // @Param: _TSIGCH
93  // @DisplayName: RSSI value channel for telemetry data on transmitter
94  // @Description: Channel to show telemetry RSSI value as received by TX
95  // @Range: 0 16
96  // @User: Advanced
97  AP_GROUPINFO("_TSIGCH", 12, AP_Radio, tx_rssi_chan, 0),
98 
99  // @Param: _TPPSCH
100  // @DisplayName: Telemetry PPS channel
101  // @Description: Channel to show telemetry packets-per-second value, as received at TX
102  // @Range: 0 16
103  // @User: Advanced
104  AP_GROUPINFO("_TPPSCH", 13, AP_Radio, tx_pps_chan, 0),
105 
106  // @Param: _TXMAX
107  // @DisplayName: Transmitter transmit power
108  // @Description: Set transmitter maximum transmit power (from 1 to 8)
109  // @Range: 1 8
110  // @User: Advanced
111  AP_GROUPINFO("_TXMAX", 14, AP_Radio, tx_max_power, 4),
112 
113  // @Param: _BZOFS
114  // @DisplayName: Transmitter buzzer adjustment
115  // @Description: Set transmitter buzzer note adjustment (adjust frequency up)
116  // @Range: 0 40
117  // @User: Advanced
118  AP_GROUPINFO("_BZOFS", 15, AP_Radio, tx_buzzer_adjust, 25),
119 
120  // @Param: _ABTIME
121  // @DisplayName: Auto-bind time
122  // @Description: When non-zero this sets the time with no transmitter packets before we start looking for auto-bind packets.
123  // @Range: 0 120
124  // @User: Advanced
125  AP_GROUPINFO("_ABTIME", 16, AP_Radio, auto_bind_time, 0),
126 
127  // @Param: _ABLVL
128  // @DisplayName: Auto-bind level
129  // @Description: This sets the minimum RSSI of an auto-bind packet for it to be accepted. This should be set so that auto-bind will only happen at short range to minimise the change of an auto-bind happening accidentially
130  // @Range: 0 31
131  // @User: Advanced
132  AP_GROUPINFO("_ABLVL", 17, AP_Radio, auto_bind_rssi, 0),
133 
135 };
136 
138 
139 // constructor
140 AP_Radio::AP_Radio(void)
141 {
143  if (_instance != nullptr) {
144  AP_HAL::panic("Multiple AP_Radio declarations");
145  }
146  _instance = this;
147 }
148 
149 bool AP_Radio::init(void)
150 {
151  switch (radio_type) {
152  case RADIO_TYPE_CYRF6936:
153  driver = new AP_Radio_cypress(*this);
154  break;
155 #if CONFIG_HAL_BOARD == HAL_BOARD_CHIBIOS
156  case RADIO_TYPE_CC2500:
157  driver = new AP_Radio_cc2500(*this);
158  break;
159 #endif
160  default:
161  break;
162  }
163  if (!driver) {
164  return false;
165  }
166  return driver->init();
167 }
168 
169 bool AP_Radio::reset(void)
170 {
171  if (!driver) {
172  return false;
173  }
174  return driver->reset();
175 }
176 
177 bool AP_Radio::send(const uint8_t *pkt, uint16_t len)
178 {
179  if (!driver) {
180  return false;
181  }
182  return driver->send(pkt, len);
183 }
184 
185 void AP_Radio::start_recv_bind(void)
186 {
187  if (!driver) {
188  return;
189  }
190  return driver->start_recv_bind();
191 }
192 
194 {
195  return driver->get_stats();
196 }
197 
198 uint8_t AP_Radio::num_channels(void)
199 {
200  if (!driver) {
201  return 0;
202  }
203  return driver->num_channels();
204 }
205 
206 uint16_t AP_Radio::read(uint8_t chan)
207 {
208  if (!driver) {
209  return 0;
210  }
211  return driver->read(chan);
212 }
213 
214 uint32_t AP_Radio::last_recv_us(void)
215 {
216  if (!driver) {
217  return 0;
218  }
219  return driver->last_recv_us();
220 }
221 
222 // handle a data96 mavlink packet for fw upload
223 void AP_Radio::handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
224 {
225  if (driver) {
226  driver->handle_data_packet(chan, m);
227  }
228 }
229 
230 // update status, should be called from main thread
231 void AP_Radio::update(void)
232 {
233  if (driver) {
234  driver->update();
235  }
236 }
237 
238 // get transmitter firmware version
239 uint32_t AP_Radio::get_tx_version(void)
240 {
241  if (driver) {
242  return driver->get_tx_version();
243  }
244  return 0;
245 }
246 
247 // set the 2.4GHz wifi channel used by companion computer, so it can be avoided
248 void AP_Radio::set_wifi_channel(uint8_t channel)
249 {
250  if (driver) {
251  driver->set_wifi_channel(channel);
252  }
253 }
254 
255 #endif // HAL_RCINPUT_WITH_AP_RADIO
256 
virtual const AP_Radio::stats & get_stats(void)=0
static const struct AP_Param::GroupInfo var_info[]
Definition: AP_Radio.h:86
void start_recv_bind(void)
AP_Radio(void)
#define AP_GROUPINFO(name, idx, clazz, element, def)
Definition: AP_Param.h:102
const AP_HAL::HAL & hal
Definition: UARTDriver.cpp:37
virtual void update(void)=0
virtual bool reset(void)=0
void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
virtual bool send(const uint8_t *pkt, uint16_t len)=0
const struct stats & get_stats(void)
virtual uint16_t read(uint8_t chan)=0
bool send(const uint8_t *pkt, uint16_t len)
virtual void handle_data_packet(mavlink_channel_t chan, const mavlink_data96_t &m)
uint32_t last_recv_us(void)
void set_wifi_channel(uint8_t channel)
virtual void start_recv_bind(void)=0
AP_Int8 radio_type
Definition: AP_Radio.h:102
uint16_t read(uint8_t chan)
bool reset(void)
virtual void set_wifi_channel(uint8_t channel)=0
void update(void)
AP_HAL::AnalogSource * chan
Definition: AnalogIn.cpp:8
virtual bool init(void)=0
uint8_t num_channels(void)
virtual uint32_t last_recv_us(void)=0
virtual uint8_t num_channels(void)=0
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
virtual uint32_t get_tx_version(void)=0
bool init(void)
AP_Radio_backend * driver
Definition: AP_Radio.h:100
#define AP_GROUPEND
Definition: AP_Param.h:121
uint32_t get_tx_version(void)
static void setup_object_defaults(const void *object_pointer, const struct GroupInfo *group_info)
Definition: AP_Param.cpp:1214
static AP_Radio * _instance
Definition: AP_Radio.h:120