APM:Libraries
UARTDriver.cpp
Go to the documentation of this file.
1 #include "UARTDriver.h"
2 
3 #include <arpa/inet.h>
4 #include <assert.h>
5 #include <errno.h>
6 #include <fcntl.h>
7 #include <netinet/in.h>
8 #include <netinet/tcp.h>
9 #include <poll.h>
10 #include <stdio.h>
11 #include <stdlib.h>
12 #include <string.h>
13 #include <sys/ioctl.h>
14 #include <sys/socket.h>
15 #include <sys/stat.h>
16 #include <sys/types.h>
17 #include <termios.h>
18 #include <unistd.h>
19 
20 #include <AP_HAL/AP_HAL.h>
21 
22 #include "ConsoleDevice.h"
23 #include "TCPServerDevice.h"
24 #include "UARTDevice.h"
25 #include "UDPDevice.h"
26 
27 #include <GCS_MAVLink/GCS.h>
28 
29 extern const AP_HAL::HAL& hal;
30 
31 using namespace Linux;
32 
33 UARTDriver::UARTDriver(bool default_console) :
34  device_path(nullptr),
35  _packetise(false),
36  _device{new ConsoleDevice()}
37 {
38  if (default_console) {
39  _console = true;
40  }
41 }
42 
43 /*
44  set the tty device to use for this UART
45  */
46 void UARTDriver::set_device_path(const char *path)
47 {
48  device_path = path;
49 }
50 
51 /*
52  open the tty
53  */
54 void UARTDriver::begin(uint32_t b)
55 {
56  begin(b, 0, 0);
57 }
58 
59 void UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
60 {
61  if (!_initialised) {
62  if (device_path == nullptr && _console) {
63  _device = new ConsoleDevice();
64  } else {
65  if (device_path == nullptr) {
66  return;
67  }
68 
70 
71  if (!_device.get()) {
72  ::fprintf(stderr, "Argument is not valid. Fallback to console.\n"
73  "Launch with --help to see an example.\n");
74  _device = new ConsoleDevice();
75  }
76  }
77  }
78 
79  if (!_connected) {
80  _connected = _device->open();
81  _device->set_blocking(false);
82  }
83  _initialised = false;
84 
85  while (_in_timer) hal.scheduler->delay(1);
86 
87  _device->set_speed(b);
88 
89  _baudrate = b;
90 
91  _allocate_buffers(rxS, txS);
92 }
93 
94 void UARTDriver::_allocate_buffers(uint16_t rxS, uint16_t txS)
95 {
96  /* we have enough memory to have a larger transmit buffer for
97  * all ports. This means we don't get delays while waiting to
98  * write GPS config packets
99  */
100 
101  if (rxS < 8192) {
102  rxS = 8192;
103  }
104  if (txS < 32000) {
105  txS = 32000;
106  }
107 
108  if (_writebuf.set_size(txS) && _readbuf.set_size(rxS)) {
109  _initialised = true;
110  }
111 }
112 
114 {
115  _readbuf.set_size(0);
116  _writebuf.set_size(0);
117 }
118 
119 /*
120  Device path accepts the following syntaxes:
121  - /dev/ttyO1
122  - tcp:*:1243:wait
123  - udp:192.168.2.15:1243
124 */
126 {
127  struct stat st;
128 
129  if (stat(arg, &st) == 0 && S_ISCHR(st.st_mode)) {
130  return AP_HAL::OwnPtr<SerialDevice>(new UARTDevice(arg));
131  } else if (strncmp(arg, "tcp:", 4) != 0 &&
132  strncmp(arg, "udp:", 4) != 0 &&
133  strncmp(arg, "udpin:", 6)) {
134  return nullptr;
135  }
136 
137  char *devstr = strdup(arg);
138 
139  if (devstr == nullptr) {
140  return nullptr;
141  }
142 
143  char *saveptr = nullptr;
144  char *protocol, *ip, *port, *flag;
145 
146  protocol = strtok_r(devstr, ":", &saveptr);
147  ip = strtok_r(nullptr, ":", &saveptr);
148  port = strtok_r(nullptr, ":", &saveptr);
149  flag = strtok_r(nullptr, ":", &saveptr);
150 
151  if (ip == nullptr || port == nullptr) {
152  free(devstr);
153  return nullptr;
154  }
155 
156  if (_ip) {
157  free(_ip);
158  _ip = nullptr;
159  }
160 
161  if (_flag) {
162  free(_flag);
163  _flag = nullptr;
164  }
165 
166  _base_port = (uint16_t) atoi(port);
167  _ip = strdup(ip);
168 
169  /* Optional flag for TCP */
170  if (flag != nullptr) {
171  _flag = strdup(flag);
172  }
173 
174  AP_HAL::OwnPtr<SerialDevice> device = nullptr;
175 
176  if (strcmp(protocol, "udp") == 0 || strcmp(protocol, "udpin") == 0) {
177  bool bcast = (_flag && strcmp(_flag, "bcast") == 0);
178  _packetise = true;
179  if (strcmp(protocol, "udp") == 0) {
180  device = new UDPDevice(_ip, _base_port, bcast, false);
181  } else {
182  if (bcast) {
183  AP_HAL::panic("Can't combine udpin with bcast");
184  }
185  device = new UDPDevice(_ip, _base_port, false, true);
186 
187  }
188  } else {
189  bool wait = (_flag && strcmp(_flag, "wait") == 0);
190  device = new TCPServerDevice(_ip, _base_port, wait);
191  }
192 
193  free(devstr);
194  return device;
195 }
196 
197 /*
198  shutdown a UART
199  */
200 void UARTDriver::end()
201 {
202  _initialised = false;
203  _connected = false;
204 
205  while (_in_timer) {
206  hal.scheduler->delay(1);
207  }
208 
209  _device->close();
211 }
212 
213 
214 void UARTDriver::flush()
215 {
216  // we are not doing any buffering, so flush is a no-op
217 }
218 
219 
220 /*
221  return true if the UART is initialised
222  */
224 {
225  return _initialised;
226 }
227 
228 
229 /*
230  enable or disable blocking writes
231  */
232 void UARTDriver::set_blocking_writes(bool blocking)
233 {
234  _nonblocking_writes = !blocking;
235 }
236 
237 
238 /*
239  do we have any bytes pending transmission?
240  */
242 {
243  return (_writebuf.available() > 0);
244 }
245 
246 /*
247  return the number of bytes available to be read
248  */
249 uint32_t UARTDriver::available()
250 {
251  if (!_initialised) {
252  return 0;
253  }
254  return _readbuf.available();
255 }
256 
257 /*
258  how many bytes are available in the output buffer?
259  */
260 uint32_t UARTDriver::txspace()
261 {
262  if (!_initialised) {
263  return 0;
264  }
265  return _writebuf.space();
266 }
267 
268 int16_t UARTDriver::read()
269 {
270  if (!_initialised) {
271  return -1;
272  }
273 
274  uint8_t byte;
275  if (!_readbuf.read_byte(&byte)) {
276  return -1;
277  }
278 
279  return byte;
280 }
281 
282 /* Linux implementations of Print virtual methods */
283 size_t UARTDriver::write(uint8_t c)
284 {
285  if (!_initialised) {
286  return 0;
287  }
288 
289  while (_writebuf.space() == 0) {
290  if (_nonblocking_writes) {
291  return 0;
292  }
293  hal.scheduler->delay(1);
294  }
295  return _writebuf.write(&c, 1);
296 }
297 
298 /*
299  write size bytes to the write buffer
300  */
301 size_t UARTDriver::write(const uint8_t *buffer, size_t size)
302 {
303  if (!_initialised) {
304  return 0;
305  }
306  if (!_nonblocking_writes) {
307  /*
308  use the per-byte delay loop in write() above for blocking writes
309  */
310  size_t ret = 0;
311  while (size--) {
312  if (write(*buffer++) != 1) break;
313  ret++;
314  }
315  return ret;
316  }
317 
318  return _writebuf.write(buffer, size);
319 }
320 
321 /*
322  try writing n bytes, handling an unresponsive port
323  */
324 int UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
325 {
326  /*
327  allow for delayed connection. This allows ArduPilot to start
328  before a network interface is available.
329  */
330  if (!_connected) {
331  _connected = _device->open();
332  }
333  if (!_connected) {
334  return 0;
335  }
336 
337  return _device->write(buf, n);
338 }
339 
340 /*
341  try reading n bytes, handling an unresponsive port
342  */
343 int UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
344 {
345  return _device->read(buf, n);
346 }
347 
348 
349 /*
350  try to push out one lump of pending bytes
351  return true if progress is made
352  */
354 {
355  // write any pending bytes
356  uint32_t available_bytes = _writebuf.available();
357  uint16_t n = available_bytes;
358  int16_t b = _writebuf.peek(0);
359  if (_packetise && n > 0 &&
360  b != MAVLINK_STX_MAVLINK1 && b != MAVLINK_STX) {
361  /*
362  we have a non-mavlink packet at the start of the
363  buffer. Look ahead for a MAVLink start byte, up to 256 bytes
364  ahead
365  */
366  uint16_t limit = n>256?256:n;
367  uint16_t i;
368  for (i=0; i<limit; i++) {
369  b = _writebuf.peek(i);
370  if (b == MAVLINK_STX_MAVLINK1 || b == MAVLINK_STX) {
371  n = i;
372  break;
373  }
374  }
375  // if we didn't find a MAVLink marker then limit the send size to 256
376  if (i == limit) {
377  n = limit;
378  }
379  }
380  b = _writebuf.peek(0);
381  if (_packetise && n > 0 &&
382  (b == MAVLINK_STX_MAVLINK1 || b == MAVLINK_STX)) {
383  uint8_t min_length = (b == MAVLINK_STX_MAVLINK1)?8:12;
384  // this looks like a MAVLink packet - try to write on
385  // packet boundaries when possible
386  if (n < min_length) {
387  // we need to wait for more data to arrive
388  n = 0;
389  } else {
390  // the length of the packet is the 2nd byte, and mavlink
391  // packets have a 6 byte header plus 2 byte checksum,
392  // giving len+8 bytes
393  int16_t len = _writebuf.peek(1);
394  if (b == MAVLINK_STX) {
395  // check for signed packet with extra 13 bytes
396  int16_t incompat_flags = _writebuf.peek(2);
397  if (incompat_flags & MAVLINK_IFLAG_SIGNED) {
398  min_length += MAVLINK_SIGNATURE_BLOCK_LEN;
399  }
400  }
401  if (n < len+min_length) {
402  // we don't have a full packet yet
403  n = 0;
404  } else if (n > len+min_length) {
405  // send just 1 packet at a time (so MAVLink packets
406  // are aligned on UDP boundaries)
407  n = len+min_length;
408  }
409  }
410  }
411 
412  if (n > 0) {
413  int ret;
414 
415  if (_packetise) {
416  // keep as a single UDP packet
417  uint8_t tmpbuf[n];
418  _writebuf.peekbytes(tmpbuf, n);
419  ret = _write_fd(tmpbuf, n);
420  if (ret > 0)
421  _writebuf.advance(ret);
422  } else {
423  ByteBuffer::IoVec vec[2];
424  const auto n_vec = _writebuf.peekiovec(vec, n);
425  for (int i = 0; i < n_vec; i++) {
426  ret = _write_fd(vec[i].data, (uint16_t)vec[i].len);
427  if (ret < 0) {
428  break;
429  }
430  _writebuf.advance(ret);
431 
432  /* We wrote less than we asked for, stop */
433  if ((unsigned)ret != vec[i].len) {
434  break;
435  }
436  }
437  }
438  }
439 
440  return _writebuf.available() != available_bytes;
441 }
442 
443 /*
444  push any pending bytes to/from the serial port. This is called at
445  1kHz in the timer thread. Doing it this way reduces the system call
446  overhead in the main task enormously.
447  */
449 {
450  if (!_initialised) return;
451 
452  _in_timer = true;
453 
454  uint8_t num_send = 10;
455  while (num_send != 0 && _write_pending_bytes()) {
456  num_send--;
457  }
458 
459  // try to fill the read buffer
460  int ret;
461  ByteBuffer::IoVec vec[2];
462 
463  const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
464  for (int i = 0; i < n_vec; i++) {
465  ret = _read_fd(vec[i].data, vec[i].len);
466  if (ret < 0) {
467  break;
468  }
469  _readbuf.commit((unsigned)ret);
470 
471  // update receive timestamp
474 
475  /* stop reading as we read less than we asked for */
476  if ((unsigned)ret < vec[i].len) {
477  break;
478  }
479  }
480 
481  _in_timer = false;
482 }
483 
484 /*
485  return timestamp estimate in microseconds for when the start of
486  a nbytes packet arrived on the uart. This should be treated as a
487  time constraint, not an exact time. It is guaranteed that the
488  packet did not start being received after this time, but it
489  could have been in a system buffer before the returned time.
490 
491  This takes account of the baudrate of the link. For transports
492  that have no baudrate (such as USB) the time estimate may be
493  less accurate.
494 
495  A return value of zero means the HAL does not support this API
496 */
497 uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
498 {
499  uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
500  if (_baudrate > 0) {
501  // assume 10 bits per byte.
502  uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
503  last_receive_us -= transport_time_us;
504  }
505  return last_receive_us;
506 }
size_t write(uint8_t c)
uint32_t _baudrate
Definition: UARTDriver.h:73
AP_HAL::OwnPtr< SerialDevice > _parseDevicePath(const char *arg)
Definition: UARTDriver.cpp:125
void set_blocking_writes(bool blocking)
uint32_t available(void) const
Definition: RingBuffer.cpp:37
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
virtual void set_blocking(bool blocking)=0
void begin(uint32_t b)
volatile bool _in_timer
Definition: UARTDriver.h:71
Interface definition for the various Ground Control System.
uint16_t _base_port
Definition: UARTDriver.h:72
bool _write_pending_bytes(void)
Definition: UARTDriver.cpp:353
virtual bool close()=0
virtual bool open()=0
bool commit(uint32_t len)
Definition: RingBuffer.cpp:202
virtual ssize_t read(uint8_t *buf, uint16_t n)=0
uint32_t space(void) const
Definition: RingBuffer.cpp:54
ByteBuffer _writebuf
Definition: UARTDriver.h:96
void _allocate_buffers(uint16_t rxS, uint16_t txS)
Definition: UARTDriver.cpp:94
virtual ssize_t write(const uint8_t *buf, uint16_t n)=0
const char * device_path
Definition: UARTDriver.h:90
virtual void delay(uint16_t ms)=0
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:87
virtual void _timer_tick(void) override
void set_device_path(const char *path)
Definition: UARTDriver.cpp:46
bool advance(uint32_t n)
Definition: RingBuffer.cpp:116
uint64_t _receive_timestamp[2]
Definition: UARTDriver.h:86
bool _nonblocking_writes
Definition: UARTDriver.h:69
bool set_size(uint32_t size)
Definition: RingBuffer.cpp:20
uint64_t receive_time_constraint_us(uint16_t nbytes) override
uint32_t peekbytes(uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:157
uint64_t micros64()
Definition: system.cpp:162
volatile bool _initialised
Definition: UARTDriver.h:91
uint8_t byte
Definition: compat.h:8
uint32_t txspace() override
uint32_t available() override
virtual int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:324
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
virtual int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:343
uint8_t peekiovec(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:125
void free(void *ptr)
Definition: malloc.c:81
int stat(const char *name, struct stat *buf)
Display struct stat, from POSIX stat(0 or fstat(), in ASCII. NOT POSIX.
Definition: posix.c:1319
virtual void set_speed(uint32_t speed)=0
int16_t peek(uint32_t ofs) const
Definition: RingBuffer.cpp:246
AP_HAL::OwnPtr< SerialDevice > _device
Definition: UARTDriver.h:68
int16_t read() override
int fprintf(FILE *fp, const char *fmt,...)
fprintf character write function
Definition: posix.c:2539
void uint32_t uint32_t uint32_t flag
Definition: systick.h:80
void _deallocate_buffers()
Definition: UARTDriver.cpp:113
uint8_t reserve(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:171
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
bool read_byte(uint8_t *data)
Definition: RingBuffer.cpp:219
T * get() const
Definition: OwnPtr.h:88
ByteBuffer _readbuf
Definition: UARTDriver.h:95