unix.cc
Go to the documentation of this file.
1 /* Copyright 2012 William Woodall and John Harrison
2  *
3  * Additional Contributors: Christopher Baker @bakercp
4  */
5 
6 #if !defined(_WIN32)
7 
8 #include <stdio.h>
9 #include <string.h>
10 #include <sstream>
11 #include <unistd.h>
12 #include <fcntl.h>
13 #include <sys/ioctl.h>
14 #include <sys/signal.h>
15 #include <errno.h>
16 #include <paths.h>
17 #include <sysexits.h>
18 #include <termios.h>
19 #include <sys/param.h>
20 #include <pthread.h>
21 
22 #if defined(__linux__)
23 # include <linux/serial.h>
24 #endif
25 
26 #include <sys/select.h>
27 #include <sys/time.h>
28 #include <time.h>
29 #ifdef __MACH__
30 #include <AvailabilityMacros.h>
31 #include <mach/clock.h>
32 #include <mach/mach.h>
33 #endif
34 
35 #include "serial/impl/unix.h"
36 
37 #ifndef TIOCINQ
38 #ifdef FIONREAD
39 #define TIOCINQ FIONREAD
40 #else
41 #define TIOCINQ 0x541B
42 #endif
43 #endif
44 
45 #if defined(MAC_OS_X_VERSION_10_3) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_3)
46 #include <IOKit/serial/ioss.h>
47 #endif
48 
49 using std::string;
50 using std::stringstream;
51 using std::invalid_argument;
53 using serial::Serial;
57 
58 
59 MillisecondTimer::MillisecondTimer (const uint32_t millis)
60  : expiry(timespec_now())
61 {
62  int64_t tv_nsec = expiry.tv_nsec + (millis * 1e6);
63  if (tv_nsec >= 1e9) {
64  int64_t sec_diff = tv_nsec / static_cast<int> (1e9);
65  expiry.tv_nsec = tv_nsec % static_cast<int>(1e9);
66  expiry.tv_sec += sec_diff;
67  } else {
68  expiry.tv_nsec = tv_nsec;
69  }
70 }
71 
72 int64_t
74 {
75  timespec now(timespec_now());
76  int64_t millis = (expiry.tv_sec - now.tv_sec) * 1e3;
77  millis += (expiry.tv_nsec - now.tv_nsec) / 1e6;
78  return millis;
79 }
80 
81 timespec
83 {
84  timespec time;
85 # ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
86  clock_serv_t cclock;
87  mach_timespec_t mts;
88  host_get_clock_service(mach_host_self(), SYSTEM_CLOCK, &cclock);
89  clock_get_time(cclock, &mts);
90  mach_port_deallocate(mach_task_self(), cclock);
91  time.tv_sec = mts.tv_sec;
92  time.tv_nsec = mts.tv_nsec;
93 # else
94  clock_gettime(CLOCK_MONOTONIC, &time);
95 # endif
96  return time;
97 }
98 
99 timespec
100 timespec_from_ms (const uint32_t millis)
101 {
102  timespec time;
103  time.tv_sec = millis / 1e3;
104  time.tv_nsec = (millis - (time.tv_sec * 1e3)) * 1e6;
105  return time;
106 }
107 
108 Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
109  bytesize_t bytesize,
110  parity_t parity, stopbits_t stopbits,
111  flowcontrol_t flowcontrol)
112  : port_ (port), fd_ (-1), is_open_ (false), xonxoff_ (false), rtscts_ (false),
113  baudrate_ (baudrate), parity_ (parity),
114  bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
115 {
116  pthread_mutex_init(&this->read_mutex, NULL);
117  pthread_mutex_init(&this->write_mutex, NULL);
118  if (port_.empty () == false)
119  open ();
120 }
121 
123 {
124  close();
125  pthread_mutex_destroy(&this->read_mutex);
126  pthread_mutex_destroy(&this->write_mutex);
127 }
128 
129 void
131 {
132  if (port_.empty ()) {
133  throw invalid_argument ("Empty port is invalid.");
134  }
135  if (is_open_ == true) {
136  throw SerialException ("Serial port already open.");
137  }
138 
139  fd_ = ::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
140 
141  if (fd_ == -1) {
142  switch (errno) {
143  case EINTR:
144  // Recurse because this is a recoverable error.
145  open ();
146  return;
147  case ENFILE:
148  case EMFILE:
149  THROW (IOException, "Too many file handles open.");
150  default:
151  THROW (IOException, errno);
152  }
153  }
154 
155  reconfigurePort();
156  is_open_ = true;
157 }
158 
159 void
161 {
162  if (fd_ == -1) {
163  // Can only operate on a valid file descriptor
164  THROW (IOException, "Invalid file descriptor, is the serial port open?");
165  }
166 
167  struct termios options; // The options for the file descriptor
168 
169  if (tcgetattr(fd_, &options) == -1) {
170  THROW (IOException, "::tcgetattr");
171  }
172 
173  // set up raw mode / no echo / binary
174  options.c_cflag |= (tcflag_t) (CLOCAL | CREAD);
175  options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
176  ISIG | IEXTEN); //|ECHOPRT
177 
178  options.c_oflag &= (tcflag_t) ~(OPOST);
179  options.c_iflag &= (tcflag_t) ~(INLCR | IGNCR | ICRNL | IGNBRK);
180 #ifdef IUCLC
181  options.c_iflag &= (tcflag_t) ~IUCLC;
182 #endif
183 #ifdef PARMRK
184  options.c_iflag &= (tcflag_t) ~PARMRK;
185 #endif
186 
187  // setup baud rate
188  bool custom_baud = false;
189  speed_t baud;
190  switch (baudrate_) {
191 #ifdef B0
192  case 0: baud = B0; break;
193 #endif
194 #ifdef B50
195  case 50: baud = B50; break;
196 #endif
197 #ifdef B75
198  case 75: baud = B75; break;
199 #endif
200 #ifdef B110
201  case 110: baud = B110; break;
202 #endif
203 #ifdef B134
204  case 134: baud = B134; break;
205 #endif
206 #ifdef B150
207  case 150: baud = B150; break;
208 #endif
209 #ifdef B200
210  case 200: baud = B200; break;
211 #endif
212 #ifdef B300
213  case 300: baud = B300; break;
214 #endif
215 #ifdef B600
216  case 600: baud = B600; break;
217 #endif
218 #ifdef B1200
219  case 1200: baud = B1200; break;
220 #endif
221 #ifdef B1800
222  case 1800: baud = B1800; break;
223 #endif
224 #ifdef B2400
225  case 2400: baud = B2400; break;
226 #endif
227 #ifdef B4800
228  case 4800: baud = B4800; break;
229 #endif
230 #ifdef B7200
231  case 7200: baud = B7200; break;
232 #endif
233 #ifdef B9600
234  case 9600: baud = B9600; break;
235 #endif
236 #ifdef B14400
237  case 14400: baud = B14400; break;
238 #endif
239 #ifdef B19200
240  case 19200: baud = B19200; break;
241 #endif
242 #ifdef B28800
243  case 28800: baud = B28800; break;
244 #endif
245 #ifdef B57600
246  case 57600: baud = B57600; break;
247 #endif
248 #ifdef B76800
249  case 76800: baud = B76800; break;
250 #endif
251 #ifdef B38400
252  case 38400: baud = B38400; break;
253 #endif
254 #ifdef B115200
255  case 115200: baud = B115200; break;
256 #endif
257 #ifdef B128000
258  case 128000: baud = B128000; break;
259 #endif
260 #ifdef B153600
261  case 153600: baud = B153600; break;
262 #endif
263 #ifdef B230400
264  case 230400: baud = B230400; break;
265 #endif
266 #ifdef B256000
267  case 256000: baud = B256000; break;
268 #endif
269 #ifdef B460800
270  case 460800: baud = B460800; break;
271 #endif
272 #ifdef B500000
273  case 500000: baud = B500000; break;
274 #endif
275 #ifdef B576000
276  case 576000: baud = B576000; break;
277 #endif
278 #ifdef B921600
279  case 921600: baud = B921600; break;
280 #endif
281 #ifdef B1000000
282  case 1000000: baud = B1000000; break;
283 #endif
284 #ifdef B1152000
285  case 1152000: baud = B1152000; break;
286 #endif
287 #ifdef B1500000
288  case 1500000: baud = B1500000; break;
289 #endif
290 #ifdef B2000000
291  case 2000000: baud = B2000000; break;
292 #endif
293 #ifdef B2500000
294  case 2500000: baud = B2500000; break;
295 #endif
296 #ifdef B3000000
297  case 3000000: baud = B3000000; break;
298 #endif
299 #ifdef B3500000
300  case 3500000: baud = B3500000; break;
301 #endif
302 #ifdef B4000000
303  case 4000000: baud = B4000000; break;
304 #endif
305  default:
306  custom_baud = true;
307  // OS X support
308 #if defined(MAC_OS_X_VERSION_10_4) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_4)
309  // Starting with Tiger, the IOSSIOSPEED ioctl can be used to set arbitrary baud rates
310  // other than those specified by POSIX. The driver for the underlying serial hardware
311  // ultimately determines which baud rates can be used. This ioctl sets both the input
312  // and output speed.
313  speed_t new_baud = static_cast<speed_t> (baudrate_);
314  if (-1 == ioctl (fd_, IOSSIOSPEED, &new_baud, 1)) {
315  THROW (IOException, errno);
316  }
317  // Linux Support
318 #elif defined(__linux__) && defined (TIOCSSERIAL)
319  struct serial_struct ser;
320 
321  if (-1 == ioctl (fd_, TIOCGSERIAL, &ser)) {
322  THROW (IOException, errno);
323  }
324 
325  // set custom divisor
326  ser.custom_divisor = ser.baud_base / static_cast<int> (baudrate_);
327  // update flags
328  ser.flags &= ~ASYNC_SPD_MASK;
329  ser.flags |= ASYNC_SPD_CUST;
330 
331  if (-1 == ioctl (fd_, TIOCSSERIAL, &ser)) {
332  THROW (IOException, errno);
333  }
334 #else
335  throw invalid_argument ("OS does not currently support custom bauds");
336 #endif
337  }
338  if (custom_baud == false) {
339 #ifdef _BSD_SOURCE
340  ::cfsetspeed(&options, baud);
341 #else
342  ::cfsetispeed(&options, baud);
343  ::cfsetospeed(&options, baud);
344 #endif
345  }
346 
347  // setup char len
348  options.c_cflag &= (tcflag_t) ~CSIZE;
349  if (bytesize_ == eightbits)
350  options.c_cflag |= CS8;
351  else if (bytesize_ == sevenbits)
352  options.c_cflag |= CS7;
353  else if (bytesize_ == sixbits)
354  options.c_cflag |= CS6;
355  else if (bytesize_ == fivebits)
356  options.c_cflag |= CS5;
357  else
358  throw invalid_argument ("invalid char len");
359  // setup stopbits
360  if (stopbits_ == stopbits_one)
361  options.c_cflag &= (tcflag_t) ~(CSTOPB);
363  // ONE POINT FIVE same as TWO.. there is no POSIX support for 1.5
364  options.c_cflag |= (CSTOPB);
365  else if (stopbits_ == stopbits_two)
366  options.c_cflag |= (CSTOPB);
367  else
368  throw invalid_argument ("invalid stop bit");
369  // setup parity
370  options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP);
371  if (parity_ == parity_none) {
372  options.c_cflag &= (tcflag_t) ~(PARENB | PARODD);
373  } else if (parity_ == parity_even) {
374  options.c_cflag &= (tcflag_t) ~(PARODD);
375  options.c_cflag |= (PARENB);
376  } else if (parity_ == parity_odd) {
377  options.c_cflag |= (PARENB | PARODD);
378  }
379 #ifdef CMSPAR
380  else if (parity_ == parity_mark) {
381  options.c_cflag |= (PARENB | CMSPAR | PARODD);
382  }
383  else if (parity_ == parity_space) {
384  options.c_cflag |= (PARENB | CMSPAR);
385  options.c_cflag &= (tcflag_t) ~(PARODD);
386  }
387 #else
388  // CMSPAR is not defined on OSX. So do not support mark or space parity.
389  else if (parity_ == parity_mark || parity_ == parity_space) {
390  throw invalid_argument ("OS does not support mark or space parity");
391  }
392 #endif // ifdef CMSPAR
393  else {
394  throw invalid_argument ("invalid parity");
395  }
396  // setup flow control
398  xonxoff_ = false;
399  rtscts_ = false;
400  }
402  xonxoff_ = true;
403  rtscts_ = false;
404  }
406  xonxoff_ = false;
407  rtscts_ = true;
408  }
409  // xonxoff
410 #ifdef IXANY
411  if (xonxoff_)
412  options.c_iflag |= (IXON | IXOFF); //|IXANY)
413  else
414  options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY);
415 #else
416  if (xonxoff_)
417  options.c_iflag |= (IXON | IXOFF);
418  else
419  options.c_iflag &= (tcflag_t) ~(IXON | IXOFF);
420 #endif
421  // rtscts
422 #ifdef CRTSCTS
423  if (rtscts_)
424  options.c_cflag |= (CRTSCTS);
425  else
426  options.c_cflag &= (unsigned long) ~(CRTSCTS);
427 #elif defined CNEW_RTSCTS
428  if (rtscts_)
429  options.c_cflag |= (CNEW_RTSCTS);
430  else
431  options.c_cflag &= (unsigned long) ~(CNEW_RTSCTS);
432 #else
433 #error "OS Support seems wrong."
434 #endif
435 
436  // http://www.unixwiz.net/techtips/termios-vmin-vtime.html
437  // this basically sets the read call up to be a polling read,
438  // but we are using select to ensure there is data available
439  // to read before each call, so we should never needlessly poll
440  options.c_cc[VMIN] = 0;
441  options.c_cc[VTIME] = 0;
442 
443  // activate settings
444  ::tcsetattr (fd_, TCSANOW, &options);
445 
446  // Update byte_time_ based on the new settings.
447  uint32_t bit_time_ns = 1e9 / baudrate_;
448  byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
449 
450  // Compensate for the stopbits_one_point_five enum being equal to int 3,
451  // and not 1.5.
453  byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns);
454  }
455 }
456 
457 void
459 {
460  if (is_open_ == true) {
461  if (fd_ != -1) {
462  int ret;
463  ret = ::close (fd_);
464  if (ret == 0) {
465  fd_ = -1;
466  } else {
467  THROW (IOException, errno);
468  }
469  }
470  is_open_ = false;
471  }
472 }
473 
474 bool
476 {
477  return is_open_;
478 }
479 
480 size_t
482 {
483  if (!is_open_) {
484  return 0;
485  }
486  int count = 0;
487  if (-1 == ioctl (fd_, TIOCINQ, &count)) {
488  THROW (IOException, errno);
489  } else {
490  return static_cast<size_t> (count);
491  }
492 }
493 
494 bool
496 {
497  // Setup a select call to block for serial data or a timeout
498  fd_set readfds;
499  FD_ZERO (&readfds);
500  FD_SET (fd_, &readfds);
501  timespec timeout_ts (timespec_from_ms (timeout));
502  int r = pselect (fd_ + 1, &readfds, NULL, NULL, &timeout_ts, NULL);
503 
504  if (r < 0) {
505  // Select was interrupted
506  if (errno == EINTR) {
507  return false;
508  }
509  // Otherwise there was some error
510  THROW (IOException, errno);
511  }
512  // Timeout occurred
513  if (r == 0) {
514  return false;
515  }
516  // This shouldn't happen, if r > 0 our fd has to be in the list!
517  if (!FD_ISSET (fd_, &readfds)) {
518  THROW (IOException, "select reports ready to read, but our fd isn't"
519  " in the list, this shouldn't happen!");
520  }
521  // Data available to read.
522  return true;
523 }
524 
525 void
527 {
528  timespec wait_time = { 0, static_cast<long>(byte_time_ns_ * count)};
529  pselect (0, NULL, NULL, NULL, &wait_time, NULL);
530 }
531 
532 size_t
533 Serial::SerialImpl::read (uint8_t *buf, size_t size)
534 {
535  // If the port is not open, throw
536  if (!is_open_) {
537  throw PortNotOpenedException ("Serial::read");
538  }
539  size_t bytes_read = 0;
540 
541  // Calculate total timeout in milliseconds t_c + (t_m * N)
542  long total_timeout_ms = timeout_.read_timeout_constant;
543  total_timeout_ms += timeout_.read_timeout_multiplier * static_cast<long> (size);
544  MillisecondTimer total_timeout(total_timeout_ms);
545 
546  // Pre-fill buffer with available bytes
547  {
548  ssize_t bytes_read_now = ::read (fd_, buf, size);
549  if (bytes_read_now > 0) {
550  bytes_read = bytes_read_now;
551  }
552  }
553 
554  while (bytes_read < size) {
555  int64_t timeout_remaining_ms = total_timeout.remaining();
556  if (timeout_remaining_ms <= 0) {
557  // Timed out
558  break;
559  }
560  // Timeout for the next select is whichever is less of the remaining
561  // total read timeout and the inter-byte timeout.
562  uint32_t timeout = std::min(static_cast<uint32_t> (timeout_remaining_ms),
564  // Wait for the device to be readable, and then attempt to read.
565  if (waitReadable(timeout)) {
566  // If it's a fixed-length multi-byte read, insert a wait here so that
567  // we can attempt to grab the whole thing in a single IO call. Skip
568  // this wait if a non-max inter_byte_timeout is specified.
569  if (size > 1 && timeout_.inter_byte_timeout == Timeout::max()) {
570  size_t bytes_available = available();
571  if (bytes_available + bytes_read < size) {
572  waitByteTimes(size - (bytes_available + bytes_read));
573  }
574  }
575  // This should be non-blocking returning only what is available now
576  // Then returning so that select can block again.
577  ssize_t bytes_read_now =
578  ::read (fd_, buf + bytes_read, size - bytes_read);
579  // read should always return some data as select reported it was
580  // ready to read when we get to this point.
581  if (bytes_read_now < 1) {
582  // Disconnected devices, at least on Linux, show the
583  // behavior that they are always ready to read immediately
584  // but reading returns nothing.
585  throw SerialException ("device reports readiness to read but "
586  "returned no data (device disconnected?)");
587  }
588  // Update bytes_read
589  bytes_read += static_cast<size_t> (bytes_read_now);
590  // If bytes_read == size then we have read everything we need
591  if (bytes_read == size) {
592  break;
593  }
594  // If bytes_read < size then we have more to read
595  if (bytes_read < size) {
596  continue;
597  }
598  // If bytes_read > size then we have over read, which shouldn't happen
599  if (bytes_read > size) {
600  throw SerialException ("read over read, too many bytes where "
601  "read, this shouldn't happen, might be "
602  "a logical error!");
603  }
604  }
605  }
606  return bytes_read;
607 }
608 
609 size_t
610 Serial::SerialImpl::write (const uint8_t *data, size_t length)
611 {
612  if (is_open_ == false) {
613  throw PortNotOpenedException ("Serial::write");
614  }
615  fd_set writefds;
616  size_t bytes_written = 0;
617 
618  // Calculate total timeout in milliseconds t_c + (t_m * N)
619  long total_timeout_ms = timeout_.write_timeout_constant;
620  total_timeout_ms += timeout_.write_timeout_multiplier * static_cast<long> (length);
621  MillisecondTimer total_timeout(total_timeout_ms);
622 
623  bool first_iteration = true;
624  while (bytes_written < length) {
625  int64_t timeout_remaining_ms = total_timeout.remaining();
626  // Only consider the timeout if it's not the first iteration of the loop
627  // otherwise a timeout of 0 won't be allowed through
628  if (!first_iteration && (timeout_remaining_ms <= 0)) {
629  // Timed out
630  break;
631  }
632  first_iteration = false;
633 
634  timespec timeout(timespec_from_ms(timeout_remaining_ms));
635 
636  FD_ZERO (&writefds);
637  FD_SET (fd_, &writefds);
638 
639  // Do the select
640  int r = pselect (fd_ + 1, NULL, &writefds, NULL, &timeout, NULL);
641 
642  // Figure out what happened by looking at select's response 'r'
644  if (r < 0) {
645  // Select was interrupted, try again
646  if (errno == EINTR) {
647  continue;
648  }
649  // Otherwise there was some error
650  THROW (IOException, errno);
651  }
653  if (r == 0) {
654  break;
655  }
657  if (r > 0) {
658  // Make sure our file descriptor is in the ready to write list
659  if (FD_ISSET (fd_, &writefds)) {
660  // This will write some
661  ssize_t bytes_written_now =
662  ::write (fd_, data + bytes_written, length - bytes_written);
663  // write should always return some data as select reported it was
664  // ready to write when we get to this point.
665  if (bytes_written_now < 1) {
666  // Disconnected devices, at least on Linux, show the
667  // behavior that they are always ready to write immediately
668  // but writing returns nothing.
669  throw SerialException ("device reports readiness to write but "
670  "returned no data (device disconnected?)");
671  }
672  // Update bytes_written
673  bytes_written += static_cast<size_t> (bytes_written_now);
674  // If bytes_written == size then we have written everything we need to
675  if (bytes_written == length) {
676  break;
677  }
678  // If bytes_written < size then we have more to write
679  if (bytes_written < length) {
680  continue;
681  }
682  // If bytes_written > size then we have over written, which shouldn't happen
683  if (bytes_written > length) {
684  throw SerialException ("write over wrote, too many bytes where "
685  "written, this shouldn't happen, might be "
686  "a logical error!");
687  }
688  }
689  // This shouldn't happen, if r > 0 our fd has to be in the list!
690  THROW (IOException, "select reports ready to write, but our fd isn't"
691  " in the list, this shouldn't happen!");
692  }
693  }
694  return bytes_written;
695 }
696 
697 void
698 Serial::SerialImpl::setPort (const string &port)
699 {
700  port_ = port;
701 }
702 
703 string
705 {
706  return port_;
707 }
708 
709 void
711 {
712  timeout_ = timeout;
713 }
714 
717 {
718  return timeout_;
719 }
720 
721 void
722 Serial::SerialImpl::setBaudrate (unsigned long baudrate)
723 {
724  baudrate_ = baudrate;
725  if (is_open_)
726  reconfigurePort ();
727 }
728 
729 unsigned long
731 {
732  return baudrate_;
733 }
734 
735 void
737 {
738  bytesize_ = bytesize;
739  if (is_open_)
740  reconfigurePort ();
741 }
742 
745 {
746  return bytesize_;
747 }
748 
749 void
751 {
752  parity_ = parity;
753  if (is_open_)
754  reconfigurePort ();
755 }
756 
759 {
760  return parity_;
761 }
762 
763 void
765 {
766  stopbits_ = stopbits;
767  if (is_open_)
768  reconfigurePort ();
769 }
770 
773 {
774  return stopbits_;
775 }
776 
777 void
779 {
780  flowcontrol_ = flowcontrol;
781  if (is_open_)
782  reconfigurePort ();
783 }
784 
787 {
788  return flowcontrol_;
789 }
790 
791 void
793 {
794  if (is_open_ == false) {
795  throw PortNotOpenedException ("Serial::flush");
796  }
797  tcdrain (fd_);
798 }
799 
800 void
802 {
803  if (is_open_ == false) {
804  throw PortNotOpenedException ("Serial::flushInput");
805  }
806  tcflush (fd_, TCIFLUSH);
807 }
808 
809 void
811 {
812  if (is_open_ == false) {
813  throw PortNotOpenedException ("Serial::flushOutput");
814  }
815  tcflush (fd_, TCOFLUSH);
816 }
817 
818 void
820 {
821  if (is_open_ == false) {
822  throw PortNotOpenedException ("Serial::sendBreak");
823  }
824  tcsendbreak (fd_, static_cast<int> (duration / 4));
825 }
826 
827 void
829 {
830  if (is_open_ == false) {
831  throw PortNotOpenedException ("Serial::setBreak");
832  }
833 
834  if (level) {
835  if (-1 == ioctl (fd_, TIOCSBRK))
836  {
837  stringstream ss;
838  ss << "setBreak failed on a call to ioctl(TIOCSBRK): " << errno << " " << strerror(errno);
839  throw(SerialException(ss.str().c_str()));
840  }
841  } else {
842  if (-1 == ioctl (fd_, TIOCCBRK))
843  {
844  stringstream ss;
845  ss << "setBreak failed on a call to ioctl(TIOCCBRK): " << errno << " " << strerror(errno);
846  throw(SerialException(ss.str().c_str()));
847  }
848  }
849 }
850 
851 void
853 {
854  if (is_open_ == false) {
855  throw PortNotOpenedException ("Serial::setRTS");
856  }
857 
858  int command = TIOCM_RTS;
859 
860  if (level) {
861  if (-1 == ioctl (fd_, TIOCMBIS, &command))
862  {
863  stringstream ss;
864  ss << "setRTS failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
865  throw(SerialException(ss.str().c_str()));
866  }
867  } else {
868  if (-1 == ioctl (fd_, TIOCMBIC, &command))
869  {
870  stringstream ss;
871  ss << "setRTS failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
872  throw(SerialException(ss.str().c_str()));
873  }
874  }
875 }
876 
877 void
879 {
880  if (is_open_ == false) {
881  throw PortNotOpenedException ("Serial::setDTR");
882  }
883 
884  int command = TIOCM_DTR;
885 
886  if (level) {
887  if (-1 == ioctl (fd_, TIOCMBIS, &command))
888  {
889  stringstream ss;
890  ss << "setDTR failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
891  throw(SerialException(ss.str().c_str()));
892  }
893  } else {
894  if (-1 == ioctl (fd_, TIOCMBIC, &command))
895  {
896  stringstream ss;
897  ss << "setDTR failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
898  throw(SerialException(ss.str().c_str()));
899  }
900  }
901 }
902 
903 bool
905 {
906 #ifndef TIOCMIWAIT
907 
908 while (is_open_ == true) {
909 
910  int status;
911 
912  if (-1 == ioctl (fd_, TIOCMGET, &status))
913  {
914  stringstream ss;
915  ss << "waitForChange failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
916  throw(SerialException(ss.str().c_str()));
917  }
918  else
919  {
920  if (0 != (status & TIOCM_CTS)
921  || 0 != (status & TIOCM_DSR)
922  || 0 != (status & TIOCM_RI)
923  || 0 != (status & TIOCM_CD))
924  {
925  return true;
926  }
927  }
928 
929  usleep(1000);
930  }
931 
932  return false;
933 #else
934  int command = (TIOCM_CD|TIOCM_DSR|TIOCM_RI|TIOCM_CTS);
935 
936  if (-1 == ioctl (fd_, TIOCMIWAIT, &command)) {
937  stringstream ss;
938  ss << "waitForDSR failed on a call to ioctl(TIOCMIWAIT): "
939  << errno << " " << strerror(errno);
940  throw(SerialException(ss.str().c_str()));
941  }
942  return true;
943 #endif
944 }
945 
946 bool
948 {
949  if (is_open_ == false) {
950  throw PortNotOpenedException ("Serial::getCTS");
951  }
952 
953  int status;
954 
955  if (-1 == ioctl (fd_, TIOCMGET, &status))
956  {
957  stringstream ss;
958  ss << "getCTS failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
959  throw(SerialException(ss.str().c_str()));
960  }
961  else
962  {
963  return 0 != (status & TIOCM_CTS);
964  }
965 }
966 
967 bool
969 {
970  if (is_open_ == false) {
971  throw PortNotOpenedException ("Serial::getDSR");
972  }
973 
974  int status;
975 
976  if (-1 == ioctl (fd_, TIOCMGET, &status))
977  {
978  stringstream ss;
979  ss << "getDSR failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
980  throw(SerialException(ss.str().c_str()));
981  }
982  else
983  {
984  return 0 != (status & TIOCM_DSR);
985  }
986 }
987 
988 bool
990 {
991  if (is_open_ == false) {
992  throw PortNotOpenedException ("Serial::getRI");
993  }
994 
995  int status;
996 
997  if (-1 == ioctl (fd_, TIOCMGET, &status))
998  {
999  stringstream ss;
1000  ss << "getRI failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
1001  throw(SerialException(ss.str().c_str()));
1002  }
1003  else
1004  {
1005  return 0 != (status & TIOCM_RI);
1006  }
1007 }
1008 
1009 bool
1011 {
1012  if (is_open_ == false) {
1013  throw PortNotOpenedException ("Serial::getCD");
1014  }
1015 
1016  int status;
1017 
1018  if (-1 == ioctl (fd_, TIOCMGET, &status))
1019  {
1020  stringstream ss;
1021  ss << "getCD failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
1022  throw(SerialException(ss.str().c_str()));
1023  }
1024  else
1025  {
1026  return 0 != (status & TIOCM_CD);
1027  }
1028 }
1029 
1030 void
1032 {
1033  int result = pthread_mutex_lock(&this->read_mutex);
1034  if (result) {
1035  THROW (IOException, result);
1036  }
1037 }
1038 
1039 void
1041 {
1042  int result = pthread_mutex_unlock(&this->read_mutex);
1043  if (result) {
1044  THROW (IOException, result);
1045  }
1046 }
1047 
1048 void
1050 {
1051  int result = pthread_mutex_lock(&this->write_mutex);
1052  if (result) {
1053  THROW (IOException, result);
1054  }
1055 }
1056 
1057 void
1059 {
1060  int result = pthread_mutex_unlock(&this->write_mutex);
1061  if (result) {
1062  THROW (IOException, result);
1063  }
1064 }
1065 
1066 #endif // !defined(_WIN32)
uint32_t write_timeout_constant
Definition: serial.h:125
int64_t remaining()
Definition: unix.cc:73
void setBytesize(bytesize_t bytesize)
Definition: unix.cc:736
pthread_mutex_t read_mutex
Definition: unix.h:212
uint32_t byte_time_ns_
Definition: unix.h:204
void waitByteTimes(size_t count)
Definition: unix.cc:526
void setRTS(bool level)
Definition: unix.cc:852
static uint32_t max()
Definition: serial.h:102
string getPort() const
Definition: unix.cc:704
void setStopbits(stopbits_t stopbits)
Definition: unix.cc:764
static timespec timespec_now()
Definition: unix.cc:82
Timeout getTimeout() const
Definition: unix.cc:716
void setBaudrate(unsigned long baudrate)
Definition: unix.cc:722
#define TIOCINQ
Definition: unix.cc:41
bytesize_t bytesize_
Definition: unix.h:207
parity_t
Definition: serial.h:66
size_t read(uint8_t *buf, size_t size=1)
Definition: unix.cc:533
bytesize_t
Definition: serial.h:56
stopbits_t getStopbits() const
Definition: unix.cc:772
pthread_mutex_t write_mutex
Definition: unix.h:214
flowcontrol_t flowcontrol_
Definition: unix.h:209
void setDTR(bool level)
Definition: unix.cc:878
uint32_t read_timeout_multiplier
Definition: serial.h:123
stopbits_t stopbits_
Definition: unix.h:208
uint32_t read_timeout_constant
Definition: serial.h:119
unsigned long baudrate_
Definition: unix.h:203
parity_t getParity() const
Definition: unix.cc:758
bytesize_t getBytesize() const
Definition: unix.cc:744
#define THROW(exceptionClass, message)
Definition: serial.h:48
bool waitReadable(uint32_t timeout)
Definition: unix.cc:495
bool isOpen() const
Definition: unix.cc:475
SerialImpl(const string &port, unsigned long baudrate, bytesize_t bytesize, parity_t parity, stopbits_t stopbits, flowcontrol_t flowcontrol)
Definition: unix.cc:108
void setParity(parity_t parity)
Definition: unix.cc:750
void sendBreak(int duration)
Definition: unix.cc:819
unsigned long getBaudrate() const
Definition: unix.cc:730
stopbits_t
Definition: serial.h:77
void setFlowcontrol(flowcontrol_t flowcontrol)
Definition: unix.cc:778
uint32_t write_timeout_multiplier
Definition: serial.h:129
uint32_t inter_byte_timeout
Definition: serial.h:117
void setTimeout(Timeout &timeout)
Definition: unix.cc:710
flowcontrol_t getFlowcontrol() const
Definition: unix.cc:786
size_t write(const uint8_t *data, size_t length)
Definition: unix.cc:610
timespec timespec_from_ms(const uint32_t millis)
Definition: unix.cc:100
void setPort(const string &port)
Definition: unix.cc:698
void setBreak(bool level)
Definition: unix.cc:828
flowcontrol_t
Definition: serial.h:86


serial
Author(s): William Woodall , John Harrison
autogenerated on Thu Jan 9 2020 07:18:58