Copter: free allocations in case of allocation failure
[ardupilot.git] / libraries / AP_RCProtocol / AP_RCProtocol.h
blobbcf7038ba96bd46c8218654d5173b173059f9503
1 /*
2 * This file is free software: you can redistribute it and/or modify it
3 * under the terms of the GNU General Public License as published by the
4 * Free Software Foundation, either version 3 of the License, or
5 * (at your option) any later version.
7 * This file is distributed in the hope that it will be useful, but
8 * WITHOUT ANY WARRANTY; without even the implied warranty of
9 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
10 * See the GNU General Public License for more details.
12 * You should have received a copy of the GNU General Public License along
13 * with this program. If not, see <http://www.gnu.org/licenses/>.
15 * Code by Andrew Tridgell and Siddharth Bharat Purohit
17 #pragma once
19 #include "AP_RCProtocol_config.h"
21 #include <AP_HAL/AP_HAL.h>
22 #include <AP_Common/AP_Common.h>
23 #if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
24 #include <GCS_MAVLink/GCS_MAVLink.h>
25 #endif
27 #define MAX_RCIN_CHANNELS 18
28 #define MIN_RCIN_CHANNELS 5
30 class AP_RCProtocol_Backend;
32 class AP_RCProtocol {
33 public:
35 enum rcprotocol_t {
36 #if AP_RCPROTOCOL_PPMSUM_ENABLED
37 PPMSUM = 0,
38 #endif
39 #if AP_RCPROTOCOL_IBUS_ENABLED
40 IBUS = 1,
41 #endif
42 #if AP_RCPROTOCOL_SBUS_ENABLED
43 SBUS = 2,
44 #endif
45 #if AP_RCPROTOCOL_SBUS_NI_ENABLED
46 SBUS_NI = 3,
47 #endif
48 #if AP_RCPROTOCOL_DSM_ENABLED
49 DSM = 4,
50 #endif
51 #if AP_RCPROTOCOL_SUMD_ENABLED
52 SUMD = 5,
53 #endif
54 #if AP_RCPROTOCOL_SRXL_ENABLED
55 SRXL = 6,
56 #endif
57 #if AP_RCPROTOCOL_SRXL2_ENABLED
58 SRXL2 = 7,
59 #endif
60 #if AP_RCPROTOCOL_CRSF_ENABLED
61 CRSF = 8,
62 #endif
63 #if AP_RCPROTOCOL_ST24_ENABLED
64 ST24 = 9,
65 #endif
66 #if AP_RCPROTOCOL_FPORT_ENABLED
67 FPORT = 10,
68 #endif
69 #if AP_RCPROTOCOL_FPORT2_ENABLED
70 FPORT2 = 11,
71 #endif
72 #if AP_RCPROTOCOL_FASTSBUS_ENABLED
73 FASTSBUS = 12,
74 #endif
75 #if AP_RCPROTOCOL_DRONECAN_ENABLED
76 DRONECAN = 13,
77 #endif
78 #if AP_RCPROTOCOL_GHST_ENABLED
79 GHST = 14,
80 #endif
81 #if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
82 MAVLINK_RADIO = 15,
83 #endif
84 #if AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED
85 JOYSTICK_SFML = 16,
86 #endif
87 #if AP_RCPROTOCOL_UDP_ENABLED
88 UDP = 17,
89 #endif
90 #if AP_RCPROTOCOL_FDM_ENABLED
91 FDM = 18,
92 #endif
93 #if AP_RCPROTOCOL_RADIO_ENABLED
94 RADIO = 19,
95 #endif
96 NONE //last enum always is None
99 // return protocol name as a string
100 static const char *protocol_name_from_protocol(rcprotocol_t protocol);
102 #if AP_RCPROTOCOL_ENABLED
104 AP_RCProtocol() {}
105 ~AP_RCProtocol();
106 friend class AP_RCProtocol_Backend;
108 void init();
109 bool valid_serial_prot() const
111 return _valid_serial_prot;
113 bool should_search(uint32_t now_ms) const;
114 void process_pulse(uint32_t width_s0, uint32_t width_s1);
115 void process_pulse_list(const uint32_t *widths, uint16_t n, bool need_swap);
116 bool process_byte(uint8_t byte, uint32_t baudrate);
117 void process_handshake(uint32_t baudrate);
118 void update(void);
120 bool failsafe_active() const {
121 return _failsafe_active;
123 void set_failsafe_active(bool active) {
124 _failsafe_active = active;
127 void disable_for_pulses(enum rcprotocol_t protocol) {
128 _disabled_for_pulses |= (1U<<(uint8_t)protocol);
131 #if !defined(__clang__)
132 // in the case we've disabled most backends then the "return true" in
133 // the following method can never be reached, and the compiler gets
134 // annoyed at that.
135 #pragma GCC diagnostic push
136 #pragma GCC diagnostic ignored "-Wswitch-unreachable"
137 #endif
139 // for protocols without strong CRCs we require 3 good frames to lock on
140 bool requires_3_frames(enum rcprotocol_t p) {
141 switch (p) {
142 #if AP_RCPROTOCOL_DSM_ENABLED
143 case DSM:
144 #endif
145 #if AP_RCPROTOCOL_FASTSBUS_ENABLED
146 case FASTSBUS:
147 #endif
148 #if AP_RCPROTOCOL_SBUS_ENABLED
149 case SBUS:
150 #endif
151 #if AP_RCPROTOCOL_SBUS_NI_ENABLED
152 case SBUS_NI:
153 #endif
154 #if AP_RCPROTOCOL_PPMSUM_ENABLED
155 case PPMSUM:
156 #endif
157 #if AP_RCPROTOCOL_FPORT_ENABLED
158 case FPORT:
159 #endif
160 #if AP_RCPROTOCOL_FPORT2_ENABLED
161 case FPORT2:
162 #endif
163 #if AP_RCPROTOCOL_CRSF_ENABLED
164 case CRSF:
165 #endif
166 #if AP_RCPROTOCOL_GHST_ENABLED
167 case GHST:
168 #endif
169 return true;
170 #if AP_RCPROTOCOL_IBUS_ENABLED
171 case IBUS:
172 #endif
173 #if AP_RCPROTOCOL_SUMD_ENABLED
174 case SUMD:
175 #endif
176 #if AP_RCPROTOCOL_SRXL_ENABLED
177 case SRXL:
178 #endif
179 #if AP_RCPROTOCOL_SRXL2_ENABLED
180 case SRXL2:
181 #endif
182 #if AP_RCPROTOCOL_ST24_ENABLED
183 case ST24:
184 #endif
185 #if AP_RCPROTOCOL_DRONECAN_ENABLED
186 case DRONECAN:
187 #endif
188 #if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
189 case MAVLINK_RADIO:
190 #endif
191 #if AP_RCPROTOCOL_JOYSTICK_SFML_ENABLED
192 case JOYSTICK_SFML:
193 #endif
194 #if AP_RCPROTOCOL_UDP_ENABLED
195 case UDP:
196 #endif
197 #if AP_RCPROTOCOL_FDM_ENABLED
198 case FDM:
199 #endif
200 #if AP_RCPROTOCOL_RADIO_ENABLED
201 case RADIO:
202 #endif
203 case NONE:
204 return false;
206 return false;
208 #if !defined(__clang__)
209 #pragma GCC diagnostic pop
210 #endif
212 uint8_t num_channels();
213 uint16_t read(uint8_t chan);
214 void read(uint16_t *pwm, uint8_t n);
215 bool new_input();
216 void start_bind(void);
217 int16_t get_RSSI(void) const;
218 int16_t get_rx_link_quality(void) const;
220 // return protocol name as a string
221 const char *protocol_name(void) const;
223 // return detected protocol
224 enum rcprotocol_t protocol_detected(void) const {
225 return _detected_protocol;
228 // add a UART for RCIN
229 void add_uart(AP_HAL::UARTDriver* uart);
230 bool has_uart() const { return added.uart != nullptr; }
232 // set allowed RC protocols
233 void set_rc_protocols(uint32_t mask) {
234 rc_protocols_mask = mask;
237 class SerialConfig {
238 public:
239 void apply_to_uart(AP_HAL::UARTDriver *uart) const;
241 uint32_t baud;
242 uint8_t parity;
243 uint8_t stop_bits;
244 bool invert_rx;
247 // return true if we are decoding a byte stream, instead of pulses
248 bool using_uart(void) const {
249 return _detected_with_bytes;
252 // handle mavlink radio
253 #if AP_RCPROTOCOL_MAVLINK_RADIO_ENABLED
254 void handle_radio_rc_channels(const mavlink_radio_rc_channels_t* packet);
255 #endif
257 private:
258 void check_added_uart(void);
260 // return true if a specific protocol is enabled
261 bool protocol_enabled(enum rcprotocol_t protocol) const;
263 // explicitly investigate a backend for data, as opposed to
264 // feeding the backend a byte (or pulse-train) at a time and
265 // having them make an "add_input" callback):
266 bool detect_async_protocol(rcprotocol_t protocol);
268 enum rcprotocol_t _detected_protocol = NONE;
269 uint16_t _disabled_for_pulses;
270 bool _detected_with_bytes;
271 AP_RCProtocol_Backend *backend[NONE];
272 bool _new_input;
273 uint32_t _last_input_ms;
274 bool _failsafe_active;
275 bool _valid_serial_prot;
277 // optional additional uart
278 struct {
279 AP_HAL::UARTDriver *uart;
280 bool opened;
281 uint32_t last_config_change_ms;
282 uint8_t config_num;
283 } added;
285 // allowed RC protocols mask (first bit means "all")
286 uint32_t rc_protocols_mask;
288 #endif // AP_RCPROTCOL_ENABLED
292 #if AP_RCPROTOCOL_ENABLED
293 namespace AP {
294 AP_RCProtocol &RC();
297 #include "AP_RCProtocol_Backend.h"
298 #endif // AP_RCProtocol_enabled