ardupilot/libraries/AP_HAL_Linux/RCInput_UDP.h
Lucas De Marchi 29d8586ea4 AP_HAL_Linux: RCInput_UDP: accept up to 16 channels
This allows more channels to be passed to RCInput_UDP protocol while
also allowing less than 8 channels - this is similar to the approach
used by SITL in which the packet size is used to figure out the number
of channels.
2020-05-03 00:07:52 -07:00

26 lines
444 B
C++

#pragma once
#include "RCInput.h"
#include <AP_HAL/utility/Socket.h>
#include "RCInput_UDP_Protocol.h"
#define RCINPUT_UDP_DEF_PORT 777
namespace Linux {
class RCInput_UDP : public RCInput
{
public:
RCInput_UDP();
void init() override;
void _timer_tick(void) override;
private:
SocketAPM _socket{true};
uint16_t _port;
struct rc_udp_packet_v3 _buf;
uint64_t _last_buf_ts;
uint16_t _last_buf_seq;
};
}