APM:Libraries
UARTDevice.cpp
Go to the documentation of this file.
1 #include "UARTDevice.h"
2 
3 #include <errno.h>
4 #include <fcntl.h>
5 #include <poll.h>
6 #include <stdio.h>
7 #include <termios.h>
8 #include <unistd.h>
9 
10 #include <AP_HAL/AP_HAL.h>
11 
12 UARTDevice::UARTDevice(const char *device_path):
13  _device_path(device_path)
14 {
15 }
16 
18 {
19 }
20 
22 {
23  if (_fd != -1) {
24  if (::close(_fd) < 0) {
25  return false;
26  }
27  }
28 
29  _fd = -1;
30 
31  return true;
32 }
33 
35 {
36  _fd = ::open(_device_path, O_RDWR | O_CLOEXEC | O_NOCTTY);
37 
38  if (_fd < 0) {
39  ::fprintf(stderr, "Failed to open UART device %s - %s\n",
41  return false;
42  }
43 
44  _disable_crlf();
45 
46  return true;
47 }
48 
49 ssize_t UARTDevice::read(uint8_t *buf, uint16_t n)
50 {
51  return ::read(_fd, buf, n);
52 }
53 
54 ssize_t UARTDevice::write(const uint8_t *buf, uint16_t n)
55 {
56  struct pollfd fds;
57  fds.fd = _fd;
58  fds.events = POLLOUT;
59  fds.revents = 0;
60 
61  int ret = 0;
62 
63  if (poll(&fds, 1, 0) == 1) {
64  ret = ::write(_fd, buf, n);
65  }
66 
67  return ret;
68 }
69 
70 void UARTDevice::set_blocking(bool blocking)
71 {
72  int flags = fcntl(_fd, F_GETFL, 0);
73 
74  if (blocking) {
75  flags = flags & ~O_NONBLOCK;
76  } else {
77  flags = flags | O_NONBLOCK;
78  }
79 
80  if (fcntl(_fd, F_SETFL, flags) < 0) {
81  ::fprintf(stderr, "Failed to make UART nonblocking %s - %s\n",
83  }
84 
85 }
86 
88 {
89  struct termios t;
90  memset(&t, 0, sizeof(t));
91 
92  tcgetattr(_fd, &t);
93 
94  // disable LF -> CR/LF
95  t.c_iflag &= ~(BRKINT | ICRNL | IMAXBEL | IXON | IXOFF);
96  t.c_oflag &= ~(OPOST | ONLCR);
97  t.c_lflag &= ~(ISIG | ICANON | IEXTEN | ECHO | ECHOE | ECHOK | ECHOCTL | ECHOKE);
98  t.c_cc[VMIN] = 0;
99 
100  tcsetattr(_fd, TCSANOW, &t);
101 }
102 
103 void UARTDevice::set_speed(uint32_t baudrate)
104 {
105  struct termios t;
106  memset(&t, 0, sizeof(t));
107 
108  tcgetattr(_fd, &t);
109  cfsetspeed(&t, baudrate);
110  tcsetattr(_fd, TCSANOW, &t);
111 }
112 
114 {
115  struct termios t;
116 
117  if (_flow_control == flow_control_setting) {
118  return;
119  }
120 
121  tcgetattr(_fd, &t);
122 
123  if (flow_control_setting != AP_HAL::UARTDriver::FLOW_CONTROL_DISABLE) {
124  t.c_cflag |= CRTSCTS;
125  } else {
126  t.c_cflag &= ~CRTSCTS;
127  }
128 
129  tcsetattr(_fd, TCSANOW, &t);
130 
131  _flow_control = flow_control_setting;
132 }
virtual void set_speed(uint32_t speed) override
Definition: UARTDevice.cpp:103
AP_HAL::UARTDriver::flow_control _flow_control
Definition: UARTDevice.h:25
virtual ssize_t read(uint8_t *buf, uint16_t n) override
Definition: UARTDevice.cpp:49
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
virtual void set_blocking(bool blocking) override
Definition: UARTDevice.cpp:70
virtual ssize_t write(const uint8_t *buf, uint16_t n) override
Definition: UARTDevice.cpp:54
void _disable_crlf()
Definition: UARTDevice.cpp:87
const char * _device_path
Definition: UARTDevice.h:28
ssize_t read(int fd, void *buf, size_t count)
POSIX read count bytes from *buf to fileno fd.
Definition: posix.c:995
virtual void set_flow_control(enum AP_HAL::UARTDriver::flow_control flow_control_setting) override
Definition: UARTDevice.cpp:113
UARTDevice(const char *device_path)
Definition: UARTDevice.cpp:12
virtual bool close() override
Definition: UARTDevice.cpp:21
virtual ~UARTDevice()
Definition: UARTDevice.cpp:17
int errno
Note: fdevopen assigns stdin,stdout,stderr.
Definition: posix.c:118
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
virtual bool open() override
Definition: UARTDevice.cpp:34