APM:Libraries
RCInput_SBUS.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 SBUS input in Linux board using a UART. Note
17  that it relies on kernel support for 100kbaud and on a uart inverted
18  in hardware
19  */
20 
21 #include <AP_HAL/AP_HAL.h>
22 
23 #if CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_DISCO || \
24  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_AERO || \
25  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_OCPOC_ZYNQ || \
26  CONFIG_HAL_BOARD_SUBTYPE == HAL_BOARD_SUBTYPE_LINUX_RST_ZYNQ
27 #include "RCInput_SBUS.h"
28 #include <stdio.h>
29 #include <fcntl.h>
30 #include <unistd.h>
31 #include <errno.h>
32 #include <sys/ioctl.h>
33 #include <asm/termbits.h>
34 
35 extern const AP_HAL::HAL& hal;
36 
37 using namespace Linux;
38 
39 #define SBUS_FRAME_SIZE 25
40 
42 {
43  fd = open(device_path, O_RDWR | O_NONBLOCK | O_CLOEXEC);
44  if (fd != -1) {
45  printf("Opened SBUS input %s fd=%d\n", device_path, (int)fd);
46  fflush(stdout);
47  struct termios2 tio {};
48 
49  if (ioctl(fd, TCGETS2, &tio) != 0) {
50  close(fd);
51  fd = -1;
52  return;
53  }
54  tio.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | ISTRIP | INLCR
55  | IGNCR | ICRNL | IXON);
56  tio.c_iflag |= (INPCK | IGNPAR);
57  tio.c_oflag &= ~OPOST;
58  tio.c_lflag &= ~(ECHO | ECHONL | ICANON | ISIG | IEXTEN);
59  tio.c_cflag &= ~(CSIZE | CRTSCTS | PARODD | CBAUD);
60  // use BOTHER to specify speed directly in c_[io]speed member
61  tio.c_cflag |= (CS8 | CSTOPB | CLOCAL | PARENB | BOTHER | CREAD);
62  tio.c_ispeed = 100000;
63  tio.c_ospeed = 100000;
64  // see select() comment below
65  tio.c_cc[VMIN] = SBUS_FRAME_SIZE;
66  tio.c_cc[VTIME] = 0;
67  if (ioctl(fd, TCSETS2, &tio) != 0) {
68  close(fd);
69  fd = -1;
70  return;
71  }
72  }
73 }
74 
75 void RCInput_SBUS::set_device_path(const char *path)
76 {
77  device_path = path;
78  printf("Set SBUS device path %s\n", path);
79 }
80 
81 #define SBUS_DEBUG_LOG 0
82 #define SBUS_CAUSE_CORRUPTION 0
83 
85 {
86  if (fd == -1) {
87  return;
88  }
89 
90  // read up to 10 frames at a time
91  uint8_t bytes[SBUS_FRAME_SIZE*10];
92  int nread;
93 
94  fd_set fds;
95  struct timeval tv;
96 
97  FD_ZERO(&fds);
98  FD_SET(fd, &fds);
99 
100  tv.tv_sec = 0;
101  tv.tv_usec = 0;
102 
103  // as VMIN is SBUS_FRAME_SIZE the select won't return unless there is
104  // at least SBUS_FRAME_SIZE bytes available
105  if (select(fd+1, &fds, nullptr, nullptr, &tv) != 1) {
106  return;
107  }
108 
109 #if SBUS_DEBUG_LOG
110  static int logfd = -1;
111  if (logfd == -1) {
112  logfd = open("sbus.log", O_WRONLY|O_CREAT|O_TRUNC|O_CLOEXEC, 0644);
113  }
114 #endif
115 
116 #if SBUS_CAUSE_CORRUPTION
117  // deliberately lose bytes from the port
118  static unsigned corruption_counter;
119  if (corruption_counter++ % 1000 == 0) {
120  uint8_t nn = corruption_counter/1000;
121  int n2 = ::read(fd, bytes, nn);
122  dprintf(logfd, "throw %u\n", (unsigned)n2);
123  }
124 #endif
125 
126  // cope with there being a large number of pending bytes at
127  // the start
128  do {
129  nread = ::read(fd, bytes, sizeof(bytes));
130  } while (nread == sizeof(bytes));
131 
132  if (nread % SBUS_FRAME_SIZE != 0) {
133  /*
134  SBUS frames are 25 bytes long, and always start with
135  0x0f, but there is no other framing information to
136  prevent us getting out of sync. All we have are the
137  timing guarantees
138 
139  In this case we have read a partial frame, or lost some
140  bytes. A 25 bytes frame at 100000 baud takes 2.5ms. By
141  delaying 3.5ms here we will get any remaining bytes for
142  this frame. We shouldn't get the start of the next frame
143  as frames happen at most every 7ms
144 
145  This strategy allows us to resync even if we lose
146  bytes. It assumes an interframe gap of more than
147  3.5ms. If SBUS is run at very high rate (like 300Hz)
148  then this won't work
149  */
150  hal.scheduler->delay_microseconds(3500);
151  int n2 = ::read(fd, bytes+nread, sizeof(bytes)-nread);
152  if (n2 > 0) {
153  nread += n2;
154  }
155  }
156  if (nread % SBUS_FRAME_SIZE != 0) {
157  // if we don't have a multuple of 25 then throw away the lot
158 #if SBUS_DEBUG_LOG
159  dprintf(logfd, "discard %u\n", (unsigned)nread);
160 #endif
161  return;
162  }
163  if (nread <= 0) {
164  return;
165  }
166 #if SBUS_DEBUG_LOG
167  if (logfd != -1) {
168  dprintf(logfd, "%06u %u: ", (unsigned)AP_HAL::millis(), (unsigned)nread);
169  for (uint8_t i=0; i<nread; i++) {
170  dprintf(logfd, "%02x ", (unsigned)bytes[i]);
171  }
172  dprintf(logfd, "\n");
173  }
174 #endif
175  // only process the last SBUS_FRAME_SIZE bytes. Only the latest
176  // frame matters
178 }
179 #endif // CONFIG_HAL_BOARD_SUBTYPE
180 
#define SBUS_FRAME_SIZE
int printf(const char *fmt,...)
Definition: stdio.c:113
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
void init() override
const char * device_path
Definition: RCInput_SBUS.h:37
void set_device_path(const char *path)
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
const AP_HAL::HAL & hal
-*- tab-width: 4; Mode: C++; c-basic-offset: 4; indent-tabs-mode: nil -*-
Definition: AC_PID_test.cpp:14
void _timer_tick(void) override
virtual void delay_microseconds(uint16_t us)=0
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
uint16_t bytes[25]
Definition: RCInput.h:76
void add_sbus_input(const uint8_t *bytes, size_t nbytes)
Definition: RCInput.cpp:511
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114