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 * sec_diff);
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(), CALENDAR_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_REALTIME, &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 B576000
273  case 576000: baud = B576000; break;
274 #endif
275 #ifdef B921600
276  case 921600: baud = B921600; break;
277 #endif
278 #ifdef B1000000
279  case 1000000: baud = B1000000; break;
280 #endif
281 #ifdef B1152000
282  case 1152000: baud = B1152000; break;
283 #endif
284 #ifdef B1500000
285  case 1500000: baud = B1500000; break;
286 #endif
287 #ifdef B2000000
288  case 2000000: baud = B2000000; break;
289 #endif
290 #ifdef B2500000
291  case 2500000: baud = B2500000; break;
292 #endif
293 #ifdef B3000000
294  case 3000000: baud = B3000000; break;
295 #endif
296 #ifdef B3500000
297  case 3500000: baud = B3500000; break;
298 #endif
299 #ifdef B4000000
300  case 4000000: baud = B4000000; break;
301 #endif
302  default:
303  custom_baud = true;
304  // OS X support
305 #if defined(MAC_OS_X_VERSION_10_4) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_4)
306  // Starting with Tiger, the IOSSIOSPEED ioctl can be used to set arbitrary baud rates
307  // other than those specified by POSIX. The driver for the underlying serial hardware
308  // ultimately determines which baud rates can be used. This ioctl sets both the input
309  // and output speed.
310  speed_t new_baud = static_cast<speed_t> (baudrate_);
311  if (-1 == ioctl (fd_, IOSSIOSPEED, &new_baud, 1)) {
312  THROW (IOException, errno);
313  }
314  // Linux Support
315 #elif defined(__linux__) && defined (TIOCSSERIAL)
316  struct serial_struct ser;
317 
318  if (-1 == ioctl (fd_, TIOCGSERIAL, &ser)) {
319  THROW (IOException, errno);
320  }
321 
322  // set custom divisor
323  ser.custom_divisor = ser.baud_base / static_cast<int> (baudrate_);
324  // update flags
325  ser.flags &= ~ASYNC_SPD_MASK;
326  ser.flags |= ASYNC_SPD_CUST;
327 
328  if (-1 == ioctl (fd_, TIOCSSERIAL, &ser)) {
329  THROW (IOException, errno);
330  }
331 #else
332  throw invalid_argument ("OS does not currently support custom bauds");
333 #endif
334  }
335  if (custom_baud == false) {
336 #ifdef _BSD_SOURCE
337  ::cfsetspeed(&options, baud);
338 #else
339  ::cfsetispeed(&options, baud);
340  ::cfsetospeed(&options, baud);
341 #endif
342  }
343 
344  // setup char len
345  options.c_cflag &= (tcflag_t) ~CSIZE;
346  if (bytesize_ == eightbits)
347  options.c_cflag |= CS8;
348  else if (bytesize_ == sevenbits)
349  options.c_cflag |= CS7;
350  else if (bytesize_ == sixbits)
351  options.c_cflag |= CS6;
352  else if (bytesize_ == fivebits)
353  options.c_cflag |= CS5;
354  else
355  throw invalid_argument ("invalid char len");
356  // setup stopbits
357  if (stopbits_ == stopbits_one)
358  options.c_cflag &= (tcflag_t) ~(CSTOPB);
359  else if (stopbits_ == stopbits_one_point_five)
360  // ONE POINT FIVE same as TWO.. there is no POSIX support for 1.5
361  options.c_cflag |= (CSTOPB);
362  else if (stopbits_ == stopbits_two)
363  options.c_cflag |= (CSTOPB);
364  else
365  throw invalid_argument ("invalid stop bit");
366  // setup parity
367  options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP);
368  if (parity_ == parity_none) {
369  options.c_cflag &= (tcflag_t) ~(PARENB | PARODD);
370  } else if (parity_ == parity_even) {
371  options.c_cflag &= (tcflag_t) ~(PARODD);
372  options.c_cflag |= (PARENB);
373  } else if (parity_ == parity_odd) {
374  options.c_cflag |= (PARENB | PARODD);
375  }
376 #ifdef CMSPAR
377  else if (parity_ == parity_mark) {
378  options.c_cflag |= (PARENB | CMSPAR | PARODD);
379  }
380  else if (parity_ == parity_space) {
381  options.c_cflag |= (PARENB | CMSPAR);
382  options.c_cflag &= (tcflag_t) ~(PARODD);
383  }
384 #else
385  // CMSPAR is not defined on OSX. So do not support mark or space parity.
386  else if (parity_ == parity_mark || parity_ == parity_space) {
387  throw invalid_argument ("OS does not support mark or space parity");
388  }
389 #endif // ifdef CMSPAR
390  else {
391  throw invalid_argument ("invalid parity");
392  }
393  // setup flow control
394  if (flowcontrol_ == flowcontrol_none) {
395  xonxoff_ = false;
396  rtscts_ = false;
397  }
398  if (flowcontrol_ == flowcontrol_software) {
399  xonxoff_ = true;
400  rtscts_ = false;
401  }
402  if (flowcontrol_ == flowcontrol_hardware) {
403  xonxoff_ = false;
404  rtscts_ = true;
405  }
406  // xonxoff
407 #ifdef IXANY
408  if (xonxoff_)
409  options.c_iflag |= (IXON | IXOFF); //|IXANY)
410  else
411  options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY);
412 #else
413  if (xonxoff_)
414  options.c_iflag |= (IXON | IXOFF);
415  else
416  options.c_iflag &= (tcflag_t) ~(IXON | IXOFF);
417 #endif
418  // rtscts
419 #ifdef CRTSCTS
420  if (rtscts_)
421  options.c_cflag |= (CRTSCTS);
422  else
423  options.c_cflag &= (unsigned long) ~(CRTSCTS);
424 #elif defined CNEW_RTSCTS
425  if (rtscts_)
426  options.c_cflag |= (CNEW_RTSCTS);
427  else
428  options.c_cflag &= (unsigned long) ~(CNEW_RTSCTS);
429 #else
430 #error "OS Support seems wrong."
431 #endif
432 
433  // http://www.unixwiz.net/techtips/termios-vmin-vtime.html
434  // this basically sets the read call up to be a polling read,
435  // but we are using select to ensure there is data available
436  // to read before each call, so we should never needlessly poll
437  options.c_cc[VMIN] = 0;
438  options.c_cc[VTIME] = 0;
439 
440  // activate settings
441  ::tcsetattr (fd_, TCSANOW, &options);
442 
443  // Update byte_time_ based on the new settings.
444  uint32_t bit_time_ns = 1e9 / baudrate_;
445  byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
446 
447  // Compensate for the stopbits_one_point_five enum being equal to int 3,
448  // and not 1.5.
449  if (stopbits_ == stopbits_one_point_five) {
450  byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns);
451  }
452 }
453 
454 void
456 {
457  if (is_open_ == true) {
458  if (fd_ != -1) {
459  int ret;
460  ret = ::close (fd_);
461  if (ret == 0) {
462  fd_ = -1;
463  } else {
464  THROW (IOException, errno);
465  }
466  }
467  is_open_ = false;
468  }
469 }
470 
471 bool
473 {
474  return is_open_;
475 }
476 
477 size_t
479 {
480  if (!is_open_) {
481  return 0;
482  }
483  int count = 0;
484  if (-1 == ioctl (fd_, TIOCINQ, &count)) {
485  THROW (IOException, errno);
486  } else {
487  return static_cast<size_t> (count);
488  }
489 }
490 
491 bool
493 {
494  // Setup a select call to block for serial data or a timeout
495  fd_set readfds;
496  FD_ZERO (&readfds);
497  FD_SET (fd_, &readfds);
498  timespec timeout_ts (timespec_from_ms (timeout));
499  int r = pselect (fd_ + 1, &readfds, NULL, NULL, &timeout_ts, NULL);
500 
501  if (r < 0) {
502  // Select was interrupted
503  if (errno == EINTR) {
504  return false;
505  }
506  // Otherwise there was some error
507  THROW (IOException, errno);
508  }
509  // Timeout occurred
510  if (r == 0) {
511  return false;
512  }
513  // This shouldn't happen, if r > 0 our fd has to be in the list!
514  if (!FD_ISSET (fd_, &readfds)) {
515  THROW (IOException, "select reports ready to read, but our fd isn't"
516  " in the list, this shouldn't happen!");
517  }
518  // Data available to read.
519  return true;
520 }
521 
522 void
524 {
525  timespec wait_time = { 0, static_cast<long>(byte_time_ns_ * count)};
526  pselect (0, NULL, NULL, NULL, &wait_time, NULL);
527 }
528 
529 size_t
530 Serial::SerialImpl::read (uint8_t *buf, size_t size)
531 {
532  // If the port is not open, throw
533  if (!is_open_) {
534  throw PortNotOpenedException ("Serial::read");
535  }
536  size_t bytes_read = 0;
537 
538  // Calculate total timeout in milliseconds t_c + (t_m * N)
539  long total_timeout_ms = timeout_.read_timeout_constant;
540  total_timeout_ms += timeout_.read_timeout_multiplier * static_cast<long> (size);
541  MillisecondTimer total_timeout(total_timeout_ms);
542 
543  // Pre-fill buffer with available bytes
544  {
545  ssize_t bytes_read_now = ::read (fd_, buf, size);
546  if (bytes_read_now > 0) {
547  bytes_read = bytes_read_now;
548  }
549  }
550 
551  while (bytes_read < size) {
552  int64_t timeout_remaining_ms = total_timeout.remaining();
553  if (timeout_remaining_ms <= 0) {
554  // Timed out
555  break;
556  }
557  // Timeout for the next select is whichever is less of the remaining
558  // total read timeout and the inter-byte timeout.
559  uint32_t timeout = std::min(static_cast<uint32_t> (timeout_remaining_ms),
560  timeout_.inter_byte_timeout);
561  // Wait for the device to be readable, and then attempt to read.
562  if (waitReadable(timeout)) {
563  // If it's a fixed-length multi-byte read, insert a wait here so that
564  // we can attempt to grab the whole thing in a single IO call. Skip
565  // this wait if a non-max inter_byte_timeout is specified.
566  if (size > 1 && timeout_.inter_byte_timeout == Timeout::max()) {
567  size_t bytes_available = available();
568  if (bytes_available + bytes_read < size) {
569  waitByteTimes(size - (bytes_available + bytes_read));
570  }
571  }
572  // This should be non-blocking returning only what is available now
573  // Then returning so that select can block again.
574  ssize_t bytes_read_now =
575  ::read (fd_, buf + bytes_read, size - bytes_read);
576  // read should always return some data as select reported it was
577  // ready to read when we get to this point.
578  if (bytes_read_now < 1) {
579  // Disconnected devices, at least on Linux, show the
580  // behavior that they are always ready to read immediately
581  // but reading returns nothing.
582  throw SerialException ("device reports readiness to read but "
583  "returned no data (device disconnected?)");
584  }
585  // Update bytes_read
586  bytes_read += static_cast<size_t> (bytes_read_now);
587  // If bytes_read == size then we have read everything we need
588  if (bytes_read == size) {
589  break;
590  }
591  // If bytes_read < size then we have more to read
592  if (bytes_read < size) {
593  continue;
594  }
595  // If bytes_read > size then we have over read, which shouldn't happen
596  if (bytes_read > size) {
597  throw SerialException ("read over read, too many bytes where "
598  "read, this shouldn't happen, might be "
599  "a logical error!");
600  }
601  }
602  }
603  return bytes_read;
604 }
605 
606 size_t
607 Serial::SerialImpl::write (const uint8_t *data, size_t length)
608 {
609  if (is_open_ == false) {
610  throw PortNotOpenedException ("Serial::write");
611  }
612  fd_set writefds;
613  size_t bytes_written = 0;
614 
615  // Calculate total timeout in milliseconds t_c + (t_m * N)
616  long total_timeout_ms = timeout_.write_timeout_constant;
617  total_timeout_ms += timeout_.write_timeout_multiplier * static_cast<long> (length);
618  MillisecondTimer total_timeout(total_timeout_ms);
619 
620  while (bytes_written < length) {
621  int64_t timeout_remaining_ms = total_timeout.remaining();
622  if (timeout_remaining_ms <= 0) {
623  // Timed out
624  break;
625  }
626  timespec timeout(timespec_from_ms(timeout_remaining_ms));
627 
628  FD_ZERO (&writefds);
629  FD_SET (fd_, &writefds);
630 
631  // Do the select
632  int r = pselect (fd_ + 1, NULL, &writefds, NULL, &timeout, NULL);
633 
634  // Figure out what happened by looking at select's response 'r'
636  if (r < 0) {
637  // Select was interrupted, try again
638  if (errno == EINTR) {
639  continue;
640  }
641  // Otherwise there was some error
642  THROW (IOException, errno);
643  }
645  if (r == 0) {
646  break;
647  }
649  if (r > 0) {
650  // Make sure our file descriptor is in the ready to write list
651  if (FD_ISSET (fd_, &writefds)) {
652  // This will write some
653  ssize_t bytes_written_now =
654  ::write (fd_, data + bytes_written, length - bytes_written);
655  // write should always return some data as select reported it was
656  // ready to write when we get to this point.
657  if (bytes_written_now < 1) {
658  // Disconnected devices, at least on Linux, show the
659  // behavior that they are always ready to write immediately
660  // but writing returns nothing.
661  throw SerialException ("device reports readiness to write but "
662  "returned no data (device disconnected?)");
663  }
664  // Update bytes_written
665  bytes_written += static_cast<size_t> (bytes_written_now);
666  // If bytes_written == size then we have written everything we need to
667  if (bytes_written == length) {
668  break;
669  }
670  // If bytes_written < size then we have more to write
671  if (bytes_written < length) {
672  continue;
673  }
674  // If bytes_written > size then we have over written, which shouldn't happen
675  if (bytes_written > length) {
676  throw SerialException ("write over wrote, too many bytes where "
677  "written, this shouldn't happen, might be "
678  "a logical error!");
679  }
680  }
681  // This shouldn't happen, if r > 0 our fd has to be in the list!
682  THROW (IOException, "select reports ready to write, but our fd isn't"
683  " in the list, this shouldn't happen!");
684  }
685  }
686  return bytes_written;
687 }
688 
689 void
690 Serial::SerialImpl::setPort (const string &port)
691 {
692  port_ = port;
693 }
694 
695 string
697 {
698  return port_;
699 }
700 
701 void
703 {
704  timeout_ = timeout;
705 }
706 
709 {
710  return timeout_;
711 }
712 
713 void
714 Serial::SerialImpl::setBaudrate (unsigned long baudrate)
715 {
716  baudrate_ = baudrate;
717  if (is_open_)
718  reconfigurePort ();
719 }
720 
721 unsigned long
723 {
724  return baudrate_;
725 }
726 
727 void
729 {
730  bytesize_ = bytesize;
731  if (is_open_)
732  reconfigurePort ();
733 }
734 
737 {
738  return bytesize_;
739 }
740 
741 void
743 {
744  parity_ = parity;
745  if (is_open_)
746  reconfigurePort ();
747 }
748 
751 {
752  return parity_;
753 }
754 
755 void
757 {
758  stopbits_ = stopbits;
759  if (is_open_)
760  reconfigurePort ();
761 }
762 
765 {
766  return stopbits_;
767 }
768 
769 void
771 {
772  flowcontrol_ = flowcontrol;
773  if (is_open_)
774  reconfigurePort ();
775 }
776 
779 {
780  return flowcontrol_;
781 }
782 
783 void
785 {
786  if (is_open_ == false) {
787  throw PortNotOpenedException ("Serial::flush");
788  }
789  tcdrain (fd_);
790 }
791 
792 void
794 {
795  if (is_open_ == false) {
796  throw PortNotOpenedException ("Serial::flushInput");
797  }
798  tcflush (fd_, TCIFLUSH);
799 }
800 
801 void
803 {
804  if (is_open_ == false) {
805  throw PortNotOpenedException ("Serial::flushOutput");
806  }
807  tcflush (fd_, TCOFLUSH);
808 }
809 
810 void
812 {
813  if (is_open_ == false) {
814  throw PortNotOpenedException ("Serial::sendBreak");
815  }
816  tcsendbreak (fd_, static_cast<int> (duration / 4));
817 }
818 
819 void
821 {
822  if (is_open_ == false) {
823  throw PortNotOpenedException ("Serial::setBreak");
824  }
825 
826  if (level) {
827  if (-1 == ioctl (fd_, TIOCSBRK))
828  {
829  stringstream ss;
830  ss << "setBreak failed on a call to ioctl(TIOCSBRK): " << errno << " " << strerror(errno);
831  throw(SerialException(ss.str().c_str()));
832  }
833  } else {
834  if (-1 == ioctl (fd_, TIOCCBRK))
835  {
836  stringstream ss;
837  ss << "setBreak failed on a call to ioctl(TIOCCBRK): " << errno << " " << strerror(errno);
838  throw(SerialException(ss.str().c_str()));
839  }
840  }
841 }
842 
843 void
845 {
846  if (is_open_ == false) {
847  throw PortNotOpenedException ("Serial::setRTS");
848  }
849 
850  int command = TIOCM_RTS;
851 
852  if (level) {
853  if (-1 == ioctl (fd_, TIOCMBIS, &command))
854  {
855  stringstream ss;
856  ss << "setRTS failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
857  throw(SerialException(ss.str().c_str()));
858  }
859  } else {
860  if (-1 == ioctl (fd_, TIOCMBIC, &command))
861  {
862  stringstream ss;
863  ss << "setRTS failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
864  throw(SerialException(ss.str().c_str()));
865  }
866  }
867 }
868 
869 void
871 {
872  if (is_open_ == false) {
873  throw PortNotOpenedException ("Serial::setDTR");
874  }
875 
876  int command = TIOCM_DTR;
877 
878  if (level) {
879  if (-1 == ioctl (fd_, TIOCMBIS, &command))
880  {
881  stringstream ss;
882  ss << "setDTR failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
883  throw(SerialException(ss.str().c_str()));
884  }
885  } else {
886  if (-1 == ioctl (fd_, TIOCMBIC, &command))
887  {
888  stringstream ss;
889  ss << "setDTR failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
890  throw(SerialException(ss.str().c_str()));
891  }
892  }
893 }
894 
895 bool
897 {
898 #ifndef TIOCMIWAIT
899 
900 while (is_open_ == true) {
901 
902  int status;
903 
904  if (-1 == ioctl (fd_, TIOCMGET, &status))
905  {
906  stringstream ss;
907  ss << "waitForChange failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
908  throw(SerialException(ss.str().c_str()));
909  }
910  else
911  {
912  if (0 != (status & TIOCM_CTS)
913  || 0 != (status & TIOCM_DSR)
914  || 0 != (status & TIOCM_RI)
915  || 0 != (status & TIOCM_CD))
916  {
917  return true;
918  }
919  }
920 
921  usleep(1000);
922  }
923 
924  return false;
925 #else
926  int command = (TIOCM_CD|TIOCM_DSR|TIOCM_RI|TIOCM_CTS);
927 
928  if (-1 == ioctl (fd_, TIOCMIWAIT, &command)) {
929  stringstream ss;
930  ss << "waitForDSR failed on a call to ioctl(TIOCMIWAIT): "
931  << errno << " " << strerror(errno);
932  throw(SerialException(ss.str().c_str()));
933  }
934  return true;
935 #endif
936 }
937 
938 bool
940 {
941  if (is_open_ == false) {
942  throw PortNotOpenedException ("Serial::getCTS");
943  }
944 
945  int status;
946 
947  if (-1 == ioctl (fd_, TIOCMGET, &status))
948  {
949  stringstream ss;
950  ss << "getCTS failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
951  throw(SerialException(ss.str().c_str()));
952  }
953  else
954  {
955  return 0 != (status & TIOCM_CTS);
956  }
957 }
958 
959 bool
961 {
962  if (is_open_ == false) {
963  throw PortNotOpenedException ("Serial::getDSR");
964  }
965 
966  int status;
967 
968  if (-1 == ioctl (fd_, TIOCMGET, &status))
969  {
970  stringstream ss;
971  ss << "getDSR failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
972  throw(SerialException(ss.str().c_str()));
973  }
974  else
975  {
976  return 0 != (status & TIOCM_DSR);
977  }
978 }
979 
980 bool
982 {
983  if (is_open_ == false) {
984  throw PortNotOpenedException ("Serial::getRI");
985  }
986 
987  int status;
988 
989  if (-1 == ioctl (fd_, TIOCMGET, &status))
990  {
991  stringstream ss;
992  ss << "getRI failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
993  throw(SerialException(ss.str().c_str()));
994  }
995  else
996  {
997  return 0 != (status & TIOCM_RI);
998  }
999 }
1000 
1001 bool
1003 {
1004  if (is_open_ == false) {
1005  throw PortNotOpenedException ("Serial::getCD");
1006  }
1007 
1008  int status;
1009 
1010  if (-1 == ioctl (fd_, TIOCMGET, &status))
1011  {
1012  stringstream ss;
1013  ss << "getCD failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
1014  throw(SerialException(ss.str().c_str()));
1015  }
1016  else
1017  {
1018  return 0 != (status & TIOCM_CD);
1019  }
1020 }
1021 
1022 void
1024 {
1025  int result = pthread_mutex_lock(&this->read_mutex);
1026  if (result) {
1027  THROW (IOException, result);
1028  }
1029 }
1030 
1031 void
1033 {
1034  int result = pthread_mutex_unlock(&this->read_mutex);
1035  if (result) {
1036  THROW (IOException, result);
1037  }
1038 }
1039 
1040 void
1042 {
1043  int result = pthread_mutex_lock(&this->write_mutex);
1044  if (result) {
1045  THROW (IOException, result);
1046  }
1047 }
1048 
1049 void
1051 {
1052  int result = pthread_mutex_unlock(&this->write_mutex);
1053  if (result) {
1054  THROW (IOException, result);
1055  }
1056 }
1057 
1058 #endif // !defined(_WIN32)
serial::parity_t
parity_t
Definition: serial.h:66
timespec_from_ms
timespec timespec_from_ms(const uint32_t millis)
Definition: unix.cc:100
serial::Serial::SerialImpl::close
void close()
Definition: unix.cc:455
serial::parity_mark
@ parity_mark
Definition: serial.h:70
THROW
#define THROW(exceptionClass, message)
Definition: serial.h:48
serial::Serial::SerialImpl::waitReadable
bool waitReadable(uint32_t timeout)
Definition: unix.cc:492
TIOCINQ
#define TIOCINQ
Definition: unix.cc:41
serial::Timeout::max
static uint32_t max()
Definition: serial.h:102
unix.h
serial::Serial::SerialImpl::sendBreak
void sendBreak(int duration)
Definition: unix.cc:811
serial::Serial::SerialImpl::getPort
string getPort() const
Definition: unix.cc:696
command
ROSLIB_DECL std::string command(const std::string &cmd)
serial::Serial::SerialImpl::getCTS
bool getCTS()
Definition: unix.cc:939
time.h
serial::Serial::SerialImpl::SerialImpl
SerialImpl(const string &port, unsigned long baudrate, bytesize_t bytesize, parity_t parity, stopbits_t stopbits, flowcontrol_t flowcontrol)
Definition: unix.cc:108
serial::Serial::SerialImpl::flushInput
void flushInput()
Definition: unix.cc:793
serial::Serial::close
void close()
Definition: serial.cc:87
serial::Serial::SerialImpl::flush
void flush()
Definition: unix.cc:784
serial::Serial::SerialImpl::getParity
parity_t getParity() const
Definition: unix.cc:750
serial::Serial::SerialImpl::getStopbits
stopbits_t getStopbits() const
Definition: unix.cc:764
serial::Serial::SerialImpl::writeLock
void writeLock()
Definition: unix.cc:1041
serial::stopbits_one
@ stopbits_one
Definition: serial.h:78
serial::Serial::SerialImpl::setTimeout
void setTimeout(Timeout &timeout)
Definition: unix.cc:702
serial::MillisecondTimer::remaining
int64_t remaining()
Definition: unix.cc:73
upgrade_firmware.r
r
Definition: upgrade_firmware.py:55
data
data
serial::Serial::SerialImpl::available
size_t available()
Definition: unix.cc:478
serial::Serial::SerialImpl::setBreak
void setBreak(bool level)
Definition: unix.cc:820
serial::flowcontrol_software
@ flowcontrol_software
Definition: serial.h:88
serial::parity_even
@ parity_even
Definition: serial.h:69
serial::Serial::SerialImpl::getRI
bool getRI()
Definition: unix.cc:981
serial::Serial::waitReadable
bool waitReadable()
Definition: serial.cc:105
serial::Serial::SerialImpl::~SerialImpl
virtual ~SerialImpl()
Definition: unix.cc:122
serial::Serial::SerialImpl::setParity
void setParity(parity_t parity)
Definition: unix.cc:742
serial::IOException
Definition: serial.h:688
serial::Serial::SerialImpl::write
size_t write(const uint8_t *data, size_t length)
Definition: unix.cc:607
serial::Serial::SerialImpl::getFlowcontrol
flowcontrol_t getFlowcontrol() const
Definition: unix.cc:778
serial::Serial::SerialImpl::setFlowcontrol
void setFlowcontrol(flowcontrol_t flowcontrol)
Definition: unix.cc:770
serial::bytesize_t
bytesize_t
Definition: serial.h:56
serial::Serial::SerialImpl::waitByteTimes
void waitByteTimes(size_t count)
Definition: unix.cc:523
serial::MillisecondTimer
Definition: unix.h:56
serial::MillisecondTimer::expiry
timespec expiry
Definition: unix.h:63
serial::Serial::SerialImpl::setPort
void setPort(const string &port)
Definition: unix.cc:690
python_serial_test.timeout
timeout
Definition: python_serial_test.py:10
serial::Serial::SerialImpl::getCD
bool getCD()
Definition: unix.cc:1002
serial::Serial::SerialImpl::readLock
void readLock()
Definition: unix.cc:1023
serial::Serial::SerialImpl::setStopbits
void setStopbits(stopbits_t stopbits)
Definition: unix.cc:756
serial::Serial::SerialImpl::setBaudrate
void setBaudrate(unsigned long baudrate)
Definition: unix.cc:714
serial::Serial::SerialImpl::getDSR
bool getDSR()
Definition: unix.cc:960
serial::Serial::SerialImpl::readUnlock
void readUnlock()
Definition: unix.cc:1032
serial::Serial::SerialImpl::reconfigurePort
void reconfigurePort()
Definition: unix.cc:160
serial::MillisecondTimer::timespec_now
static timespec timespec_now()
Definition: unix.cc:82
serial::Serial
Definition: serial.h:147
upgrade_firmware.ser
ser
Definition: upgrade_firmware.py:433
serial::Serial::SerialImpl::open
void open()
Definition: unix.cc:130
serial::parity_odd
@ parity_odd
Definition: serial.h:68
serial::Serial::SerialImpl::writeUnlock
void writeUnlock()
Definition: unix.cc:1050
serial::Serial::SerialImpl::flushOutput
void flushOutput()
Definition: unix.cc:802
serial::Serial::SerialImpl::setBytesize
void setBytesize(bytesize_t bytesize)
Definition: unix.cc:728
serial::Serial::open
void open()
Definition: serial.cc:81
serial::Serial::SerialImpl::read_mutex
pthread_mutex_t read_mutex
Definition: unix.h:212
serial::flowcontrol_t
flowcontrol_t
Definition: serial.h:86
serial::sevenbits
@ sevenbits
Definition: serial.h:59
length
TFSIMD_FORCE_INLINE tfScalar length(const Quaternion &q)
serial::Serial::available
size_t available()
Definition: serial.cc:99
serial::Serial::SerialImpl::read
size_t read(uint8_t *buf, size_t size=1)
Definition: unix.cc:530
serial::stopbits_one_point_five
@ stopbits_one_point_five
Definition: serial.h:80
serial::parity_space
@ parity_space
Definition: serial.h:71
serial::stopbits_t
stopbits_t
Definition: serial.h:77
serial::Serial::SerialImpl::setRTS
void setRTS(bool level)
Definition: unix.cc:844
serial::Serial::SerialImpl::write_mutex
pthread_mutex_t write_mutex
Definition: unix.h:214
serial::flowcontrol_none
@ flowcontrol_none
Definition: serial.h:87
serial::Serial::SerialImpl::isOpen
bool isOpen() const
Definition: unix.cc:472
serial::Serial::SerialImpl::getTimeout
Timeout getTimeout() const
Definition: unix.cc:708
serial::Serial::SerialImpl::port_
string port_
Definition: unix.h:195
serial::flowcontrol_hardware
@ flowcontrol_hardware
Definition: serial.h:89
serial::Serial::SerialImpl::setDTR
void setDTR(bool level)
Definition: unix.cc:870
serial::Serial::waitByteTimes
void waitByteTimes(size_t count)
Definition: serial.cc:112
serial::fivebits
@ fivebits
Definition: serial.h:57
serial::SerialException
Definition: serial.h:670
serial::parity_none
@ parity_none
Definition: serial.h:67
serial::stopbits_two
@ stopbits_two
Definition: serial.h:79
serial::Serial::SerialImpl::waitForChange
bool waitForChange()
Definition: unix.cc:896
serial::Serial::SerialImpl::getBytesize
bytesize_t getBytesize() const
Definition: unix.cc:736
serial::PortNotOpenedException
Definition: serial.h:727
serial::Serial::write
size_t write(const uint8_t *data, size_t size)
Definition: serial.cc:252
serial::sixbits
@ sixbits
Definition: serial.h:58
serial::Serial::read
size_t read(uint8_t *buffer, size_t size)
Definition: serial.cc:124
serial::Serial::SerialImpl::getBaudrate
unsigned long getBaudrate() const
Definition: unix.cc:722
serial::Timeout
Definition: serial.h:98
serial::eightbits
@ eightbits
Definition: serial.h:60


ubiquity_motor
Author(s):
autogenerated on Thu Nov 16 2023 03:30:56