APM:Libraries
RCInput_SoloLink.cpp
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2017 Intel Corporation. All rights reserved.
3  *
4  * This file is free software: you can redistribute it and/or modify it
5  * under the terms of the GNU General Public License as published by the
6  * Free Software Foundation, either version 3 of the License, or
7  * (at your option) any later version.
8  *
9  * This file is distributed in the hope that it will be useful, but
10  * WITHOUT ANY WARRANTY; without even the implied warranty of
11  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.
12  * See the GNU General Public License for more details.
13  *
14  * You should have received a copy of the GNU General Public License along
15  * with this program. If not, see <http://www.gnu.org/licenses/>.
16  */
17 #include "RCInput_SoloLink.h"
18 
19 #include <errno.h>
20 #include <inttypes.h>
21 #include <stdio.h>
22 
23 #include <AP_HAL/AP_HAL.h>
24 
25 #define DEBUG 0
26 #if DEBUG
27 #define debug(fmt, args...) ::printf(fmt "\n", ##args)
28 #else
29 #define debug(fmt, args...)
30 #endif
31 
32 extern const AP_HAL::HAL& hal;
33 
34 using namespace Linux;
35 
37 {
38  memset(&_packet, 0, sizeof(_packet));
39 }
40 
42 {
43  if (!_socket.bind("0.0.0.0", PORT)) {
44  AP_HAL::panic("failed to bind UDP socket");
45  }
46 
47  // timeout is handled by poll() in SocketAPM
48  _socket.set_blocking(true);
49 
50  return;
51 }
52 
54 {
55  if (len < (ssize_t) sizeof(_packet)) {
56  hal.console->printf("RCInput: Packet too small (%zd), doesn't contain full frame\n",
57  len);
58  return false;
59  }
60 
61  uint64_t now_usec = AP_HAL::micros64();
62  uint64_t delay = now_usec - _last_usec;
63 
64  if (_last_usec != 0 && delay > 40000) {
65  debug("RCInput: no rc cmds received for %llu\n", (unsigned long long)delay);
66  }
67  _last_usec = now_usec;
68 
69  uint16_t seq = le16toh(_packet.seq);
70  if (seq - _last_seq > 1) {
71  debug("RCInput: gap in rc cmds : %u\n", seq - _last_seq);
72  }
73  _last_seq = seq;
74 
75  return true;
76 }
77 
78 /* TODO: this should be a PollerThread or at least stop using a SchedThread */
80 {
81  do {
82  uint16_t channels[8];
83  ssize_t r;
84 
85  r = _socket.recv(&_packet.buf, sizeof(_packet), 20);
86  if (r < 0) {
87  break;
88  }
89 
90  if (!_check_hdr(r)) {
91  break;
92  }
93 
94  channels[0] = le16toh(_packet.channel[1]);
95  channels[1] = le16toh(_packet.channel[2]);
96  channels[2] = le16toh(_packet.channel[0]);
97 
98  for (unsigned int i = 3; i < 8; i++) {
99  channels[i] = le16toh(_packet.channel[i]);
100  }
101 
102 
103 
104  _update_periods(channels, 8);
105  } while (true);
106 }
AP_HAL::UARTDriver * console
Definition: HAL.h:110
void delay(uint32_t ms)
Definition: system.cpp:91
static uint16_t channels[SRXL_MAX_CHANNELS]
Definition: srxl.cpp:59
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint64_t micros64()
Definition: system.cpp:162
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
static uint16_t le16toh(le16_t value)
Definition: sparse-endian.h:79
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333