2016-02-17 21:25:26 -04:00
|
|
|
#pragma once
|
2015-09-04 13:37:09 -03:00
|
|
|
|
|
|
|
#include "RCInput.h"
|
|
|
|
#include <AP_HAL/utility/Socket.h>
|
|
|
|
#include "RCInput_UDP_Protocol.h"
|
|
|
|
|
|
|
|
#define RCINPUT_UDP_DEF_PORT 777
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
class Linux::RCInput_UDP : public Linux::RCInput
|
2015-09-04 13:37:09 -03:00
|
|
|
{
|
|
|
|
public:
|
2015-10-20 18:13:25 -03:00
|
|
|
RCInput_UDP();
|
2015-12-02 11:14:20 -04:00
|
|
|
void init();
|
2015-09-04 13:37:09 -03:00
|
|
|
void _timer_tick(void);
|
|
|
|
private:
|
|
|
|
SocketAPM _socket{true};
|
|
|
|
uint16_t _port;
|
|
|
|
struct rc_udp_packet _buf;
|
|
|
|
uint64_t _last_buf_ts;
|
|
|
|
uint16_t _last_buf_seq;
|
|
|
|
};
|