APM:Libraries
UARTDriver.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 //
17 // Copyright (c) 2010 Michael Smith. All rights reserved.
18 //
19 #include <AP_HAL/AP_HAL.h>
20 #if CONFIG_HAL_BOARD == HAL_BOARD_SITL
21 
22 #include <limits.h>
23 #include <stdlib.h>
24 #include <stdio.h>
25 #include <unistd.h>
26 #include <fcntl.h>
27 #include <stdarg.h>
28 #include <AP_Math/AP_Math.h>
29 
30 #include <errno.h>
31 #include <sys/ioctl.h>
32 #include <sys/types.h>
33 #include <sys/socket.h>
34 #include <netinet/in.h>
35 #include <netinet/tcp.h>
36 #include <sys/select.h>
37 #include <termios.h>
38 #include <sys/time.h>
39 
40 #include "UARTDriver.h"
41 #include "SITL_State.h"
42 
43 extern const AP_HAL::HAL& hal;
44 
45 using namespace HALSITL;
46 
48 
49 /* UARTDriver method implementations */
50 
51 void UARTDriver::begin(uint32_t baud, uint16_t rxSpace, uint16_t txSpace)
52 {
53  const char *path = _sitlState->_uart_path[_portNumber];
54 
55  // default to 1MBit
56  _uart_baudrate = 1000000U;
57 
58  if (strcmp(path, "GPS1") == 0) {
59  /* gps */
60  _connected = true;
61  _fd = _sitlState->gps_pipe();
62  } else if (strcmp(path, "GPS2") == 0) {
63  /* 2nd gps */
64  _connected = true;
66  } else {
67  /* parse type:args:flags string for path.
68  For example:
69  tcp:5760:wait // tcp listen on port 5760
70  tcp:0:wait // tcp listen on use base_port + 0
71  tcpclient:192.168.2.15:5762
72  uart:/dev/ttyUSB0:57600
73  sim:ParticleSensor_SDS021:
74  */
75  char *saveptr = nullptr;
76  char *s = strdup(path);
77  char *devtype = strtok_r(s, ":", &saveptr);
78  char *args1 = strtok_r(nullptr, ":", &saveptr);
79  char *args2 = strtok_r(nullptr, ":", &saveptr);
80  if (strcmp(devtype, "tcp") == 0) {
81  uint16_t port = atoi(args1);
82  bool wait = (args2 && strcmp(args2, "wait") == 0);
83  _tcp_start_connection(port, wait);
84  } else if (strcmp(devtype, "tcpclient") == 0) {
85  if (args2 == nullptr) {
86  AP_HAL::panic("Invalid tcp client path: %s", path);
87  }
88  uint16_t port = atoi(args2);
89  _tcp_start_client(args1, port);
90  } else if (strcmp(devtype, "uart") == 0) {
91  uint32_t baudrate = args2? atoi(args2) : baud;
92  ::printf("UART connection %s:%u\n", args1, baudrate);
93  _uart_path = strdup(args1);
94  _uart_baudrate = baudrate;
96  } else if (strcmp(devtype, "sim") == 0) {
97  ::printf("SIM connection %s:%s\n", args1, args2);
98  if (!_connected) {
99  _connected = true;
100  _fd = _sitlState->sim_fd(args1, args2);
101  }
102  } else {
103  AP_HAL::panic("Invalid device path: %s", path);
104  }
105  free(s);
106  }
107 
109 }
110 
111 void UARTDriver::end()
112 {
113 }
114 
115 uint32_t UARTDriver::available(void)
116 {
118 
119  if (!_connected) {
120  return 0;
121  }
122 
123  return _readbuffer.available();
124 }
125 
126 uint32_t UARTDriver::txspace(void)
127 {
129  if (!_connected) {
130  return 0;
131  }
132  return _writebuffer.space();
133 }
134 
135 int16_t UARTDriver::read(void)
136 {
137  if (available() <= 0) {
138  return -1;
139  }
140  uint8_t c;
141  _readbuffer.read(&c, 1);
142  return c;
143 }
144 
145 void UARTDriver::flush(void)
146 {
147 }
148 
149 size_t UARTDriver::write(uint8_t c)
150 {
151  if (txspace() <= 0) {
152  return 0;
153  }
154  _writebuffer.write(&c, 1);
155  return 1;
156 }
157 
158 size_t UARTDriver::write(const uint8_t *buffer, size_t size)
159 {
160  if (txspace() <= size) {
161  size = txspace();
162  }
163  if (size <= 0) {
164  return 0;
165  }
166  if (_unbuffered_writes) {
167  // write buffer straight to the file descriptor
168  const ssize_t nwritten = ::write(_fd, buffer, size);
169  if (nwritten == -1 && errno != EAGAIN && _uart_path) {
170  close(_fd);
171  _fd = -1;
172  _connected = false;
173  }
174  // these have no effect
175  tcdrain(_fd);
176  } else {
177  _writebuffer.write(buffer, size);
178  }
179  return size;
180 }
181 
182 
183 /*
184  start a TCP connection for the serial port. If wait_for_connection
185  is true then block until a client connects
186  */
187 void UARTDriver::_tcp_start_connection(uint16_t port, bool wait_for_connection)
188 {
189  int one=1;
190  struct sockaddr_in sockaddr;
191  int ret;
192 
193  if (_connected) {
194  return;
195  }
196 
197  _use_send_recv = true;
198 
199  if (_console) {
200  // hack for console access
201  _connected = true;
202  _use_send_recv = false;
203  _listen_fd = -1;
204  _fd = 1;
205  return;
206  }
207 
208  if (_fd != -1) {
209  close(_fd);
210  }
211 
212  if (_listen_fd == -1) {
213  memset(&sockaddr,0,sizeof(sockaddr));
214 
215 #ifdef HAVE_SOCK_SIN_LEN
216  sockaddr.sin_len = sizeof(sockaddr);
217 #endif
218  if (port > 1000) {
219  sockaddr.sin_port = htons(port);
220  } else {
221  sockaddr.sin_port = htons(_sitlState->base_port() + port);
222  }
223  sockaddr.sin_family = AF_INET;
224 
225  _listen_fd = socket(AF_INET, SOCK_STREAM | SOCK_CLOEXEC, 0);
226  if (_listen_fd == -1) {
227  fprintf(stderr, "socket failed - %s\n", strerror(errno));
228  exit(1);
229  }
230 
231  /* we want to be able to re-use ports quickly */
232  if (setsockopt(_listen_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one)) == -1) {
233  fprintf(stderr, "setsockopt failed: %s\n", strerror(errno));
234  exit(1);
235  }
236 
237  fprintf(stderr, "bind port %u for %u\n",
238  (unsigned)ntohs(sockaddr.sin_port),
239  (unsigned)_portNumber);
240 
241  ret = bind(_listen_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
242  if (ret == -1) {
243  fprintf(stderr, "bind failed on port %u - %s\n",
244  (unsigned)ntohs(sockaddr.sin_port),
245  strerror(errno));
246  exit(1);
247  }
248 
249  ret = listen(_listen_fd, 5);
250  if (ret == -1) {
251  fprintf(stderr, "listen failed - %s\n", strerror(errno));
252  exit(1);
253  }
254 
255  fprintf(stderr, "Serial port %u on TCP port %u\n", _portNumber,
257  fflush(stdout);
258  }
259 
260  if (wait_for_connection) {
261  fprintf(stdout, "Waiting for connection ....\n");
262  fflush(stdout);
263  _fd = accept(_listen_fd, nullptr, nullptr);
264  if (_fd == -1) {
265  fprintf(stderr, "accept() error - %s", strerror(errno));
266  exit(1);
267  }
268  setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
269  setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
270  _connected = true;
271  }
272 }
273 
274 
275 /*
276  start a TCP client connection for the serial port.
277  */
278 void UARTDriver::_tcp_start_client(const char *address, uint16_t port)
279 {
280  int one=1;
281  struct sockaddr_in sockaddr;
282  int ret;
283 
284  if (_connected) {
285  return;
286  }
287 
288  _use_send_recv = true;
289 
290  if (_fd != -1) {
291  close(_fd);
292  }
293 
294  memset(&sockaddr,0,sizeof(sockaddr));
295 
296 #ifdef HAVE_SOCK_SIN_LEN
297  sockaddr.sin_len = sizeof(sockaddr);
298 #endif
299  sockaddr.sin_port = htons(port);
300  sockaddr.sin_family = AF_INET;
301  sockaddr.sin_addr.s_addr = inet_addr(address);
302 
303  _fd = socket(AF_INET, SOCK_STREAM | SOCK_CLOEXEC, 0);
304  if (_fd == -1) {
305  fprintf(stderr, "socket failed - %s\n", strerror(errno));
306  exit(1);
307  }
308 
309  /* we want to be able to re-use ports quickly */
310  setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
311 
312  ret = connect(_fd, (struct sockaddr *)&sockaddr, sizeof(sockaddr));
313  if (ret == -1) {
314  fprintf(stderr, "connect failed on port %u - %s\n",
315  (unsigned)ntohs(sockaddr.sin_port),
316  strerror(errno));
317  exit(1);
318  }
319 
320  setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
321  setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
322  _connected = true;
323 }
324 
325 
326 /*
327  start a UART connection for the serial port
328  */
330 {
331  struct termios t {};
332  if (!_connected) {
333  _fd = ::open(_uart_path, O_RDWR | O_CLOEXEC);
334  if (_fd == -1) {
335  return;
336  }
337  // use much smaller buffer sizes on real UARTs
338  _writebuffer.set_size(1024);
339  _readbuffer.set_size(512);
340  ::printf("Opened %s\n", _uart_path);
341  }
342 
343  if (_fd == -1) {
344  AP_HAL::panic("Unable to open UART %s", _uart_path);
345  }
346 
347  // set non-blocking
348  int flags = fcntl(_fd, F_GETFL, 0);
349  flags = flags | O_NONBLOCK;
350  fcntl(_fd, F_SETFL, flags);
351 
352  // disable LF -> CR/LF
353  tcgetattr(_fd, &t);
354  t.c_iflag &= ~(BRKINT | ICRNL | IMAXBEL | IXON | IXOFF);
355  t.c_oflag &= ~(OPOST | ONLCR);
356  t.c_lflag &= ~(ISIG | ICANON | IEXTEN | ECHO | ECHOE | ECHOK | ECHOCTL | ECHOKE);
357  t.c_cc[VMIN] = 0;
358  if (_sitlState->use_rtscts()) {
359  t.c_cflag |= CRTSCTS;
360  }
361  tcsetattr(_fd, TCSANOW, &t);
362 
363  // set baudrate
365 
366  _connected = true;
367  _use_send_recv = false;
368 }
369 
370 /*
371  see if a new connection is coming in
372  */
374 {
375  if (_connected) {
376  // we only want 1 connection at a time
377  return;
378  }
379  if (_select_check(_listen_fd)) {
380  _fd = accept(_listen_fd, nullptr, nullptr);
381  if (_fd != -1) {
382  int one = 1;
383  _connected = true;
384  setsockopt(_fd, IPPROTO_TCP, TCP_NODELAY, &one, sizeof(one));
385  setsockopt(_fd, SOL_SOCKET, SO_REUSEADDR, &one, sizeof(one));
386  fprintf(stdout, "New connection on serial port %u\n", _portNumber);
387  }
388  }
389 }
390 
391 /*
392  use select() to see if something is pending
393  */
395 {
396  if (fd == -1) {
397  return false;
398  }
399  fd_set fds;
400  struct timeval tv;
401 
402  FD_ZERO(&fds);
403  FD_SET(fd, &fds);
404 
405  // zero time means immediate return from select()
406  tv.tv_sec = 0;
407  tv.tv_usec = 0;
408 
409  if (select(fd+1, &fds, nullptr, nullptr, &tv) == 1) {
410  return true;
411  }
412  return false;
413 }
414 
416 {
417  unsigned v = fcntl(fd, F_GETFL, 0);
418  fcntl(fd, F_SETFL, v | O_NONBLOCK);
419 }
420 
422  if (_fd == -1) {
423  return false;
424  }
426 
427  // this has no effect
428  unsigned v = fcntl(_fd, F_GETFL, 0);
429  v &= ~O_NONBLOCK;
430 #if defined(__APPLE__) && defined(__MACH__)
431  fcntl(_fd, F_SETFL | F_NOCACHE, v | O_SYNC);
432 #else
433  fcntl(_fd, F_SETFL, v | O_DIRECT | O_SYNC);
434 #endif
435  return _unbuffered_writes;
436 }
437 
439 {
440  if (!_uart_path) {
441  return;
442  }
444 }
445 
446 void UARTDriver::_timer_tick(void)
447 {
448  if (!_connected) {
450  return;
451  }
452  uint32_t navail;
453  ssize_t nwritten;
454 
455  const uint8_t *readptr = _writebuffer.readptr(navail);
456  if (readptr && navail > 0) {
457  if (!_use_send_recv) {
458  nwritten = ::write(_fd, readptr, navail);
459  if (nwritten == -1 && errno != EAGAIN && _uart_path) {
460  close(_fd);
461  _fd = -1;
462  _connected = false;
463  }
464  } else {
465  nwritten = send(_fd, readptr, navail, MSG_DONTWAIT);
466  }
467  if (nwritten > 0) {
468  _writebuffer.advance(nwritten);
469  }
470  }
471 
472  uint32_t space = _readbuffer.space();
473  if (space == 0) {
474  return;
475  }
476 
477  char buf[space];
478  ssize_t nread = 0;
479  if (!_use_send_recv) {
480  int fd = _console?0:_fd;
481  nread = ::read(fd, buf, space);
482  if (nread == -1 && errno != EAGAIN && _uart_path) {
483  close(_fd);
484  _fd = -1;
485  _connected = false;
486  }
487  } else {
488  if (_select_check(_fd)) {
489  nread = recv(_fd, buf, space, MSG_DONTWAIT);
490  if (nread <= 0) {
491  // the socket has reached EOF
492  close(_fd);
493  _connected = false;
494  fprintf(stdout, "Closed connection on serial port %u\n", _portNumber);
495  fflush(stdout);
496  return;
497  }
498  } else {
499  nread = 0;
500  }
501  }
502  if (nread > 0) {
503  _readbuffer.write((uint8_t *)buf, nread);
505  }
506 }
507 
508 /*
509  return timestamp estimate in microseconds for when the start of
510  a nbytes packet arrived on the uart. This should be treated as a
511  time constraint, not an exact time. It is guaranteed that the
512  packet did not start being received after this time, but it
513  could have been in a system buffer before the returned time.
514 
515  This takes account of the baudrate of the link. For transports
516  that have no baudrate (such as USB) the time estimate may be
517  less accurate.
518 
519  A return value of zero means the HAL does not support this API
520 */
521 uint64_t UARTDriver::receive_time_constraint_us(uint16_t nbytes)
522 {
523  uint64_t last_receive_us = _receive_timestamp;
524  if (_uart_baudrate > 0) {
525  // assume 10 bits per byte.
526  uint32_t transport_time_us = (1000000UL * 10UL / _uart_baudrate) * (nbytes+available());
527  last_receive_us -= transport_time_us;
528  }
529  return last_receive_us;
530 }
531 
532 #endif // CONFIG_HAL_BOARD
533 
size_t write(uint8_t c)
static bool _select_check(int)
Definition: UARTDriver.cpp:394
SITL_State * _sitlState
Definition: UARTDriver.h:111
uint32_t _uart_baudrate
Definition: UARTDriver.h:97
void _timer_tick(void)
Definition: UARTDriver.cpp:448
uint32_t available(void) const
Definition: RingBuffer.cpp:37
const AP_HAL::HAL & hal
Definition: AC_PID_test.cpp:14
#define on
Definition: Config.h:51
int open(const char *pathname, int flags)
POSIX Open a file with integer mode flags.
Definition: posix.c:885
const uint8_t * readptr(uint32_t &available_bytes)
Definition: RingBuffer.cpp:238
bool set_unbuffered_writes(bool on) override
int gps_pipe(void)
Definition: sitl_gps.cpp:68
void _tcp_start_connection(uint16_t port, bool wait_for_connection)
Definition: UARTDriver.cpp:187
static uint8_t buffer[SRXL_FRAMELEN_MAX]
Definition: srxl.cpp:56
char * strerror(int errnum)
POSIX strerror() - convert POSIX errno to text with user message.
Definition: posix.c:1852
void _tcp_start_client(const char *address, uint16_t port)
Definition: UARTDriver.cpp:278
const char * _uart_path[6]
Definition: SITL_State.h:77
ByteBuffer _writebuffer
Definition: UARTDriver.h:94
uint32_t space(void) const
Definition: RingBuffer.cpp:54
static bool _console
Definition: UARTDriver.h:91
int gps2_pipe(void)
Definition: sitl_gps.cpp:86
static void _set_nonblocking(int)
Definition: UARTDriver.cpp:415
bool set_speed(int speed)
Definition: UART_utils.cpp:37
virtual void printf(const char *,...) FMT_PRINTF(2
Definition: BetterStream.cpp:5
uint64_t receive_time_constraint_us(uint16_t nbytes) override
void _check_connection(void)
Definition: UARTDriver.cpp:373
bool advance(uint32_t n)
Definition: RingBuffer.cpp:116
uint32_t available() override
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
uint32_t read(uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:212
uint64_t micros64()
Definition: system.cpp:162
const char * _uart_path
Definition: UARTDriver.h:96
float v
Definition: Printf.cpp:15
uint32_t write(const uint8_t *data, uint32_t len)
Definition: RingBuffer.cpp:79
int16_t read() override
void free(void *ptr)
Definition: malloc.c:81
bool use_rtscts(void) const
Definition: SITL_State.h:60
uint32_t txspace() override
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
int sim_fd(const char *name, const char *arg)
Definition: SITL_State.cpp:195
uint64_t _receive_timestamp
Definition: UARTDriver.h:112
ByteBuffer _readbuffer
Definition: UARTDriver.h:93
void panic(const char *errormsg,...) FMT_PRINTF(1
Definition: system.cpp:140
void _uart_start_connection(void)
Definition: UARTDriver.cpp:329
void begin(uint32_t b)
Definition: UARTDriver.h:29
uint16_t base_port(void) const
Definition: SITL_State.h:52