2016-05-17 23:26:57 -03:00
|
|
|
#include <stdio.h>
|
|
|
|
|
2015-09-04 13:37:09 -03:00
|
|
|
#include <AP_HAL/AP_HAL.h>
|
|
|
|
|
|
|
|
#include "RCInput_UDP.h"
|
|
|
|
|
|
|
|
extern const AP_HAL::HAL& hal;
|
|
|
|
|
|
|
|
using namespace Linux;
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
RCInput_UDP::RCInput_UDP() :
|
2015-09-04 13:37:09 -03:00
|
|
|
_port(0),
|
|
|
|
_last_buf_ts(0),
|
|
|
|
_last_buf_seq(0)
|
|
|
|
{}
|
|
|
|
|
2015-12-02 11:14:20 -04:00
|
|
|
void RCInput_UDP::init()
|
2015-09-04 13:37:09 -03:00
|
|
|
{
|
|
|
|
_port = RCINPUT_UDP_DEF_PORT;
|
|
|
|
if(!_socket.bind("0.0.0.0", _port)) {
|
|
|
|
hal.console->printf("failed to bind UDP socket\n");
|
|
|
|
}
|
|
|
|
|
|
|
|
_socket.set_blocking(false);
|
|
|
|
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
|
2015-10-20 18:13:25 -03:00
|
|
|
void RCInput_UDP::_timer_tick(void)
|
2015-09-04 13:37:09 -03:00
|
|
|
{
|
|
|
|
uint64_t delay;
|
|
|
|
uint16_t seq_inc;
|
|
|
|
|
|
|
|
/* Read from udp */
|
|
|
|
while (_socket.recv(&_buf, sizeof(_buf), 10) == sizeof(_buf)) {
|
|
|
|
if (_buf.version != RCINPUT_UDP_VERSION) {
|
|
|
|
hal.console->printf("bad protocol version for UDP RCInput\n");
|
|
|
|
return;
|
|
|
|
}
|
|
|
|
if (_last_buf_ts != 0 &&
|
|
|
|
(delay = _buf.timestamp_us - _last_buf_ts) > 100000) {
|
2015-09-23 17:24:25 -03:00
|
|
|
hal.console->printf("no rc cmds received for %llu\n", (unsigned long long)delay);
|
2015-09-04 13:37:09 -03:00
|
|
|
}
|
|
|
|
_last_buf_ts = _buf.timestamp_us;
|
|
|
|
|
|
|
|
if ((seq_inc = _buf.sequence - _last_buf_seq) > 10) {
|
|
|
|
hal.console->printf("gap in rc cmds : %u\n", seq_inc);
|
|
|
|
}
|
|
|
|
_last_buf_seq = _buf.sequence;
|
|
|
|
|
|
|
|
_update_periods(_buf.pwms, RCINPUT_UDP_NUM_CHANNELS);
|
|
|
|
}
|
|
|
|
}
|