mirror of
https://github.com/ArduPilot/ardupilot
synced 2025-01-02 14:13:42 -04:00
29d8586ea4
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.
26 lines
444 B
C++
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;
|
|
};
|
|
|
|
}
|