APM:Libraries
UARTDriver.cpp
Go to the documentation of this file.
1 #include <AP_HAL/AP_HAL.h>
2 
3 #if CONFIG_HAL_BOARD == HAL_BOARD_PX4
4 #include "UARTDriver.h"
5 
6 #include <stdio.h>
7 #include <unistd.h>
8 #include <stdlib.h>
9 #include <errno.h>
10 #include <sys/ioctl.h>
11 #include <sys/types.h>
12 #include <sys/stat.h>
13 #include <fcntl.h>
14 #include <termios.h>
15 #include <drivers/drv_hrt.h>
16 #include <assert.h>
17 #include "GPIO.h"
18 
19 using namespace PX4;
20 
21 extern const AP_HAL::HAL& hal;
22 
23 PX4UARTDriver::PX4UARTDriver(const char *devpath, const char *perf_name) :
24  _devpath(devpath),
25  _fd(-1),
26  _baudrate(57600),
27  _initialised(false),
28  _in_timer(false),
29  _unbuffered_writes(false),
30  _perf_uart(perf_alloc(PC_ELAPSED, perf_name)),
31  _os_start_auto_space(-1),
32  _flow_control(FLOW_CONTROL_DISABLE)
33 {
34 }
35 
36 
37 extern const AP_HAL::HAL& hal;
38 
39 /*
40  this UART driver maps to a serial device in /dev
41  */
42 
43 void PX4UARTDriver::begin(uint32_t b, uint16_t rxS, uint16_t txS)
44 {
45  if (strcmp(_devpath, "/dev/null") == 0) {
46  // leave uninitialised
47  return;
48  }
49 
50  uint16_t min_tx_buffer = 1024;
51  uint16_t min_rx_buffer = 512;
52  if (strcmp(_devpath, "/dev/ttyACM0") == 0) {
53  _is_usb = true;
54  min_tx_buffer = 4096;
55  min_rx_buffer = 1024;
56  }
57  // on PX4 we have enough memory to have a larger transmit and
58  // receive buffer for all ports. This means we don't get delays
59  // while waiting to write GPS config packets
60  if (txS < min_tx_buffer) {
61  txS = min_tx_buffer;
62  }
63  if (rxS < min_rx_buffer) {
64  rxS = min_rx_buffer;
65  }
66 
67  /*
68  allocate the read buffer
69  we allocate buffers before we successfully open the device as we
70  want to allocate in the early stages of boot, and cause minimum
71  thrashing of the heap once we are up. The ttyACM0 driver may not
72  connect for some time after boot
73  */
74  if (rxS != _readbuf.get_size()) {
75  _initialised = false;
76  while (_in_timer) {
77  hal.scheduler->delay(1);
78  }
79 
80  _readbuf.set_size(rxS);
81  }
82 
83  if (b != 0) {
84  _baudrate = b;
85  }
86 
87  /*
88  allocate the write buffer
89  */
90  if (txS != _writebuf.get_size()) {
91  _initialised = false;
92  while (_in_timer) {
93  hal.scheduler->delay(1);
94  }
95  _writebuf.set_size(txS);
96  }
97 
98  if (_fd == -1) {
99  _fd = open(_devpath, O_RDWR);
100  if (_fd == -1) {
101  return;
102  }
103  }
104 
105  if (_baudrate != 0) {
106  // set the baud rate
107  struct termios t;
108  tcgetattr(_fd, &t);
109  cfsetspeed(&t, _baudrate);
110  // disable LF -> CR/LF
111  t.c_oflag &= ~ONLCR;
112  tcsetattr(_fd, TCSANOW, &t);
113 
114  // separately setup IFLOW if we can. We do this as a 2nd call
115  // as if the port has no RTS pin then the tcsetattr() call
116  // will fail, and if done as one call then it would fail to
117  // set the baudrate.
118  tcgetattr(_fd, &t);
119  t.c_cflag |= CRTS_IFLOW;
120  tcsetattr(_fd, TCSANOW, &t);
121  }
122 
123  if (_writebuf.get_size() && _readbuf.get_size() && _fd != -1) {
124  if (!_initialised) {
125  if (_is_usb) {
126  ((PX4GPIO *)hal.gpio)->set_usb_connected();
127  }
128  ::printf("initialised %s OK %u %u\n", _devpath,
129  (unsigned)_writebuf.get_size(), (unsigned)_readbuf.get_size());
130  }
131  _initialised = true;
132  }
133 }
134 
136 {
137  if (_fd == -1) {
138  return;
139  }
140  struct termios t;
141  tcgetattr(_fd, &t);
142  // we already enabled CRTS_IFLOW above, just enable output flow control
143  if (fcontrol != FLOW_CONTROL_DISABLE) {
144  t.c_cflag |= CRTSCTS;
145  } else {
146  t.c_cflag &= ~CRTSCTS;
147  }
148  tcsetattr(_fd, TCSANOW, &t);
149  if (fcontrol == FLOW_CONTROL_AUTO) {
150  // reset flow control auto state machine
151  _total_written = 0;
152  _first_write_time = 0;
153  }
154  _flow_control = fcontrol;
155 }
156 
158  if (_fd == -1) {
159  return;
160  }
161  struct termios t;
162  tcgetattr(_fd, &t);
163  if (v != 0) {
164  // enable parity
165  t.c_cflag |= PARENB;
166  if (v == 1) {
167  t.c_cflag |= PARODD;
168  } else {
169  t.c_cflag &= ~PARODD;
170  }
171  }
172  else {
173  // disable parity
174  t.c_cflag &= ~PARENB;
175  }
176  tcsetattr(_fd, TCSANOW, &t);
177 }
178 
180  if (_fd == -1) {
181  return;
182  }
183  struct termios t;
184  tcgetattr(_fd, &t);
185  if (n > 1) t.c_cflag |= CSTOPB;
186  else t.c_cflag &= ~CSTOPB;
187  tcsetattr(_fd, TCSANOW, &t);
188 }
189 
192  return _unbuffered_writes;
193 }
194 
195 void PX4UARTDriver::begin(uint32_t b)
196 {
197  begin(b, 0, 0);
198 }
199 
200 
201 /*
202  try to initialise the UART. This is used to cope with the way NuttX
203  handles /dev/ttyACM0 (the USB port). The port appears in /dev on
204  boot, but cannot be opened until a USB cable is connected and the
205  host starts the CDCACM communication.
206  */
208 {
209  if (_initialised) {
210  return;
211  }
212  if ((AP_HAL::millis() - _last_initialise_attempt_ms) < 2000) {
213  return;
214  }
217  begin(0);
218  }
219 }
220 
221 
223 {
224  _initialised = false;
225  while (_in_timer) hal.scheduler->delay(1);
226  if (_fd != -1) {
227  close(_fd);
228  _fd = -1;
229  }
230 
231  _readbuf.set_size(0);
232  _writebuf.set_size(0);
233 }
234 
236 
238 {
239  try_initialise();
240  return _initialised;
241 }
242 
244 {
245  _nonblocking_writes = !blocking;
246 }
247 
248 bool PX4UARTDriver::tx_pending() { return false; }
249 
250 /*
251  return number of bytes available to be read from the buffer
252  */
254 {
255  if (!_initialised) {
256  try_initialise();
257  return 0;
258  }
259 
260  return _readbuf.available();
261 }
262 
263 /*
264  return number of bytes that can be added to the write buffer
265  */
267 {
268  if (!_initialised) {
269  try_initialise();
270  return 0;
271  }
272 
273  return _writebuf.space();
274 }
275 
276 /*
277  read one byte from the read buffer
278  */
280 {
281  if (!_semaphore.take_nonblocking()) {
282  return -1;
283  }
284  if (!_initialised) {
285  try_initialise();
286  _semaphore.give();
287  return -1;
288  }
289 
290  uint8_t byte;
291  if (!_readbuf.read_byte(&byte)) {
292  _semaphore.give();
293  return -1;
294  }
295 
296  _semaphore.give();
297  return byte;
298 }
299 
300 /*
301  write one byte
302  */
303 size_t PX4UARTDriver::write(uint8_t c)
304 {
305  if (!_semaphore.take_nonblocking()) {
306  return -1;
307  }
308  if (!_initialised) {
309  try_initialise();
310  _semaphore.give();
311  return 0;
312  }
313 
314  if (_unbuffered_writes) {
315  // write one byte to the file descriptor
316  return _write_fd(&c, 1);
317  }
318 
319  while (_writebuf.space() == 0) {
320  if (_nonblocking_writes) {
321  _semaphore.give();
322  return 0;
323  }
324  _semaphore.give();
325  hal.scheduler->delay(1);
326  if (!_semaphore.take_nonblocking()) {
327  return -1;
328  }
329  }
330  size_t ret = _writebuf.write(&c, 1);
331  _semaphore.give();
332  return ret;
333 }
334 
335 /*
336  * write size bytes
337  */
338 size_t PX4UARTDriver::write(const uint8_t *buffer, size_t size)
339 {
340  if (!_semaphore.take_nonblocking()) {
341  return -1;
342  }
343  if (!_initialised) {
344  try_initialise();
345  _semaphore.give();
346  return 0;
347  }
348 
349  size_t ret = 0;
350 
351  if (!_nonblocking_writes) {
352  _semaphore.give();
353  /*
354  use the per-byte delay loop in write() above for blocking writes
355  */
356  while (size--) {
357  if (write(*buffer++) != 1) break;
358  ret++;
359  }
360  return ret;
361  }
362 
363  if (_unbuffered_writes) {
364  // write buffer straight to the file descriptor
365  ret = _write_fd(buffer, size);
366  } else {
367  ret = _writebuf.write(buffer, size);
368  }
369  _semaphore.give();
370  return ret;
371 }
372 
373 /*
374  try writing n bytes, handling an unresponsive port
375  */
376 int PX4UARTDriver::_write_fd(const uint8_t *buf, uint16_t n)
377 {
378  int ret = 0;
379 
380  // the FIONWRITE check is to cope with broken O_NONBLOCK behaviour
381  // in NuttX on ttyACM0
382 
383  // FIONWRITE is also used for auto flow control detection
384  // Assume output flow control is not working if:
385  // port is configured for auto flow control
386  // and this is not the first write since flow control turned on
387  // and no data has been removed from the buffer since flow control turned on
388  // and more than .5 seconds elapsed after writing a total of > 5 characters
389  //
390 
391  int nwrite = 0;
392 
393  if (ioctl(_fd, FIONWRITE, (unsigned long)&nwrite) == 0) {
395  if (_first_write_time == 0) {
396  if (_total_written == 0) {
397  // save the remaining buffer bytes for comparison next write
398  _os_start_auto_space = nwrite;
399  }
400  } else {
401  if (_os_start_auto_space - nwrite + 1 >= _total_written &&
402  (AP_HAL::micros64() - _first_write_time) > 500*1000UL) {
403  // it doesn't look like hw flow control is working
404  ::printf("disabling flow control on %s _total_written=%u\n",
405  _devpath, (unsigned)_total_written);
407  }
408  }
409  }
410  if (nwrite > n) {
411  nwrite = n;
412  }
413  if (nwrite > 0) {
414  ret = ::write(_fd, buf, nwrite);
415  }
416  }
417 
418  if (ret > 0) {
420  _total_written += ret;
421  if (! _first_write_time && _total_written > 5) {
423  }
424  return ret;
425  }
426 
427  if (AP_HAL::micros64() - _last_write_time > 2000 &&
430 
431  // we haven't done a successful write for 2ms, which means the
432  // port is running at less than 500 bytes/sec. Start
433  // discarding bytes, even if this is a blocking port. This
434  // prevents the ttyACM0 port blocking startup if the endpoint
435  // is not connected
436  return n;
437  }
438  return ret;
439 }
440 
441 /*
442  try reading n bytes, handling an unresponsive port
443  */
444 int PX4UARTDriver::_read_fd(uint8_t *buf, uint16_t n)
445 {
446  int ret = 0;
447 
448  // the FIONREAD check is to cope with broken O_NONBLOCK behaviour
449  // in NuttX on ttyACM0
450  int nread = 0;
451  if (ioctl(_fd, FIONREAD, (unsigned long)&nread) == 0) {
452  if (nread > n) {
453  nread = n;
454  }
455  if (nread > 0) {
456  ret = ::read(_fd, buf, nread);
457  }
458  }
459  if (ret > 0) {
460  _total_read += ret;
461  }
462  return ret;
463 }
464 
465 
466 /*
467  push any pending bytes to/from the serial port. This is called at
468  1kHz in the timer thread. Doing it this way reduces the system call
469  overhead in the main task enormously.
470  */
472 {
473  int ret;
474  uint32_t n;
475 
476  if (!_initialised) return;
477 
478  // don't try IO on a disconnected USB port
479  if (_is_usb && !hal.gpio->usb_connected()) {
480  return;
481  }
482 
483  _in_timer = true;
484 
485  // write any pending bytes
486  n = _writebuf.available();
487  if (n > 0) {
488  ByteBuffer::IoVec vec[2];
489  perf_begin(_perf_uart);
490  const auto n_vec = _writebuf.peekiovec(vec, n);
491  for (int i = 0; i < n_vec; i++) {
492  ret = _write_fd(vec[i].data, (uint16_t)vec[i].len);
493  if (ret < 0) {
494  break;
495  }
496  _writebuf.advance(ret);
497 
498  /* We wrote less than we asked for, stop */
499  if ((unsigned)ret != vec[i].len) {
500  break;
501  }
502  }
503  perf_end(_perf_uart);
504  }
505 
506  // try to fill the read buffer
507  ByteBuffer::IoVec vec[2];
508 
509  perf_begin(_perf_uart);
510  const auto n_vec = _readbuf.reserve(vec, _readbuf.space());
511  for (int i = 0; i < n_vec; i++) {
512  ret = _read_fd(vec[i].data, vec[i].len);
513  if (ret < 0) {
514  break;
515  }
516  _readbuf.commit((unsigned)ret);
517 
518  // update receive timestamp
521 
522  /* stop reading as we read less than we asked for */
523  if ((unsigned)ret < vec[i].len) {
524  break;
525  }
526  }
527  perf_end(_perf_uart);
528 
529  _in_timer = false;
530 }
531 
532 /*
533  return timestamp estimate in microseconds for when the start of
534  a nbytes packet arrived on the uart. This should be treated as a
535  time constraint, not an exact time. It is guaranteed that the
536  packet did not start being received after this time, but it
537  could have been in a system buffer before the returned time.
538 
539  This takes account of the baudrate of the link. For transports
540  that have no baudrate (such as USB) the time estimate may be
541  less accurate.
542 
543  A return value of zero means the HAL does not support this API
544 */
546 {
547  uint64_t last_receive_us = _receive_timestamp[_receive_timestamp_idx];
548  if (_baudrate > 0 && !_is_usb) {
549  // assume 10 bits per byte. For USB we assume zero transport delay
550  uint32_t transport_time_us = (1000000UL * 10UL / _baudrate) * (nbytes+available());
551  last_receive_us -= transport_time_us;
552  }
553  return last_receive_us;
554 }
555 
556 #endif
bool get_soft_armed() const
Definition: Util.h:15
bool _nonblocking_writes
Definition: UARTDriver.h:69
void configure_parity(uint8_t v)
Definition: UARTDriver.cpp:157
void try_initialise(void)
Definition: UARTDriver.cpp:207
uint32_t available() override
Definition: UARTDriver.cpp:253
uint64_t _receive_timestamp[2]
Definition: UARTDriver.h:92
uint32_t available(void) const
Definition: RingBuffer.cpp:37
PX4UARTDriver(const char *devpath, const char *perf_name)
Definition: UARTDriver.cpp:23
ByteBuffer _writebuf
Definition: UARTDriver.h:75
const char * _devpath
Definition: UARTDriver.h:63
#define on
Definition: Config.h:51
bool set_unbuffered_writes(bool on)
Definition: UARTDriver.cpp:190
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
bool take_nonblocking()
Definition: Semaphores.cpp:39
int16_t read() override
Definition: UARTDriver.cpp:279
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
void set_flow_control(enum flow_control flow_control)
Definition: UARTDriver.cpp:135
AP_HAL::Util * util
Definition: HAL.h:115
bool commit(uint32_t len)
Definition: RingBuffer.cpp:202
uint32_t _total_written
Definition: UARTDriver.h:88
virtual bool usb_connected(void)=0
uint32_t get_size(void) const
Definition: RingBuffer.h:42
uint32_t space(void) const
Definition: RingBuffer.cpp:54
uint32_t _baudrate
Definition: UARTDriver.h:65
virtual void delay(uint16_t ms)=0
int _read_fd(uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:444
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
void set_stop_bits(int n)
Definition: UARTDriver.cpp:179
enum flow_control _flow_control
Definition: UARTDriver.h:89
bool advance(uint32_t n)
Definition: RingBuffer.cpp:116
uint32_t millis()
Definition: system.cpp:157
int close(int fileno)
POSIX Close a file with fileno handel.
Definition: posix.c:675
bool set_size(uint32_t size)
Definition: RingBuffer.cpp:20
void begin(uint32_t b)
Definition: UARTDriver.cpp:195
uint64_t _last_write_time
Definition: UARTDriver.h:81
uint64_t micros64()
Definition: system.cpp:162
virtual enum safety_state safety_switch_state(void)
Definition: Util.h:42
perf_counter_t _perf_uart
Definition: UARTDriver.h:76
float v
Definition: Printf.cpp:15
uint8_t byte
Definition: compat.h:8
uint32_t txspace() override
Definition: UARTDriver.cpp:266
uint64_t receive_time_constraint_us(uint16_t nbytes) override
Definition: UARTDriver.cpp:545
volatile bool _in_timer
Definition: UARTDriver.h:67
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
uint8_t peekiovec(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:125
uint8_t _receive_timestamp_idx
Definition: UARTDriver.h:93
int _write_fd(const uint8_t *buf, uint16_t n)
Definition: UARTDriver.cpp:376
AP_HAL::GPIO * gpio
Definition: HAL.h:111
uint64_t _first_write_time
Definition: UARTDriver.h:80
uint32_t _os_start_auto_space
Definition: UARTDriver.h:86
void set_blocking_writes(bool blocking)
Definition: UARTDriver.cpp:243
uint32_t _last_initialise_attempt_ms
Definition: UARTDriver.h:84
void _timer_tick(void) override
Definition: UARTDriver.cpp:471
uint8_t reserve(IoVec vec[2], uint32_t len)
Definition: RingBuffer.cpp:171
uint32_t _total_read
Definition: UARTDriver.h:87
size_t write(uint8_t c)
Definition: UARTDriver.cpp:303
ByteBuffer _readbuf
Definition: UARTDriver.h:74
Semaphore _semaphore
Definition: UARTDriver.h:95
AP_HAL::Scheduler * scheduler
Definition: HAL.h:114
volatile bool _initialised
Definition: UARTDriver.h:66
bool read_byte(uint8_t *data)
Definition: RingBuffer.cpp:219
static const AP_HAL::HAL & hal
Definition: Device.cpp:29