RCInput_UDP.cpp 1.2 KB

1234567891011121314151617181920212223242526272829303132333435363738394041424344454647484950515253
  1. #include <stdio.h>
  2. #include <AP_HAL/AP_HAL.h>
  3. #include "RCInput_UDP.h"
  4. extern const AP_HAL::HAL& hal;
  5. using namespace Linux;
  6. RCInput_UDP::RCInput_UDP() :
  7. _port(0),
  8. _last_buf_ts(0),
  9. _last_buf_seq(0)
  10. {}
  11. void RCInput_UDP::init()
  12. {
  13. _port = RCINPUT_UDP_DEF_PORT;
  14. if(!_socket.bind("0.0.0.0", _port)) {
  15. hal.console->printf("failed to bind UDP socket\n");
  16. }
  17. _socket.set_blocking(false);
  18. return;
  19. }
  20. void RCInput_UDP::_timer_tick(void)
  21. {
  22. uint64_t delay;
  23. uint16_t seq_inc;
  24. /* Read from udp */
  25. while (_socket.recv(&_buf, sizeof(_buf), 10) == sizeof(_buf)) {
  26. if (_buf.version != RCINPUT_UDP_VERSION) {
  27. hal.console->printf("bad protocol version for UDP RCInput\n");
  28. return;
  29. }
  30. if (_last_buf_ts != 0 &&
  31. (delay = _buf.timestamp_us - _last_buf_ts) > 100000) {
  32. hal.console->printf("no rc cmds received for %llu\n", (unsigned long long)delay);
  33. }
  34. _last_buf_ts = _buf.timestamp_us;
  35. if ((seq_inc = _buf.sequence - _last_buf_seq) > 10) {
  36. hal.console->printf("gap in rc cmds : %u\n", seq_inc);
  37. }
  38. _last_buf_seq = _buf.sequence;
  39. _update_periods(_buf.pwms, RCINPUT_UDP_NUM_CHANNELS);
  40. }
  41. }