APM:Libraries
RCInput_UDP.cpp
Go to the documentation of this file.
1 #include <stdio.h>
2 
3 #include <AP_HAL/AP_HAL.h>
4 
5 #include "RCInput_UDP.h"
6 
7 extern const AP_HAL::HAL& hal;
8 
9 using namespace Linux;
10 
12  _port(0),
13  _last_buf_ts(0),
14  _last_buf_seq(0)
15 {}
16 
18 {
20  if(!_socket.bind("0.0.0.0", _port)) {
21  hal.console->printf("failed to bind UDP socket\n");
22  }
23 
24  _socket.set_blocking(false);
25 
26  return;
27 }
28 
30 {
31  uint64_t delay;
32  uint16_t seq_inc;
33 
34  /* Read from udp */
35  while (_socket.recv(&_buf, sizeof(_buf), 10) == sizeof(_buf)) {
36  if (_buf.version != RCINPUT_UDP_VERSION) {
37  hal.console->printf("bad protocol version for UDP RCInput\n");
38  return;
39  }
40  if (_last_buf_ts != 0 &&
41  (delay = _buf.timestamp_us - _last_buf_ts) > 100000) {
42  hal.console->printf("no rc cmds received for %llu\n", (unsigned long long)delay);
43  }
44  _last_buf_ts = _buf.timestamp_us;
45 
46  if ((seq_inc = _buf.sequence - _last_buf_seq) > 10) {
47  hal.console->printf("gap in rc cmds : %u\n", seq_inc);
48  }
49  _last_buf_seq = _buf.sequence;
50 
52  }
53 }
SocketAPM _socket
Definition: RCInput_UDP.h:18
uint64_t _last_buf_ts
Definition: RCInput_UDP.h:21
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void delay(uint32_t ms)
Definition: system.cpp:91
struct rc_udp_packet _buf
Definition: RCInput_UDP.h:20
#define RCINPUT_UDP_DEF_PORT
Definition: RCInput_UDP.h:7
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void _timer_tick(void)
Definition: RCInput_UDP.cpp:29
#define RCINPUT_UDP_NUM_CHANNELS
uint16_t _last_buf_seq
Definition: RCInput_UDP.h:22
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
#define RCINPUT_UDP_VERSION
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333