unix.cc
Go to the documentation of this file.
00001 /* Copyright 2012 William Woodall and John Harrison
00002  *
00003  * Additional Contributors: Christopher Baker @bakercp
00004  */
00005 
00006 #if !defined(_WIN32)
00007 
00008 #include <stdio.h>
00009 #include <string.h>
00010 #include <sstream>
00011 #include <unistd.h>
00012 #include <fcntl.h>
00013 #include <sys/ioctl.h>
00014 #include <sys/signal.h>
00015 #include <errno.h>
00016 #include <paths.h>
00017 #include <sysexits.h>
00018 #include <termios.h>
00019 #include <sys/param.h>
00020 #include <pthread.h>
00021 
00022 #if defined(__linux__)
00023 # include <linux/serial.h>
00024 #endif
00025 
00026 #include <sys/select.h>
00027 #include <sys/time.h>
00028 #include <time.h>
00029 #ifdef __MACH__
00030 #include <AvailabilityMacros.h>
00031 #include <mach/clock.h>
00032 #include <mach/mach.h>
00033 #endif
00034 
00035 #include "serial/impl/unix.h"
00036 
00037 #ifndef TIOCINQ
00038 #ifdef FIONREAD
00039 #define TIOCINQ FIONREAD
00040 #else
00041 #define TIOCINQ 0x541B
00042 #endif
00043 #endif
00044 
00045 #if defined(MAC_OS_X_VERSION_10_3) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_3)
00046 #include <IOKit/serial/ioss.h>
00047 #endif
00048 
00049 using std::string;
00050 using std::stringstream;
00051 using std::invalid_argument;
00052 using serial::MillisecondTimer;
00053 using serial::Serial;
00054 using serial::SerialException;
00055 using serial::PortNotOpenedException;
00056 using serial::IOException;
00057 
00058 
00059 MillisecondTimer::MillisecondTimer (const uint32_t millis)
00060   : expiry(timespec_now())
00061 {
00062   int64_t tv_nsec = expiry.tv_nsec + (millis * 1e6);
00063   if (tv_nsec >= 1e9) {
00064     int64_t sec_diff = tv_nsec / static_cast<int> (1e9);
00065     expiry.tv_nsec = tv_nsec - static_cast<int> (1e9 * sec_diff);
00066     expiry.tv_sec += sec_diff;
00067   } else {
00068     expiry.tv_nsec = tv_nsec;
00069   }
00070 }
00071 
00072 int64_t
00073 MillisecondTimer::remaining ()
00074 {
00075   timespec now(timespec_now());
00076   int64_t millis = (expiry.tv_sec - now.tv_sec) * 1e3;
00077   millis += (expiry.tv_nsec - now.tv_nsec) / 1e6;
00078   return millis;
00079 }
00080 
00081 timespec
00082 MillisecondTimer::timespec_now ()
00083 {
00084   timespec time;
00085 # ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
00086   clock_serv_t cclock;
00087   mach_timespec_t mts;
00088   host_get_clock_service(mach_host_self(), CALENDAR_CLOCK, &cclock);
00089   clock_get_time(cclock, &mts);
00090   mach_port_deallocate(mach_task_self(), cclock);
00091   time.tv_sec = mts.tv_sec;
00092   time.tv_nsec = mts.tv_nsec;
00093 # else
00094   clock_gettime(CLOCK_REALTIME, &time);
00095 # endif
00096   return time;
00097 }
00098 
00099 timespec
00100 timespec_from_ms (const uint32_t millis)
00101 {
00102   timespec time;
00103   time.tv_sec = millis / 1e3;
00104   time.tv_nsec = (millis - (time.tv_sec * 1e3)) * 1e6;
00105   return time;
00106 }
00107 
00108 Serial::SerialImpl::SerialImpl (const string &port, unsigned long baudrate,
00109                                 bytesize_t bytesize,
00110                                 parity_t parity, stopbits_t stopbits,
00111                                 flowcontrol_t flowcontrol)
00112   : port_ (port), fd_ (-1), is_open_ (false), xonxoff_ (false), rtscts_ (false),
00113     baudrate_ (baudrate), parity_ (parity),
00114     bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
00115 {
00116   pthread_mutex_init(&this->read_mutex, NULL);
00117   pthread_mutex_init(&this->write_mutex, NULL);
00118   if (port_.empty () == false)
00119     open ();
00120 }
00121 
00122 Serial::SerialImpl::~SerialImpl ()
00123 {
00124   close();
00125   pthread_mutex_destroy(&this->read_mutex);
00126   pthread_mutex_destroy(&this->write_mutex);
00127 }
00128 
00129 void
00130 Serial::SerialImpl::open ()
00131 {
00132   if (port_.empty ()) {
00133     throw invalid_argument ("Empty port is invalid.");
00134   }
00135   if (is_open_ == true) {
00136     throw SerialException ("Serial port already open.");
00137   }
00138 
00139   fd_ = ::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
00140 
00141   if (fd_ == -1) {
00142     switch (errno) {
00143     case EINTR:
00144       // Recurse because this is a recoverable error.
00145       open ();
00146       return;
00147     case ENFILE:
00148     case EMFILE:
00149       THROW (IOException, "Too many file handles open.");
00150     default:
00151       THROW (IOException, errno);
00152     }
00153   }
00154 
00155   reconfigurePort();
00156   is_open_ = true;
00157 }
00158 
00159 void
00160 Serial::SerialImpl::reconfigurePort ()
00161 {
00162   if (fd_ == -1) {
00163     // Can only operate on a valid file descriptor
00164     THROW (IOException, "Invalid file descriptor, is the serial port open?");
00165   }
00166 
00167   struct termios options; // The options for the file descriptor
00168 
00169   if (tcgetattr(fd_, &options) == -1) {
00170     THROW (IOException, "::tcgetattr");
00171   }
00172 
00173   // set up raw mode / no echo / binary
00174   options.c_cflag |= (tcflag_t)  (CLOCAL | CREAD);
00175   options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
00176                                        ISIG | IEXTEN); //|ECHOPRT
00177 
00178   options.c_oflag &= (tcflag_t) ~(OPOST);
00179   options.c_iflag &= (tcflag_t) ~(INLCR | IGNCR | ICRNL | IGNBRK);
00180 #ifdef IUCLC
00181   options.c_iflag &= (tcflag_t) ~IUCLC;
00182 #endif
00183 #ifdef PARMRK
00184   options.c_iflag &= (tcflag_t) ~PARMRK;
00185 #endif
00186 
00187   // setup baud rate
00188   bool custom_baud = false;
00189   speed_t baud;
00190   switch (baudrate_) {
00191 #ifdef B0
00192   case 0: baud = B0; break;
00193 #endif
00194 #ifdef B50
00195   case 50: baud = B50; break;
00196 #endif
00197 #ifdef B75
00198   case 75: baud = B75; break;
00199 #endif
00200 #ifdef B110
00201   case 110: baud = B110; break;
00202 #endif
00203 #ifdef B134
00204   case 134: baud = B134; break;
00205 #endif
00206 #ifdef B150
00207   case 150: baud = B150; break;
00208 #endif
00209 #ifdef B200
00210   case 200: baud = B200; break;
00211 #endif
00212 #ifdef B300
00213   case 300: baud = B300; break;
00214 #endif
00215 #ifdef B600
00216   case 600: baud = B600; break;
00217 #endif
00218 #ifdef B1200
00219   case 1200: baud = B1200; break;
00220 #endif
00221 #ifdef B1800
00222   case 1800: baud = B1800; break;
00223 #endif
00224 #ifdef B2400
00225   case 2400: baud = B2400; break;
00226 #endif
00227 #ifdef B4800
00228   case 4800: baud = B4800; break;
00229 #endif
00230 #ifdef B7200
00231   case 7200: baud = B7200; break;
00232 #endif
00233 #ifdef B9600
00234   case 9600: baud = B9600; break;
00235 #endif
00236 #ifdef B14400
00237   case 14400: baud = B14400; break;
00238 #endif
00239 #ifdef B19200
00240   case 19200: baud = B19200; break;
00241 #endif
00242 #ifdef B28800
00243   case 28800: baud = B28800; break;
00244 #endif
00245 #ifdef B57600
00246   case 57600: baud = B57600; break;
00247 #endif
00248 #ifdef B76800
00249   case 76800: baud = B76800; break;
00250 #endif
00251 #ifdef B38400
00252   case 38400: baud = B38400; break;
00253 #endif
00254 #ifdef B115200
00255   case 115200: baud = B115200; break;
00256 #endif
00257 #ifdef B128000
00258   case 128000: baud = B128000; break;
00259 #endif
00260 #ifdef B153600
00261   case 153600: baud = B153600; break;
00262 #endif
00263 #ifdef B230400
00264   case 230400: baud = B230400; break;
00265 #endif
00266 #ifdef B256000
00267   case 256000: baud = B256000; break;
00268 #endif
00269 #ifdef B460800
00270   case 460800: baud = B460800; break;
00271 #endif
00272 #ifdef B921600
00273   case 921600: baud = B921600; break;
00274 #endif
00275 #ifdef B1000000
00276   case 1000000: baud = B1000000; break;
00277 #endif
00278 #ifdef B1152000
00279   case 1152000: baud = B1152000; break;
00280 #endif
00281 #ifdef B1500000
00282   case 1500000: baud = B1500000; break;
00283 #endif
00284 #ifdef B2000000
00285   case 2000000: baud = B2000000; break;
00286 #endif
00287 #ifdef B2500000
00288   case 2500000: baud = B2500000; break;
00289 #endif
00290 #ifdef B3000000
00291   case 3000000: baud = B3000000; break;
00292 #endif
00293 #ifdef B3500000
00294   case 3500000: baud = B3500000; break;
00295 #endif
00296 #ifdef B4000000
00297   case 4000000: baud = B4000000; break;
00298 #endif
00299   default:
00300     custom_baud = true;
00301     // OS X support
00302 #if defined(MAC_OS_X_VERSION_10_4) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_4)
00303     // Starting with Tiger, the IOSSIOSPEED ioctl can be used to set arbitrary baud rates
00304     // other than those specified by POSIX. The driver for the underlying serial hardware
00305     // ultimately determines which baud rates can be used. This ioctl sets both the input
00306     // and output speed.
00307     speed_t new_baud = static_cast<speed_t> (baudrate_);
00308     if (-1 == ioctl (fd_, IOSSIOSPEED, &new_baud, 1)) {
00309       THROW (IOException, errno);
00310     }
00311     // Linux Support
00312 #elif defined(__linux__) && defined (TIOCSSERIAL)
00313     struct serial_struct ser;
00314 
00315     if (-1 == ioctl (fd_, TIOCGSERIAL, &ser)) {
00316       THROW (IOException, errno);
00317     }
00318 
00319     // set custom divisor
00320     ser.custom_divisor = ser.baud_base / static_cast<int> (baudrate_);
00321     // update flags
00322     ser.flags &= ~ASYNC_SPD_MASK;
00323     ser.flags |= ASYNC_SPD_CUST;
00324 
00325     if (-1 == ioctl (fd_, TIOCSSERIAL, &ser)) {
00326       THROW (IOException, errno);
00327     }
00328 #else
00329     throw invalid_argument ("OS does not currently support custom bauds");
00330 #endif
00331   }
00332   if (custom_baud == false) {
00333 #ifdef _BSD_SOURCE
00334     ::cfsetspeed(&options, baud);
00335 #else
00336     ::cfsetispeed(&options, baud);
00337     ::cfsetospeed(&options, baud);
00338 #endif
00339   }
00340 
00341   // setup char len
00342   options.c_cflag &= (tcflag_t) ~CSIZE;
00343   if (bytesize_ == eightbits)
00344     options.c_cflag |= CS8;
00345   else if (bytesize_ == sevenbits)
00346     options.c_cflag |= CS7;
00347   else if (bytesize_ == sixbits)
00348     options.c_cflag |= CS6;
00349   else if (bytesize_ == fivebits)
00350     options.c_cflag |= CS5;
00351   else
00352     throw invalid_argument ("invalid char len");
00353   // setup stopbits
00354   if (stopbits_ == stopbits_one)
00355     options.c_cflag &= (tcflag_t) ~(CSTOPB);
00356   else if (stopbits_ == stopbits_one_point_five)
00357     // ONE POINT FIVE same as TWO.. there is no POSIX support for 1.5
00358     options.c_cflag |=  (CSTOPB);
00359   else if (stopbits_ == stopbits_two)
00360     options.c_cflag |=  (CSTOPB);
00361   else
00362     throw invalid_argument ("invalid stop bit");
00363   // setup parity
00364   options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP);
00365   if (parity_ == parity_none) {
00366     options.c_cflag &= (tcflag_t) ~(PARENB | PARODD);
00367   } else if (parity_ == parity_even) {
00368     options.c_cflag &= (tcflag_t) ~(PARODD);
00369     options.c_cflag |=  (PARENB);
00370   } else if (parity_ == parity_odd) {
00371     options.c_cflag |=  (PARENB | PARODD);
00372   } else {
00373     throw invalid_argument ("invalid parity");
00374   }
00375   // setup flow control
00376   if (flowcontrol_ == flowcontrol_none) {
00377     xonxoff_ = false;
00378     rtscts_ = false;
00379   }
00380   if (flowcontrol_ == flowcontrol_software) {
00381     xonxoff_ = true;
00382     rtscts_ = false;
00383   }
00384   if (flowcontrol_ == flowcontrol_hardware) {
00385     xonxoff_ = false;
00386     rtscts_ = true;
00387   }
00388   // xonxoff
00389 #ifdef IXANY
00390   if (xonxoff_)
00391     options.c_iflag |=  (IXON | IXOFF); //|IXANY)
00392   else
00393     options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY);
00394 #else
00395   if (xonxoff_)
00396     options.c_iflag |=  (IXON | IXOFF);
00397   else
00398     options.c_iflag &= (tcflag_t) ~(IXON | IXOFF);
00399 #endif
00400   // rtscts
00401 #ifdef CRTSCTS
00402   if (rtscts_)
00403     options.c_cflag |=  (CRTSCTS);
00404   else
00405     options.c_cflag &= (unsigned long) ~(CRTSCTS);
00406 #elif defined CNEW_RTSCTS
00407   if (rtscts_)
00408     options.c_cflag |=  (CNEW_RTSCTS);
00409   else
00410     options.c_cflag &= (unsigned long) ~(CNEW_RTSCTS);
00411 #else
00412 #error "OS Support seems wrong."
00413 #endif
00414 
00415   // http://www.unixwiz.net/techtips/termios-vmin-vtime.html
00416   // this basically sets the read call up to be a polling read,
00417   // but we are using select to ensure there is data available
00418   // to read before each call, so we should never needlessly poll
00419   options.c_cc[VMIN] = 0;
00420   options.c_cc[VTIME] = 0;
00421 
00422   // activate settings
00423   ::tcsetattr (fd_, TCSANOW, &options);
00424 
00425   // Update byte_time_ based on the new settings.
00426   uint32_t bit_time_ns = 1e9 / baudrate_;
00427   byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
00428 
00429   // Compensate for the stopbits_one_point_five enum being equal to int 3,
00430   // and not 1.5.
00431   if (stopbits_ == stopbits_one_point_five) {
00432     byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns);
00433   }
00434 }
00435 
00436 void
00437 Serial::SerialImpl::close ()
00438 {
00439   if (is_open_ == true) {
00440     if (fd_ != -1) {
00441       int ret;
00442       ret = ::close (fd_);
00443       if (ret == 0) {
00444         fd_ = -1;
00445       } else {
00446         THROW (IOException, errno);
00447       }
00448     }
00449     is_open_ = false;
00450   }
00451 }
00452 
00453 bool
00454 Serial::SerialImpl::isOpen () const
00455 {
00456   return is_open_;
00457 }
00458 
00459 size_t
00460 Serial::SerialImpl::available ()
00461 {
00462   if (!is_open_) {
00463     return 0;
00464   }
00465   int count = 0;
00466   if (-1 == ioctl (fd_, TIOCINQ, &count)) {
00467       THROW (IOException, errno);
00468   } else {
00469       return static_cast<size_t> (count);
00470   }
00471 }
00472 
00473 bool
00474 Serial::SerialImpl::waitReadable (uint32_t timeout)
00475 {
00476   // Setup a select call to block for serial data or a timeout
00477   fd_set readfds;
00478   FD_ZERO (&readfds);
00479   FD_SET (fd_, &readfds);
00480   timespec timeout_ts (timespec_from_ms (timeout));
00481   int r = pselect (fd_ + 1, &readfds, NULL, NULL, &timeout_ts, NULL);
00482 
00483   if (r < 0) {
00484     // Select was interrupted
00485     if (errno == EINTR) {
00486       return false;
00487     }
00488     // Otherwise there was some error
00489     THROW (IOException, errno);
00490   }
00491   // Timeout occurred
00492   if (r == 0) {
00493     return false;
00494   }
00495   // This shouldn't happen, if r > 0 our fd has to be in the list!
00496   if (!FD_ISSET (fd_, &readfds)) {
00497     THROW (IOException, "select reports ready to read, but our fd isn't"
00498            " in the list, this shouldn't happen!");
00499   }
00500   // Data available to read.
00501   return true;
00502 }
00503 
00504 void
00505 Serial::SerialImpl::waitByteTimes (size_t count)
00506 {
00507   timespec wait_time = { 0, byte_time_ns_ * count };
00508   pselect (0, NULL, NULL, NULL, &wait_time, NULL);
00509 }
00510 
00511 size_t
00512 Serial::SerialImpl::read (uint8_t *buf, size_t size)
00513 {
00514   // If the port is not open, throw
00515   if (!is_open_) {
00516     throw PortNotOpenedException ("Serial::read");
00517   }
00518   size_t bytes_read = 0;
00519 
00520   // Calculate total timeout in milliseconds t_c + (t_m * N)
00521   long total_timeout_ms = timeout_.read_timeout_constant;
00522   total_timeout_ms += timeout_.read_timeout_multiplier * static_cast<long> (size);
00523   MillisecondTimer total_timeout(total_timeout_ms);
00524 
00525   // Pre-fill buffer with available bytes
00526   {
00527     ssize_t bytes_read_now = ::read (fd_, buf, size);
00528     if (bytes_read_now > 0) {
00529       bytes_read = bytes_read_now;
00530     }
00531   }
00532 
00533   while (bytes_read < size) {
00534     int64_t timeout_remaining_ms = total_timeout.remaining();
00535     if (timeout_remaining_ms <= 0) {
00536       // Timed out
00537       break;
00538     }
00539     // Timeout for the next select is whichever is less of the remaining
00540     // total read timeout and the inter-byte timeout.
00541     uint32_t timeout = std::min(static_cast<uint32_t> (timeout_remaining_ms),
00542                                 timeout_.inter_byte_timeout);
00543     // Wait for the device to be readable, and then attempt to read.
00544     if (waitReadable(timeout)) {
00545       // If it's a fixed-length multi-byte read, insert a wait here so that
00546       // we can attempt to grab the whole thing in a single IO call. Skip
00547       // this wait if a non-max inter_byte_timeout is specified.
00548       if (size > 1 && timeout_.inter_byte_timeout == Timeout::max()) {
00549         size_t bytes_available = available();
00550         if (bytes_available + bytes_read < size) {
00551           waitByteTimes(size - (bytes_available + bytes_read));
00552         }
00553       }
00554       // This should be non-blocking returning only what is available now
00555       //  Then returning so that select can block again.
00556       ssize_t bytes_read_now =
00557         ::read (fd_, buf + bytes_read, size - bytes_read);
00558       // read should always return some data as select reported it was
00559       // ready to read when we get to this point.
00560       if (bytes_read_now < 1) {
00561         // Disconnected devices, at least on Linux, show the
00562         // behavior that they are always ready to read immediately
00563         // but reading returns nothing.
00564         throw SerialException ("device reports readiness to read but "
00565                                "returned no data (device disconnected?)");
00566       }
00567       // Update bytes_read
00568       bytes_read += static_cast<size_t> (bytes_read_now);
00569       // If bytes_read == size then we have read everything we need
00570       if (bytes_read == size) {
00571         break;
00572       }
00573       // If bytes_read < size then we have more to read
00574       if (bytes_read < size) {
00575         continue;
00576       }
00577       // If bytes_read > size then we have over read, which shouldn't happen
00578       if (bytes_read > size) {
00579         throw SerialException ("read over read, too many bytes where "
00580                                "read, this shouldn't happen, might be "
00581                                "a logical error!");
00582       }
00583     }
00584   }
00585   return bytes_read;
00586 }
00587 
00588 size_t
00589 Serial::SerialImpl::write (const uint8_t *data, size_t length)
00590 {
00591   if (is_open_ == false) {
00592     throw PortNotOpenedException ("Serial::write");
00593   }
00594   fd_set writefds;
00595   size_t bytes_written = 0;
00596 
00597   // Calculate total timeout in milliseconds t_c + (t_m * N)
00598   long total_timeout_ms = timeout_.write_timeout_constant;
00599   total_timeout_ms += timeout_.write_timeout_multiplier * static_cast<long> (length);
00600   MillisecondTimer total_timeout(total_timeout_ms);
00601 
00602   while (bytes_written < length) {
00603     int64_t timeout_remaining_ms = total_timeout.remaining();
00604     if (timeout_remaining_ms <= 0) {
00605       // Timed out
00606       break;
00607     }
00608     timespec timeout(timespec_from_ms(timeout_remaining_ms));
00609 
00610     FD_ZERO (&writefds);
00611     FD_SET (fd_, &writefds);
00612 
00613     // Do the select
00614     int r = pselect (fd_ + 1, NULL, &writefds, NULL, &timeout, NULL);
00615 
00616     // Figure out what happened by looking at select's response 'r'
00618     if (r < 0) {
00619       // Select was interrupted, try again
00620       if (errno == EINTR) {
00621         continue;
00622       }
00623       // Otherwise there was some error
00624       THROW (IOException, errno);
00625     }
00627     if (r == 0) {
00628       break;
00629     }
00631     if (r > 0) {
00632       // Make sure our file descriptor is in the ready to write list
00633       if (FD_ISSET (fd_, &writefds)) {
00634         // This will write some
00635         ssize_t bytes_written_now =
00636           ::write (fd_, data + bytes_written, length - bytes_written);
00637         // write should always return some data as select reported it was
00638         // ready to write when we get to this point.
00639         if (bytes_written_now < 1) {
00640           // Disconnected devices, at least on Linux, show the
00641           // behavior that they are always ready to write immediately
00642           // but writing returns nothing.
00643           throw SerialException ("device reports readiness to write but "
00644                                  "returned no data (device disconnected?)");
00645         }
00646         // Update bytes_written
00647         bytes_written += static_cast<size_t> (bytes_written_now);
00648         // If bytes_written == size then we have written everything we need to
00649         if (bytes_written == length) {
00650           break;
00651         }
00652         // If bytes_written < size then we have more to write
00653         if (bytes_written < length) {
00654           continue;
00655         }
00656         // If bytes_written > size then we have over written, which shouldn't happen
00657         if (bytes_written > length) {
00658           throw SerialException ("write over wrote, too many bytes where "
00659                                  "written, this shouldn't happen, might be "
00660                                  "a logical error!");
00661         }
00662       }
00663       // This shouldn't happen, if r > 0 our fd has to be in the list!
00664       THROW (IOException, "select reports ready to write, but our fd isn't"
00665                           " in the list, this shouldn't happen!");
00666     }
00667   }
00668   return bytes_written;
00669 }
00670 
00671 void
00672 Serial::SerialImpl::setPort (const string &port)
00673 {
00674   port_ = port;
00675 }
00676 
00677 string
00678 Serial::SerialImpl::getPort () const
00679 {
00680   return port_;
00681 }
00682 
00683 void
00684 Serial::SerialImpl::setTimeout (serial::Timeout &timeout)
00685 {
00686   timeout_ = timeout;
00687 }
00688 
00689 serial::Timeout
00690 Serial::SerialImpl::getTimeout () const
00691 {
00692   return timeout_;
00693 }
00694 
00695 void
00696 Serial::SerialImpl::setBaudrate (unsigned long baudrate)
00697 {
00698   baudrate_ = baudrate;
00699   if (is_open_)
00700     reconfigurePort ();
00701 }
00702 
00703 unsigned long
00704 Serial::SerialImpl::getBaudrate () const
00705 {
00706   return baudrate_;
00707 }
00708 
00709 void
00710 Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
00711 {
00712   bytesize_ = bytesize;
00713   if (is_open_)
00714     reconfigurePort ();
00715 }
00716 
00717 serial::bytesize_t
00718 Serial::SerialImpl::getBytesize () const
00719 {
00720   return bytesize_;
00721 }
00722 
00723 void
00724 Serial::SerialImpl::setParity (serial::parity_t parity)
00725 {
00726   parity_ = parity;
00727   if (is_open_)
00728     reconfigurePort ();
00729 }
00730 
00731 serial::parity_t
00732 Serial::SerialImpl::getParity () const
00733 {
00734   return parity_;
00735 }
00736 
00737 void
00738 Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
00739 {
00740   stopbits_ = stopbits;
00741   if (is_open_)
00742     reconfigurePort ();
00743 }
00744 
00745 serial::stopbits_t
00746 Serial::SerialImpl::getStopbits () const
00747 {
00748   return stopbits_;
00749 }
00750 
00751 void
00752 Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
00753 {
00754   flowcontrol_ = flowcontrol;
00755   if (is_open_)
00756     reconfigurePort ();
00757 }
00758 
00759 serial::flowcontrol_t
00760 Serial::SerialImpl::getFlowcontrol () const
00761 {
00762   return flowcontrol_;
00763 }
00764 
00765 void
00766 Serial::SerialImpl::flush ()
00767 {
00768   if (is_open_ == false) {
00769     throw PortNotOpenedException ("Serial::flush");
00770   }
00771   tcdrain (fd_);
00772 }
00773 
00774 void
00775 Serial::SerialImpl::flushInput ()
00776 {
00777   if (is_open_ == false) {
00778     throw PortNotOpenedException ("Serial::flushInput");
00779   }
00780   tcflush (fd_, TCIFLUSH);
00781 }
00782 
00783 void
00784 Serial::SerialImpl::flushOutput ()
00785 {
00786   if (is_open_ == false) {
00787     throw PortNotOpenedException ("Serial::flushOutput");
00788   }
00789   tcflush (fd_, TCOFLUSH);
00790 }
00791 
00792 void
00793 Serial::SerialImpl::sendBreak (int duration)
00794 {
00795   if (is_open_ == false) {
00796     throw PortNotOpenedException ("Serial::sendBreak");
00797   }
00798   tcsendbreak (fd_, static_cast<int> (duration / 4));
00799 }
00800 
00801 void
00802 Serial::SerialImpl::setBreak (bool level)
00803 {
00804   if (is_open_ == false) {
00805     throw PortNotOpenedException ("Serial::setBreak");
00806   }
00807 
00808   if (level) {
00809     if (-1 == ioctl (fd_, TIOCSBRK))
00810     {
00811         stringstream ss;
00812         ss << "setBreak failed on a call to ioctl(TIOCSBRK): " << errno << " " << strerror(errno);
00813         throw(SerialException(ss.str().c_str()));
00814     }
00815   } else {
00816     if (-1 == ioctl (fd_, TIOCCBRK))
00817     {
00818         stringstream ss;
00819         ss << "setBreak failed on a call to ioctl(TIOCCBRK): " << errno << " " << strerror(errno);
00820         throw(SerialException(ss.str().c_str()));
00821     }
00822   }
00823 }
00824 
00825 void
00826 Serial::SerialImpl::setRTS (bool level)
00827 {
00828   if (is_open_ == false) {
00829     throw PortNotOpenedException ("Serial::setRTS");
00830   }
00831 
00832   int command = TIOCM_RTS;
00833 
00834   if (level) {
00835     if (-1 == ioctl (fd_, TIOCMBIS, &command))
00836     {
00837       stringstream ss;
00838       ss << "setRTS failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
00839       throw(SerialException(ss.str().c_str()));
00840     }
00841   } else {
00842     if (-1 == ioctl (fd_, TIOCMBIC, &command))
00843     {
00844       stringstream ss;
00845       ss << "setRTS failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
00846       throw(SerialException(ss.str().c_str()));
00847     }
00848   }
00849 }
00850 
00851 void
00852 Serial::SerialImpl::setDTR (bool level)
00853 {
00854   if (is_open_ == false) {
00855     throw PortNotOpenedException ("Serial::setDTR");
00856   }
00857 
00858   int command = TIOCM_DTR;
00859 
00860   if (level) {
00861     if (-1 == ioctl (fd_, TIOCMBIS, &command))
00862     {
00863       stringstream ss;
00864       ss << "setDTR failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
00865       throw(SerialException(ss.str().c_str()));
00866     }
00867   } else {
00868     if (-1 == ioctl (fd_, TIOCMBIC, &command))
00869     {
00870       stringstream ss;
00871       ss << "setDTR failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
00872       throw(SerialException(ss.str().c_str()));
00873     }
00874   }
00875 }
00876 
00877 bool
00878 Serial::SerialImpl::waitForChange ()
00879 {
00880 #ifndef TIOCMIWAIT
00881 
00882 while (is_open_ == true) {
00883 
00884     int status;
00885 
00886     if (-1 == ioctl (fd_, TIOCMGET, &status))
00887     {
00888         stringstream ss;
00889         ss << "waitForChange failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00890         throw(SerialException(ss.str().c_str()));
00891     }
00892     else
00893     {
00894         if (0 != (status & TIOCM_CTS)
00895          || 0 != (status & TIOCM_DSR)
00896          || 0 != (status & TIOCM_RI)
00897          || 0 != (status & TIOCM_CD))
00898         {
00899           return true;
00900         }
00901     }
00902 
00903     usleep(1000);
00904   }
00905 
00906   return false;
00907 #else
00908   int command = (TIOCM_CD|TIOCM_DSR|TIOCM_RI|TIOCM_CTS);
00909 
00910   if (-1 == ioctl (fd_, TIOCMIWAIT, &command)) {
00911     stringstream ss;
00912     ss << "waitForDSR failed on a call to ioctl(TIOCMIWAIT): "
00913        << errno << " " << strerror(errno);
00914     throw(SerialException(ss.str().c_str()));
00915   }
00916   return true;
00917 #endif
00918 }
00919 
00920 bool
00921 Serial::SerialImpl::getCTS ()
00922 {
00923   if (is_open_ == false) {
00924     throw PortNotOpenedException ("Serial::getCTS");
00925   }
00926 
00927   int status;
00928 
00929   if (-1 == ioctl (fd_, TIOCMGET, &status))
00930   {
00931     stringstream ss;
00932     ss << "getCTS failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00933     throw(SerialException(ss.str().c_str()));
00934   }
00935   else
00936   {
00937     return 0 != (status & TIOCM_CTS);
00938   }
00939 }
00940 
00941 bool
00942 Serial::SerialImpl::getDSR ()
00943 {
00944   if (is_open_ == false) {
00945     throw PortNotOpenedException ("Serial::getDSR");
00946   }
00947 
00948   int status;
00949 
00950   if (-1 == ioctl (fd_, TIOCMGET, &status))
00951   {
00952       stringstream ss;
00953       ss << "getDSR failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00954       throw(SerialException(ss.str().c_str()));
00955   }
00956   else
00957   {
00958       return 0 != (status & TIOCM_DSR);
00959   }
00960 }
00961 
00962 bool
00963 Serial::SerialImpl::getRI ()
00964 {
00965   if (is_open_ == false) {
00966     throw PortNotOpenedException ("Serial::getRI");
00967   }
00968 
00969   int status;
00970 
00971   if (-1 == ioctl (fd_, TIOCMGET, &status))
00972   {
00973     stringstream ss;
00974     ss << "getRI failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00975     throw(SerialException(ss.str().c_str()));
00976   }
00977   else
00978   {
00979     return 0 != (status & TIOCM_RI);
00980   }
00981 }
00982 
00983 bool
00984 Serial::SerialImpl::getCD ()
00985 {
00986   if (is_open_ == false) {
00987     throw PortNotOpenedException ("Serial::getCD");
00988   }
00989 
00990   int status;
00991 
00992   if (-1 == ioctl (fd_, TIOCMGET, &status))
00993   {
00994     stringstream ss;
00995     ss << "getCD failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00996     throw(SerialException(ss.str().c_str()));
00997   }
00998   else
00999   {
01000     return 0 != (status & TIOCM_CD);
01001   }
01002 }
01003 
01004 void
01005 Serial::SerialImpl::readLock ()
01006 {
01007   int result = pthread_mutex_lock(&this->read_mutex);
01008   if (result) {
01009     THROW (IOException, result);
01010   }
01011 }
01012 
01013 void
01014 Serial::SerialImpl::readUnlock ()
01015 {
01016   int result = pthread_mutex_unlock(&this->read_mutex);
01017   if (result) {
01018     THROW (IOException, result);
01019   }
01020 }
01021 
01022 void
01023 Serial::SerialImpl::writeLock ()
01024 {
01025   int result = pthread_mutex_lock(&this->write_mutex);
01026   if (result) {
01027     THROW (IOException, result);
01028   }
01029 }
01030 
01031 void
01032 Serial::SerialImpl::writeUnlock ()
01033 {
01034   int result = pthread_mutex_unlock(&this->write_mutex);
01035   if (result) {
01036     THROW (IOException, result);
01037   }
01038 }
01039 
01040 #endif // !defined(_WIN32)


serial
Author(s): William Woodall , John Harrison
autogenerated on Mon Oct 6 2014 07:34:37