APM:Libraries
RCInput_115200.cpp
Go to the documentation of this file.
1 /*
2  This program is free software: you can redistribute it and/or modify
3  it under the terms of the GNU General Public License as published by
4  the Free Software Foundation, either version 3 of the License, or
5  (at your option) any later version.
6 
7  This program is distributed in the hope that it will be useful,
8  but WITHOUT ANY WARRANTY; without even the implied warranty of
9  MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
10  GNU General Public License for more details.
11 
12  You should have received a copy of the GNU General Public License
13  along with this program. If not, see <http://www.gnu.org/licenses/>.
14  */
15 /*
16  this is a driver for R/C input protocols that use a 115200 baud
17  non-inverted 8-bit protocol. That includes:
18  - DSM
19  - SUMD
20  - ST24
21  */
22 
23 #include <AP_HAL/AP_HAL.h>
24 
25 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
26  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_BLUE
27 #include "RCInput_115200.h"
28 #include <stdio.h>
29 #include <fcntl.h>
30 #include <unistd.h>
31 #include <errno.h>
32 #include <sys/ioctl.h>
33 #include <termios.h>
34 
35 extern const AP_HAL::HAL& hal;
36 
37 using namespace Linux;
38 
40 {
41  fd = open(device_path, O_RDWR | O_NONBLOCK | O_CLOEXEC);
42  if (fd != -1) {
43  struct termios options;
44 
45  tcgetattr(fd, &options);
46 
47  cfsetispeed(&options, B115200);
48  cfsetospeed(&options, B115200);
49 
50  options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
51  options.c_cflag |= CS8;
52 
53  options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
54  options.c_iflag &= ~(IXON|IXOFF|IXANY);
55  options.c_oflag &= ~OPOST;
56 
57  if (tcsetattr(fd, TCSANOW, &options) != 0) {
58  AP_HAL::panic("RCInput_UART: error configuring device: %s",
59  strerror(errno));
60  }
61 
62  tcflush(fd, TCIOFLUSH);
63  }
64 }
65 
66 void RCInput_115200::set_device_path(const char *path)
67 {
68  device_path = path;
69 }
70 
72 {
73  if (fd == -1) {
74  return;
75  }
76 
77  // read up to 256 bytes at a time
78  uint8_t bytes[256];
79  int nread;
80 
81  fd_set fds;
82  struct timeval tv;
83 
84  FD_ZERO(&fds);
85  FD_SET(fd, &fds);
86 
87  tv.tv_sec = 0;
88  tv.tv_usec = 0;
89 
90  // check if any bytes are available
91  if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
92  return;
93  }
94 
95  // cope with there being a large number of pending bytes at
96  // the start and discard them
97  do {
98  nread = ::read(fd, bytes, sizeof(bytes));
99  } while (nread == sizeof(bytes));
100 
101  if (nread <= 0) {
102  return;
103  }
104  bool got_frame = false;
105 
106  if (decoder == DECODER_SYNC ||
107  decoder == DECODER_SRXL) {
108  // try srxl first as it has a 16 bit CRC
109  if (add_srxl_input(bytes, nread)) {
110  // lock immediately
112  got_frame = true;
113  }
114  }
115 
116  if (decoder == DECODER_SYNC ||
117  decoder == DECODER_SUMD) {
118  // SUMD also has a 16 bit CRC
119  if (add_sumd_input(bytes, nread)) {
120  // lock immediately
122  got_frame = true;
123  }
124  }
125 
126  if (decoder == DECODER_SYNC ||
127  decoder == DECODER_DSM) {
128  // process as DSM
129  if (add_dsm_input(bytes, nread)) {
130  dsm_count++;
131  if (dsm_count == 10) {
132  // we're confident
134  }
135  got_frame = true;
136  }
137  }
138 
139  if (decoder == DECODER_SYNC ||
140  decoder == DECODER_ST24) {
141  // process as st24
142  if (add_st24_input(bytes, nread)) {
143  st24_count++;
144  if (st24_count == 10) {
145  // we're confident
147  }
148  got_frame = true;
149  }
150  }
151 
152  uint32_t now = AP_HAL::millis();
153  if (got_frame) {
154  last_input_ms = now;
155  } else if (now - last_input_ms > 1000 && decoder != DECODER_SYNC) {
156  // start search again
158  dsm_count = 0;
159  st24_count = 0;
160  }
161 }
162 
163 #endif // CONFIG_HAL_BOARD_SUBTYPE
164 
void init() override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
bool add_st24_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:449
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
enum Decoders decoder
bool add_srxl_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:480
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
bool add_sumd_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:418
uint32_t millis()
Definition: system.cpp:157
const char * device_path
void _timer_tick(void) override
bool add_dsm_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:349
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
uint16_t bytes[25]
Definition: RCInput.h:76
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void set_device_path(const char *path)