APM:Libraries
RCInput_UART.cpp
Go to the documentation of this file.
1 #include "RCInput_UART.h"
2 
3 #include <errno.h>
4 #include <fcntl.h>
5 #include <inttypes.h>
6 #include <stdio.h>
7 #include <stdlib.h>
8 #include <string.h>
9 #include <termios.h>
10 #include <unistd.h>
11 
12 #include <AP_HAL/AP_HAL.h>
13 
14 #define MAGIC 0x55AA
15 
16 using namespace Linux;
17 
18 RCInput_UART::RCInput_UART(const char *path)
19 {
20  _fd = open(path, O_RDONLY|O_NOCTTY|O_NONBLOCK|O_NDELAY|O_CLOEXEC);
21  if (_fd < 0) {
22  AP_HAL::panic("RCInput_UART: Error opening '%s': %s",
23  path, strerror(errno));
24  }
25 }
26 
28 {
29  close(_fd);
30 }
31 
33 {
34  struct termios options;
35 
36  tcgetattr(_fd, &options);
37 
38  cfsetispeed(&options, B115200);
39  cfsetospeed(&options, B115200);
40 
41  options.c_cflag &= ~(PARENB|CSTOPB|CSIZE);
42  options.c_cflag |= CS8;
43 
44  options.c_lflag &= ~(ICANON|ECHO|ECHOE|ISIG);
45  options.c_iflag &= ~(IXON|IXOFF|IXANY);
46  options.c_oflag &= ~OPOST;
47 
48  if (tcsetattr(_fd, TCSANOW, &options) != 0) {
49  AP_HAL::panic("RCInput_UART: error configuring device: %s",
50  strerror(errno));
51  }
52 
53  tcflush(_fd, TCIOFLUSH);
54 
55  _pdata = (uint8_t *)&_data;
56  _remain = sizeof(_data);
57 }
58 
60 {
61  ssize_t n;
62 
63  if ((n = ::read(_fd, _pdata, _remain)) <= 0)
64  return;
65 
66  _remain -= n;
67  _pdata += n;
68 
69  if (_remain != 0)
70  return;
71 
72  if (_data.magic != MAGIC) {
73  /* try to find the magic number and move
74  * it to the beginning of our buffer */
75  uint16_t magic = MAGIC;
76 
77  _pdata = (uint8_t *)memmem(&_data, sizeof(_data), &magic, sizeof(magic));
78 
79  if (!_pdata)
80  _pdata = (uint8_t *)&_data + sizeof(_data) - 1;
81 
82  _remain = _pdata - (uint8_t *)&_data;
83  n = sizeof(_data) - _remain;
84  memmove(&_data, _pdata, n);
85  _pdata = (uint8_t *)&_data + n;
86  return;
87  }
88 
90  _pdata = (uint8_t *)&_data;
91  _remain = sizeof(_data);
92 }
void init() override
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
uint16_t values[CHANNELS]
Definition: RCInput_UART.h:27
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
struct Linux::RCInput_UART::PACKED _data
#define MAGIC
void _timer_tick(void) override
RCInput_UART(const char *path)
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
uint16_t read(uint8_t ch)
Definition: RCInput.cpp:51
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void _update_periods(uint16_t *periods, uint8_t len)
Definition: RCInput.cpp:333
#define CHANNELS
Definition: RCInput_UART.h:8