3 #include "AP_RCProtocol_config.h"
5 #if AP_RCPROTOCOL_UDP_ENABLED
8 * Reads fixed-length packets containing either 8 or 16 2-byte values,
9 * and interprets them as RC input.
12 #include "AP_RCProtocol_Backend.h"
14 #include <AP_Common/missing/endian.h>
15 #include <AP_HAL/utility/Socket_native.h>
17 class AP_RCProtocol_UDP
: public AP_RCProtocol_Backend
{
20 using AP_RCProtocol_Backend::AP_RCProtocol_Backend
;
22 void update() override
;
24 #if AP_RCPROTOCOL_FDM_ENABLED
25 void set_fdm_backend(class AP_RCProtocol_FDM
*_fdm_backend
) {
26 fdm_backend
= _fdm_backend
;
35 uint32_t last_input_ms
;
37 void read_all_socket_input(void);
38 SocketAPM_native rc_in
{true}; // "true" means "datagram"
40 // these are the values that will be fed into the autopilot.
41 // Packets we receive usually only contain a subset of channel
42 // values to insert into here:
43 uint16_t pwm_input
[16];
46 void set_default_pwm_input_values();
48 #if AP_RCPROTOCOL_FDM_ENABLED
49 AP_RCProtocol_FDM
*fdm_backend
;
54 #endif // AP_RCPROTOCOL_UDP_ENABLED