impl_unix.cpp
Go to the documentation of this file.
1 /***
2  * MIT License
3  *
4  * Copyright (c) 2020 Alessandro Tondo
5  * Copyright (c) 2012 William Woodall, John Harrison
6  *
7  * Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated
8  * documentation files (the "Software"), to deal in the Software without restriction, including without limitation
9  * the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and
10  * to permit persons to whom the Software is furnished to do so, subject to the following conditions:
11  *
12  * The above copyright notice and this permission notice shall be included in all copies or substantial portions of
13  * the Software.
14  *
15  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO
16  * THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
17  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT,
18  * TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
19  * SOFTWARE.
20  */
21 
22 #if !defined(_WIN32)
23 
24 #include <serial/impl/impl.h>
25 
26 using namespace serial;
27 
28 Serial::SerialImpl::SerialImpl(std::string port, unsigned long baudrate, Timeout timeout, bytesize_t bytesize,
29  parity_t parity, stopbits_t stopbits, flowcontrol_t flowcontrol)
30  : port_(std::move(port)),
31  fd_(-1),
32  is_open_(false),
33  timeout_(timeout),
34  baudrate_(baudrate),
35  parity_(parity),
36  bytesize_(bytesize),
37  stopbits_(stopbits),
38  flowcontrol_(flowcontrol) {
39  if (!port_.empty()) {
40  open();
41  }
42 }
43 
45  close();
46 }
47 
49  if (port_.empty()) {
50  throw SerialInvalidArgumentException("serial port is empty.");
51  }
52  if (is_open_) {
53  return;
54  }
55 
56  fd_ = ::open(port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK | O_CLOEXEC);
57  if (fd_ == -1) {
58  if (errno == EINTR) {
59  open(); // Recurse because this is a recoverable error
60  return;
61  }
62  throw SerialIOException("failure during ::open()", errno);
63  }
64 
65  // prevent multiple openings
66  if (::ioctl(fd_, TIOCEXCL) == -1) {
67  throw SerialIOException("failure during ::ioctl()", errno);
68  }
69 
70  // set communication as BLOCKING
71 
72  if(::fcntl(fd_, F_SETFL, 0) == -1) {
73  throw SerialIOException("failure during ::fcntl()", errno);
74  }
75 
76  reconfigurePort();
77  is_open_ = true;
78 }
79 
81  if (fd_ == -1) {
82  throw SerialInvalidArgumentException("invalid file descriptor");
83  }
84 
85  struct termios options{0};
86  if (::tcgetattr(fd_, &options) == -1) {
87  throw SerialIOException("failure during ::tcgetattr()", errno);
88  }
89 
90  // input modes
91  options.c_iflag &= ~(IGNBRK | BRKINT | IGNPAR | PARMRK | INPCK | ISTRIP | INLCR | IGNCR | ICRNL | IXON | IXOFF | IXANY);
92 #ifdef IUCLC
93  options.c_iflag &= ~IUCLC;
94 #endif
95 #ifdef IMAXBEL
96  options.c_iflag &= ~IMAXBEL;
97 #endif
98 
99  // output modes
100  options.c_oflag &= ~(OPOST | ONLCR | OCRNL | ONOCR | ONLRET | OFILL);
101 #ifdef OLCUC
102  options.c_oflag &= ~OLCUC;
103 #endif
104 #ifdef NLDLY
105  options.c_oflag &= ~NLDLY;
106 #endif
107 #ifdef CRDLY
108  options.c_oflag &= ~CRDLY;
109 #endif
110 #ifdef TABDLY
111  options.c_oflag &= ~TABDLY;
112 #endif
113 #ifdef BSDLY
114  options.c_oflag &= ~BSDLY;
115 #endif
116 #ifdef VTDLY
117  options.c_oflag &= ~VTDLY;
118 #endif
119 #ifdef FFDLY
120  options.c_oflag &= ~FFDLY;
121 #endif
122 
123  // control modes
124  options.c_cflag &= (CSIZE | CSTOPB | PARENB | PARODD);
125  options.c_cflag |= (CREAD | HUPCL | CLOCAL);
126 #ifdef CMSPAR
127  options.c_cflag &= ~CMSPAR;
128 #endif
129 #ifdef CRTSCTS
130  options.c_cflag &= ~CRTSCTS;
131 #endif
132 
133  // local modes
134  options.c_lflag &= ~(ISIG | ICANON | ECHO | ECHOE | ECHOK | ECHONL | IEXTEN);
135 #ifdef ECHOCTL
136  options.c_lflag &= ~ECHOCTL;
137 #endif
138 #ifdef ECHOPRT
139  options.c_lflag &= ~ECHOPRT;
140 #endif
141 #ifdef ECHOKE
142  options.c_lflag &= ~ECHOKE;
143 #endif
144 
145  // control characters
146  options.c_cc[VMIN] = 0;
147  options.c_cc[VTIME] = 0;
148 
149  struct serial_struct serinfo;
150 
151  ::ioctl(fd_, TIOCGSERIAL, &serinfo);
152  serinfo.flags |= ASYNC_LOW_LATENCY;
153  ::ioctl(fd_, TIOCSSERIAL, &serinfo);
154 
155  bool use_custom_baudrate = false;
156  speed_t baudrate = 0;
157  switch (baudrate_) {
158 #ifdef B0
159  case 0: baudrate = B0; break;
160 #endif
161 #ifdef B50
162  case 50: baudrate = B50; break;
163 #endif
164 #ifdef B75
165  case 75: baudrate = B75; break;
166 #endif
167 #ifdef B110
168  case 110: baudrate = B110; break;
169 #endif
170 #ifdef B134
171  case 134: baudrate = B134; break;
172 #endif
173 #ifdef B150
174  case 150: baudrate = B150; break;
175 #endif
176 #ifdef B200
177  case 200: baudrate = B200; break;
178 #endif
179 #ifdef B300
180  case 300: baudrate = B300; break;
181 #endif
182 #ifdef B600
183  case 600: baudrate = B600; break;
184 #endif
185 #ifdef B1200
186  case 1200: baudrate = B1200; break;
187 #endif
188 #ifdef B1800
189  case 1800: baudrate = B1800; break;
190 #endif
191 #ifdef B2400
192  case 2400: baudrate = B2400; break;
193 #endif
194 #ifdef B4800
195  case 4800: baudrate = B4800; break;
196 #endif
197 #ifdef B7200
198  case 7200: baudrate = B7200; break;
199 #endif
200 #ifdef B9600
201  case 9600: baudrate = B9600; break;
202 #endif
203 #ifdef B14400
204  case 14400: baudrate = B14400; break;
205 #endif
206 #ifdef B19200
207  case 19200: baudrate = B19200; break;
208 #endif
209 #ifdef B28800
210  case 28800: baudrate = B28800; break;
211 #endif
212 #ifdef B57600
213  case 57600: baudrate = B57600; break;
214 #endif
215 #ifdef B76800
216  case 76800: baudrate = B76800; break;
217 #endif
218 #ifdef B38400
219  case 38400: baudrate = B38400; break;
220 #endif
221 #ifdef B115200
222  case 115200: baudrate = B115200; break;
223 #endif
224 #ifdef B128000
225  case 128000: baudrate = B128000; break;
226 #endif
227 #ifdef B153600
228  case 153600: baudrate = B153600; break;
229 #endif
230 #ifdef B230400
231  case 230400: baudrate = B230400; break;
232 #endif
233 #ifdef B256000
234  case 256000: baudrate = B256000; break;
235 #endif
236 #ifdef B460800
237  case 460800: baudrate = B460800; break;
238 #endif
239 #ifdef B500000
240  case 500000: baudrate = B500000; break;
241 #endif
242 #ifdef B576000
243  case 576000: baudrate = B576000; break;
244 #endif
245 #ifdef B921600
246  case 921600: baudrate = B921600; break;
247 #endif
248 #ifdef B1000000
249  case 1000000: baudrate = B1000000; break;
250 #endif
251 #ifdef B1152000
252  case 1152000: baudrate = B1152000; break;
253 #endif
254 #ifdef B1500000
255  case 1500000: baudrate = B1500000; break;
256 #endif
257 #ifdef B2000000
258  case 2000000: baudrate = B2000000; break;
259 #endif
260 #ifdef B2500000
261  case 2500000: baudrate = B2500000; break;
262 #endif
263 #ifdef B3000000
264  case 3000000: baudrate = B3000000; break;
265 #endif
266 #ifdef B3500000
267  case 3500000: baudrate = B3500000; break;
268 #endif
269 #ifdef B4000000
270  case 4000000: baudrate = B4000000; break;
271 #endif
272  default:
273  baudrate = baudrate_;
274  use_custom_baudrate = true;
275  }
276 
277  if (!use_custom_baudrate) {
278  if (::cfsetispeed(&options, baudrate) == -1) {
279  throw SerialIOException("failure during ::cfsetispeed()", errno);
280  }
281  if (::cfsetospeed(&options, baudrate) == -1) {
282  throw SerialIOException("failure during ::cfsetospeed()", errno);
283  }
284  }
285 
286  switch (bytesize_) {
287  case eightbits: options.c_cflag |= CS8; break;
288  case sevenbits: options.c_cflag |= CS7; break;
289  case sixbits: options.c_cflag |= CS6; break;
290  case fivebits: options.c_cflag |= CS5; break;
291  default:
292  throw SerialInvalidArgumentException("invalid byte size");
293  }
294 
295  switch (stopbits_) {
296  case stopbits_one: options.c_cflag &= ~CSTOPB; break;
297  case stopbits_one_point_five: // there is no POSIX support for 1.5 stop bit
298  case stopbits_two: options.c_cflag |= CSTOPB; break;
299  default:
300  throw SerialInvalidArgumentException("invalid stop bit");
301  }
302 
303  switch (parity_) {
304  case parity_none: options.c_iflag |= IGNPAR; break;
305  case parity_even: options.c_cflag |= PARENB; break;
306  case parity_odd: options.c_cflag |= (PARENB | PARODD); break;
307 #ifdef CMSPAR
308  case parity_mark: options.c_cflag |= (PARENB | PARODD | CMSPAR); break;
309  case parity_space: options.c_cflag |= (PARENB | CMSPAR); break;
310 #endif
311  default:
312  throw SerialInvalidArgumentException("invalid parity");
313  }
314 
315  switch (flowcontrol_) {
316  case flowcontrol_none: break;
317  case flowcontrol_software: options.c_iflag |= (IXON | IXOFF | IXANY); break;
318 #ifdef CRTSCTS
319  case flowcontrol_hardware: options.c_cflag |= (CRTSCTS); break;
320 #endif
321  default:
322  throw SerialInvalidArgumentException("invalid flow control");
323  }
324 
325  // activate settings
326  if (::tcsetattr(fd_, TCSANOW, &options) != 0) {
327  throw SerialIOException("failure during ::tcsetattr()", errno);
328  }
329 
330  if (use_custom_baudrate) {
331 #if defined(__APPLE__)
332  if (::ioctl(fd_, IOSSIOSPEED, &baudrate) == -1) {
333  throw SerialIOException("failure during ::ioctl(IOSSIOSPEED)", errno);
334  }
335 #elif defined(__linux__) && defined (TIOCSSERIAL) //TODO: maybe termios2 could be an alternative
336  struct serial_struct serial {0};
337  if (::ioctl(fd_, TIOCGSERIAL, &serial) == -1) {
338  throw SerialIOException("failure during ::ioctl()", errno);
339  }
340 
341  //TODO: check ASYNC_LOW_LATENCY
342  serial.flags &= ~ASYNC_SPD_MASK;
343  serial.flags |= ASYNC_SPD_CUST;
344  serial.custom_divisor = static_cast<int>((serial.baud_base + baudrate_ / 2) / baudrate_);
345  int closest_baudrate = serial.baud_base / serial.custom_divisor;
346  if (std::abs(static_cast<int>(closest_baudrate - baudrate_)) < 0.02) {
347  throw SerialIOException("cannot set baudrate to " + std::to_string(baudrate_) + " (the closest possible value is " + std::to_string(closest_baudrate) + ")");
348  }
349 
350  if (::ioctl(fd_, TIOCSSERIAL, &serial) == -1) {
351  throw SerialIOException("failure during ::ioctl()", errno);
352  }
353 #else
354  throw SerialInvalidArgumentException("custom baudrates are not supported on current OS");
355 #endif
356  }
357 }
358 
360  if (is_open_ && fd_ != -1 && ::close(fd_) != 0) {
361  throw SerialIOException("failure during ::close()", errno);
362  }
363  fd_ = -1;
364  is_open_ = false;
365 }
366 
368  return is_open_;
369 }
370 
372  if (!is_open_) {
374  }
375  int count = 0;
376  if (::ioctl(fd_, TIOCINQ, &count) == -1) {
377  throw SerialIOException("failure during ::ioctl()", errno);
378  }
379  return static_cast<size_t>(count);
380 }
381 
382 bool waitOnPoll(std::chrono::milliseconds timeout_ms, std::unique_ptr<pollfd> fds) {
383  int r = ::poll(fds.get(), 1, timeout_ms.count());
384  if (r < 0 && errno != EINTR) {
385  throw SerialIOException("failure during ::poll()", errno);
386  }
387  if (fds->revents == POLLERR || fds->revents == POLLHUP || fds->revents == POLLNVAL) {
388  throw SerialIOException("failure during ::poll(), revents has been set to '" + std::to_string(fds->revents) + "'.");
389  }
390  return r > 0;
391 }
392 
393 bool Serial::SerialImpl::waitReadable(std::chrono::milliseconds timeout_ms) const {
394  if (!is_open_) {
396  }
397  return waitOnPoll(timeout_ms, std::unique_ptr<pollfd>(new pollfd{fd_, POLLIN, 0}));
398 }
399 
400 bool Serial::SerialImpl::waitWritable(std::chrono::milliseconds timeout_ms) const {
401  if (!is_open_) {
403  }
404  return waitOnPoll(timeout_ms, std::unique_ptr<pollfd>(new pollfd{fd_, POLLOUT, 0}));
405 }
406 
407 void Serial::SerialImpl::waitByteTimes(size_t count) const {
408  auto start = std::chrono::steady_clock::now();
409  uint32_t bit_time_ns = 1e9 / baudrate_;
410  uint32_t byte_time_ns = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
411  byte_time_ns += stopbits_ == stopbits_one_point_five ? -1.5*bit_time_ns : 0; // stopbits_one_point_five is 3
412  std::this_thread::sleep_until(start + std::chrono::nanoseconds(byte_time_ns * count));
413 }
414 
415 size_t Serial::SerialImpl::read(uint8_t *buf, size_t size) {
416  if (!is_open_) {
418  }
419  auto read_deadline = timeout_.getReadDeadline(size);
420  size_t total_bytes_read = ::read(fd_, buf, size);
421  if (total_bytes_read == -1) {
422  throw SerialIOException("failure during ::read()", errno);
423  }
424  while (total_bytes_read < size) {
425  auto remaining_time = Timeout::remainingMicroseconds(read_deadline);
426  if (remaining_time.count() <= 0) {
427  break;
428  }
429  if (waitReadable(std::min(std::chrono::duration_cast<std::chrono::milliseconds>(remaining_time), timeout_.getInterByte()))) {
430  if (size - total_bytes_read > 1 && timeout_.getInterByteMilliseconds() == std::numeric_limits<uint32_t>::max()) {
431  size_t bytes_available = available();
432  if (bytes_available + total_bytes_read < size) {
433  waitByteTimes(size - (bytes_available + total_bytes_read));
434  }
435  }
436  size_t bytes_read = ::read(fd_, buf + total_bytes_read, size - total_bytes_read);
437  if (bytes_read < 1) { // at least one byte is for sure available
438  throw SerialIOException("failure during ::read()", errno);
439  }
440  total_bytes_read += bytes_read;
441  }
442  }
443  return total_bytes_read;
444 }
445 
446 size_t Serial::SerialImpl::write(const uint8_t *data, size_t size) {
447  if (!is_open_) {
449  }
450  auto write_deadline = timeout_.getWriteDeadline(size);
451  size_t total_bytes_written = ::write(fd_, data, size);
452  if (total_bytes_written == -1) {
453  throw SerialIOException("failure during ::write()", errno);
454  }
455  while (total_bytes_written < size) {
456  auto remaining_time = Timeout::remainingMicroseconds(write_deadline);
457  if (remaining_time.count() <= 0) {
458  break;
459  }
460  if (waitWritable(std::chrono::duration_cast<std::chrono::milliseconds>(remaining_time))) {
461  size_t bytes_written = ::write(fd_, data + total_bytes_written, size - total_bytes_written);
462  if (bytes_written < 1) { // at least one byte is for sure available
463  throw SerialIOException("failure during ::write()", errno);
464  }
465  total_bytes_written += bytes_written;
466  }
467  }
468  return total_bytes_written;
469 }
470 
471 void Serial::SerialImpl::setPort(const std::string &port) {
472  port_ = port;
473 }
474 
475 std::string Serial::SerialImpl::getPort() const {
476  return port_;
477 }
478 
480  timeout_ = timeout; // timeout is used directly inside read() and write(): there is no need to call reconfigurePort()
481 }
482 
484  return timeout_;
485 }
486 
487 void Serial::SerialImpl::setBaudrate(unsigned long baudrate) {
488  baudrate_ = baudrate;
489  if (is_open_) {
490  reconfigurePort();
491  }
492 }
493 
494 unsigned long Serial::SerialImpl::getBaudrate() const {
495  return baudrate_;
496 }
497 
499  bytesize_ = bytesize;
500  if (is_open_) {
501  reconfigurePort();
502  }
503 }
504 
506  return bytesize_;
507 }
508 
510  parity_ = parity;
511  if (is_open_) {
512  reconfigurePort();
513  }
514 }
515 
517  return parity_;
518 }
519 
521  stopbits_ = stopbits;
522  if (is_open_) {
523  reconfigurePort();
524  }
525 }
526 
528  return stopbits_;
529 }
530 
532  flowcontrol_ = flowcontrol;
533  if (is_open_) {
534  reconfigurePort();
535  }
536 }
537 
539  return flowcontrol_;
540 }
541 
543  if (!is_open_) {
545  }
546  if (::tcflush(fd_, TCIOFLUSH) == -1) {
547  throw SerialIOException("failure during ::tcflush()", errno);
548  }
549 }
550 
552  if (!is_open_) {
554  }
555  if (::tcflush(fd_, TCIFLUSH) == -1) {
556  throw SerialIOException("failure during ::tcflush()", errno);
557  }
558 }
559 
561  if (!is_open_) {
563  }
564  if (::tcflush(fd_, TCOFLUSH) == -1) {
565  throw SerialIOException("failure during ::tcflush()", errno);
566  }
567 }
568 
569 void Serial::SerialImpl::sendBreak(int duration_ms) const {
570  if (!is_open_) {
572  }
573  if (::tcsendbreak(fd_, duration_ms) == -1) {
574  throw SerialIOException("failure during ::tcsendbreak()", errno);
575  }
576 }
577 
578 void Serial::SerialImpl::setBreak(bool level) const {
579  setModemStatus(level ? TIOCSBRK : TIOCCBRK);
580 }
581 
582 void Serial::SerialImpl::setModemStatus(uint32_t request, uint32_t command) const {
583  if (!is_open_) {
585  }
586  if (::ioctl(fd_, request, &command) == -1) {
587  throw SerialIOException("failure during ::ioctl()", errno);
588  }
589 }
590 
591 void Serial::SerialImpl::setRTS(bool level) const {
592  setModemStatus(level ? TIOCMBIS : TIOCMBIC, TIOCM_RTS);
593 }
594 
595 void Serial::SerialImpl::setDTR(bool level) const {
596  setModemStatus(level ? TIOCMBIS : TIOCMBIC, TIOCM_DTR);
597 }
598 
600 #ifndef TIOCMIWAIT
601  throw SerialException("TIOCMIWAIT is not defined");
602 #else
603  if (!is_open_) {
605  }
606  // cannot use setModemStatus(): TIOCMIWAIT requires arg by value (not by pointer)
607  if (::ioctl(fd_, TIOCMIWAIT, TIOCM_CTS | TIOCM_DSR | TIOCM_RI | TIOCM_CD) == -1) {
608  throw SerialIOException("failure during ::ioctl()", errno);
609  }
610 #endif
611 }
612 
614  if (!is_open_) {
616  }
617  uint32_t modem_status;
618  if (::ioctl(fd_, TIOCMGET, &modem_status) == -1) {
619  throw SerialIOException("failure during ::ioctl()", errno);
620  }
621  return modem_status;
622 }
623 
625  return getModemStatus() & TIOCM_CTS;
626 }
627 
629  return getModemStatus() & TIOCM_DSR;
630 }
631 
633  return getModemStatus() & TIOCM_RI;
634 }
635 
637  return getModemStatus() & TIOCM_CD;
638 }
639 
640 #endif // !defined(_WIN32)
serial::parity_t
parity_t
Definition: serial.h:68
serial::parity_mark
@ parity_mark
Definition: serial.h:74
serial::Serial::SerialImpl::flushOutput
void flushOutput() const
Definition: impl_unix.cpp:560
serial::SerialIOException
Definition: serial.h:594
serial
Definition: impl.h:56
serial::Serial::SerialImpl::setPort
void setPort(const std::string &port)
Definition: impl_unix.cpp:471
serial::Serial::SerialImpl::waitByteTimes
void waitByteTimes(size_t count) const
Definition: impl_unix.cpp:407
serial::Serial::SerialImpl::sendBreak
void sendBreak(int duration_ms) const
Definition: impl_unix.cpp:569
command
ROSLIB_DECL std::string command(const std::string &cmd)
serial::Serial::SerialImpl::open
void open()
Definition: impl_unix.cpp:48
serial::Serial::SerialImpl::getStopbits
stopbits_t getStopbits() const
Definition: impl_unix.cpp:527
serial::Serial::SerialImpl::getPort
std::string getPort() const
Definition: impl_unix.cpp:475
serial::Serial::Timeout
Definition: serial.h:101
waitOnPoll
bool waitOnPoll(std::chrono::milliseconds timeout_ms, std::unique_ptr< pollfd > fds)
Definition: impl_unix.cpp:382
serial::Serial::SerialImpl::setBaudrate
void setBaudrate(unsigned long baudrate)
Definition: impl_unix.cpp:487
serial::Serial::close
void close()
Definition: serial.cpp:41
serial::Serial::SerialImpl::setDTR
void setDTR(bool level) const
Definition: impl_unix.cpp:595
serial::Serial::SerialImpl::waitReadable
bool waitReadable(std::chrono::milliseconds timeout_ms) const
Definition: impl_unix.cpp:393
serial::stopbits_one
@ stopbits_one
Definition: serial.h:82
serial::Serial::SerialImpl::reconfigurePort
void reconfigurePort()
Definition: impl_unix.cpp:80
serial::Serial::SerialImpl::setBytesize
void setBytesize(bytesize_t bytesize)
Definition: impl_unix.cpp:498
impl.h
serial::flowcontrol_software
@ flowcontrol_software
Definition: serial.h:92
serial::parity_even
@ parity_even
Definition: serial.h:73
serial::Serial::SerialImpl::flush
void flush() const
Definition: impl_unix.cpp:542
serial::Serial::waitReadable
bool waitReadable()
Definition: serial.cpp:53
serial::Serial::SerialImpl::setModemStatus
void setModemStatus(uint32_t request, uint32_t command=0) const
Definition: impl_unix.cpp:582
serial::Serial::SerialImpl::getBaudrate
unsigned long getBaudrate() const
Definition: impl_unix.cpp:494
serial::Serial::SerialImpl::read
size_t read(uint8_t *buf, size_t size=1)
Definition: impl_unix.cpp:415
serial::Serial::SerialImpl::getTimeout
Timeout getTimeout() const
Definition: impl_unix.cpp:483
serial::bytesize_t
bytesize_t
Definition: serial.h:58
serial::Serial::SerialImpl::setRTS
void setRTS(bool level) const
Definition: impl_unix.cpp:591
serial::Serial::SerialImpl::getCD
bool getCD() const
Definition: impl_unix.cpp:636
serial::Serial::SerialImpl::setFlowcontrol
void setFlowcontrol(flowcontrol_t flowcontrol)
Definition: impl_unix.cpp:531
serial::SerialInvalidArgumentException
Definition: serial.h:588
serial::Serial::SerialImpl::available
size_t available() const
Definition: impl_unix.cpp:371
serial::Serial::SerialImpl::waitWritable
bool waitWritable(std::chrono::milliseconds timeout_ms) const
Definition: impl_unix.cpp:400
serial::Serial::SerialImpl::getModemStatus
uint32_t getModemStatus() const
Definition: impl_unix.cpp:613
serial::Serial::SerialImpl::getCTS
bool getCTS() const
Definition: impl_unix.cpp:624
serial::Serial::SerialImpl::setParity
void setParity(parity_t parity)
Definition: impl_unix.cpp:509
serial::Serial::SerialImpl::setBreak
void setBreak(bool level) const
Definition: impl_unix.cpp:578
serial::Serial::SerialImpl::close
void close()
Definition: impl_unix.cpp:359
serial::Serial::SerialImpl::setStopbits
void setStopbits(stopbits_t stopbits)
Definition: impl_unix.cpp:520
serial::Serial::SerialImpl::getDSR
bool getDSR() const
Definition: impl_unix.cpp:628
serial::parity_odd
@ parity_odd
Definition: serial.h:72
start
ROSCPP_DECL void start()
serial::Serial::SerialImpl::write
size_t write(const uint8_t *data, size_t size)
Definition: impl_unix.cpp:446
serial::Serial::SerialImpl::port_
std::string port_
Definition: impl.h:197
serial::Serial::SerialImpl::getBytesize
bytesize_t getBytesize() const
Definition: impl_unix.cpp:505
serial::Serial::SerialImpl::~SerialImpl
virtual ~SerialImpl()
Definition: impl_unix.cpp:44
serial::Serial::open
void open()
Definition: serial.cpp:37
serial::flowcontrol_t
flowcontrol_t
Definition: serial.h:88
serial::sevenbits
@ sevenbits
Definition: serial.h:82
serial::Serial::SerialImpl::SerialImpl
SerialImpl(std::string port, unsigned long baudrate, Timeout timeout, bytesize_t bytesize, parity_t parity, stopbits_t stopbits, flowcontrol_t flowcontrol)
Definition: impl_unix.cpp:28
std
serial::Serial::SerialImpl::getRI
bool getRI() const
Definition: impl_unix.cpp:632
serial::Serial::SerialImpl::getParity
parity_t getParity() const
Definition: impl_unix.cpp:516
serial::Serial::available
size_t available()
Definition: serial.cpp:49
serial::stopbits_one_point_five
@ stopbits_one_point_five
Definition: serial.h:84
serial::parity_space
@ parity_space
Definition: serial.h:75
serial::stopbits_t
stopbits_t
Definition: serial.h:79
serial::flowcontrol_none
@ flowcontrol_none
Definition: serial.h:91
serial::SerialPortNotOpenException
Definition: serial.h:601
serial::flowcontrol_hardware
@ flowcontrol_hardware
Definition: serial.h:93
serial::Serial::waitByteTimes
void waitByteTimes(size_t count)
Definition: serial.cpp:61
serial::Serial::SerialImpl::waitForModemChanges
void waitForModemChanges() const
Definition: impl_unix.cpp:599
serial::Serial::SerialImpl::getFlowcontrol
flowcontrol_t getFlowcontrol() const
Definition: impl_unix.cpp:538
serial::fivebits
@ fivebits
Definition: serial.h:80
serial::SerialException
Definition: serial.h:582
serial::parity_none
@ parity_none
Definition: serial.h:71
serial::Serial::Timeout::remainingMicroseconds
static std::chrono::microseconds remainingMicroseconds(std::chrono::steady_clock::time_point deadline)
Definition: serial.h:168
serial::Serial::SerialImpl::flushInput
void flushInput() const
Definition: impl_unix.cpp:551
serial::stopbits_two
@ stopbits_two
Definition: serial.h:83
serial::Serial::SerialImpl::isOpen
bool isOpen() const
Definition: impl_unix.cpp:367
serial::Serial::write
size_t write(const uint8_t *data, size_t size)
Definition: serial.cpp:144
serial::sixbits
@ sixbits
Definition: serial.h:81
serial::Serial::SerialImpl::setTimeout
void setTimeout(const Timeout &timeout)
Definition: impl_unix.cpp:479
serial::Serial::read
size_t read(uint8_t *buffer, size_t size)
Definition: serial.cpp:65
serial::eightbits
@ eightbits
Definition: serial.h:83
serial::Serial::waitWritable
bool waitWritable()
Definition: serial.cpp:57


qb_device_driver
Author(s): qbroboticsĀ®
autogenerated on Thu Apr 27 2023 02:36:32