00001
00002
00003
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);
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(), SYSTEM_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_MONOTONIC, &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
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
00164 THROW (IOException, "Invalid file descriptor, is the serial port open?");
00165 }
00166
00167 struct termios options;
00168
00169 if (tcgetattr(fd_, &options) == -1) {
00170 THROW (IOException, "::tcgetattr");
00171 }
00172
00173
00174 options.c_cflag |= (tcflag_t) (CLOCAL | CREAD);
00175 options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
00176 ISIG | IEXTEN);
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
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 B500000
00273 case 500000: baud = B500000; break;
00274 #endif
00275 #ifdef B576000
00276 case 576000: baud = B576000; break;
00277 #endif
00278 #ifdef B921600
00279 case 921600: baud = B921600; break;
00280 #endif
00281 #ifdef B1000000
00282 case 1000000: baud = B1000000; break;
00283 #endif
00284 #ifdef B1152000
00285 case 1152000: baud = B1152000; break;
00286 #endif
00287 #ifdef B1500000
00288 case 1500000: baud = B1500000; break;
00289 #endif
00290 #ifdef B2000000
00291 case 2000000: baud = B2000000; break;
00292 #endif
00293 #ifdef B2500000
00294 case 2500000: baud = B2500000; break;
00295 #endif
00296 #ifdef B3000000
00297 case 3000000: baud = B3000000; break;
00298 #endif
00299 #ifdef B3500000
00300 case 3500000: baud = B3500000; break;
00301 #endif
00302 #ifdef B4000000
00303 case 4000000: baud = B4000000; break;
00304 #endif
00305 default:
00306 custom_baud = true;
00307
00308 #if defined(MAC_OS_X_VERSION_10_4) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_4)
00309
00310
00311
00312
00313 speed_t new_baud = static_cast<speed_t> (baudrate_);
00314 if (-1 == ioctl (fd_, IOSSIOSPEED, &new_baud, 1)) {
00315 THROW (IOException, errno);
00316 }
00317
00318 #elif defined(__linux__) && defined (TIOCSSERIAL)
00319 struct serial_struct ser;
00320
00321 if (-1 == ioctl (fd_, TIOCGSERIAL, &ser)) {
00322 THROW (IOException, errno);
00323 }
00324
00325
00326 ser.custom_divisor = ser.baud_base / static_cast<int> (baudrate_);
00327
00328 ser.flags &= ~ASYNC_SPD_MASK;
00329 ser.flags |= ASYNC_SPD_CUST;
00330
00331 if (-1 == ioctl (fd_, TIOCSSERIAL, &ser)) {
00332 THROW (IOException, errno);
00333 }
00334 #else
00335 throw invalid_argument ("OS does not currently support custom bauds");
00336 #endif
00337 }
00338 if (custom_baud == false) {
00339 #ifdef _BSD_SOURCE
00340 ::cfsetspeed(&options, baud);
00341 #else
00342 ::cfsetispeed(&options, baud);
00343 ::cfsetospeed(&options, baud);
00344 #endif
00345 }
00346
00347
00348 options.c_cflag &= (tcflag_t) ~CSIZE;
00349 if (bytesize_ == eightbits)
00350 options.c_cflag |= CS8;
00351 else if (bytesize_ == sevenbits)
00352 options.c_cflag |= CS7;
00353 else if (bytesize_ == sixbits)
00354 options.c_cflag |= CS6;
00355 else if (bytesize_ == fivebits)
00356 options.c_cflag |= CS5;
00357 else
00358 throw invalid_argument ("invalid char len");
00359
00360 if (stopbits_ == stopbits_one)
00361 options.c_cflag &= (tcflag_t) ~(CSTOPB);
00362 else if (stopbits_ == stopbits_one_point_five)
00363
00364 options.c_cflag |= (CSTOPB);
00365 else if (stopbits_ == stopbits_two)
00366 options.c_cflag |= (CSTOPB);
00367 else
00368 throw invalid_argument ("invalid stop bit");
00369
00370 options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP);
00371 if (parity_ == parity_none) {
00372 options.c_cflag &= (tcflag_t) ~(PARENB | PARODD);
00373 } else if (parity_ == parity_even) {
00374 options.c_cflag &= (tcflag_t) ~(PARODD);
00375 options.c_cflag |= (PARENB);
00376 } else if (parity_ == parity_odd) {
00377 options.c_cflag |= (PARENB | PARODD);
00378 }
00379 #ifdef CMSPAR
00380 else if (parity_ == parity_mark) {
00381 options.c_cflag |= (PARENB | CMSPAR | PARODD);
00382 }
00383 else if (parity_ == parity_space) {
00384 options.c_cflag |= (PARENB | CMSPAR);
00385 options.c_cflag &= (tcflag_t) ~(PARODD);
00386 }
00387 #else
00388
00389 else if (parity_ == parity_mark || parity_ == parity_space) {
00390 throw invalid_argument ("OS does not support mark or space parity");
00391 }
00392 #endif // ifdef CMSPAR
00393 else {
00394 throw invalid_argument ("invalid parity");
00395 }
00396
00397 if (flowcontrol_ == flowcontrol_none) {
00398 xonxoff_ = false;
00399 rtscts_ = false;
00400 }
00401 if (flowcontrol_ == flowcontrol_software) {
00402 xonxoff_ = true;
00403 rtscts_ = false;
00404 }
00405 if (flowcontrol_ == flowcontrol_hardware) {
00406 xonxoff_ = false;
00407 rtscts_ = true;
00408 }
00409
00410 #ifdef IXANY
00411 if (xonxoff_)
00412 options.c_iflag |= (IXON | IXOFF);
00413 else
00414 options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY);
00415 #else
00416 if (xonxoff_)
00417 options.c_iflag |= (IXON | IXOFF);
00418 else
00419 options.c_iflag &= (tcflag_t) ~(IXON | IXOFF);
00420 #endif
00421
00422 #ifdef CRTSCTS
00423 if (rtscts_)
00424 options.c_cflag |= (CRTSCTS);
00425 else
00426 options.c_cflag &= (unsigned long) ~(CRTSCTS);
00427 #elif defined CNEW_RTSCTS
00428 if (rtscts_)
00429 options.c_cflag |= (CNEW_RTSCTS);
00430 else
00431 options.c_cflag &= (unsigned long) ~(CNEW_RTSCTS);
00432 #else
00433 #error "OS Support seems wrong."
00434 #endif
00435
00436
00437
00438
00439
00440 options.c_cc[VMIN] = 0;
00441 options.c_cc[VTIME] = 0;
00442
00443
00444 ::tcsetattr (fd_, TCSANOW, &options);
00445
00446
00447 uint32_t bit_time_ns = 1e9 / baudrate_;
00448 byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
00449
00450
00451
00452 if (stopbits_ == stopbits_one_point_five) {
00453 byte_time_ns_ += ((1.5 - stopbits_one_point_five) * bit_time_ns);
00454 }
00455 }
00456
00457 void
00458 Serial::SerialImpl::close ()
00459 {
00460 if (is_open_ == true) {
00461 if (fd_ != -1) {
00462 int ret;
00463 ret = ::close (fd_);
00464 if (ret == 0) {
00465 fd_ = -1;
00466 } else {
00467 THROW (IOException, errno);
00468 }
00469 }
00470 is_open_ = false;
00471 }
00472 }
00473
00474 bool
00475 Serial::SerialImpl::isOpen () const
00476 {
00477 return is_open_;
00478 }
00479
00480 size_t
00481 Serial::SerialImpl::available ()
00482 {
00483 if (!is_open_) {
00484 return 0;
00485 }
00486 int count = 0;
00487 if (-1 == ioctl (fd_, TIOCINQ, &count)) {
00488 THROW (IOException, errno);
00489 } else {
00490 return static_cast<size_t> (count);
00491 }
00492 }
00493
00494 bool
00495 Serial::SerialImpl::waitReadable (uint32_t timeout)
00496 {
00497
00498 fd_set readfds;
00499 FD_ZERO (&readfds);
00500 FD_SET (fd_, &readfds);
00501 timespec timeout_ts (timespec_from_ms (timeout));
00502 int r = pselect (fd_ + 1, &readfds, NULL, NULL, &timeout_ts, NULL);
00503
00504 if (r < 0) {
00505
00506 if (errno == EINTR) {
00507 return false;
00508 }
00509
00510 THROW (IOException, errno);
00511 }
00512
00513 if (r == 0) {
00514 return false;
00515 }
00516
00517 if (!FD_ISSET (fd_, &readfds)) {
00518 THROW (IOException, "select reports ready to read, but our fd isn't"
00519 " in the list, this shouldn't happen!");
00520 }
00521
00522 return true;
00523 }
00524
00525 void
00526 Serial::SerialImpl::waitByteTimes (size_t count)
00527 {
00528 timespec wait_time = { 0, static_cast<long>(byte_time_ns_ * count)};
00529 pselect (0, NULL, NULL, NULL, &wait_time, NULL);
00530 }
00531
00532 size_t
00533 Serial::SerialImpl::read (uint8_t *buf, size_t size)
00534 {
00535
00536 if (!is_open_) {
00537 throw PortNotOpenedException ("Serial::read");
00538 }
00539 size_t bytes_read = 0;
00540
00541
00542 long total_timeout_ms = timeout_.read_timeout_constant;
00543 total_timeout_ms += timeout_.read_timeout_multiplier * static_cast<long> (size);
00544 MillisecondTimer total_timeout(total_timeout_ms);
00545
00546
00547 {
00548 ssize_t bytes_read_now = ::read (fd_, buf, size);
00549 if (bytes_read_now > 0) {
00550 bytes_read = bytes_read_now;
00551 }
00552 }
00553
00554 while (bytes_read < size) {
00555 int64_t timeout_remaining_ms = total_timeout.remaining();
00556 if (timeout_remaining_ms <= 0) {
00557
00558 break;
00559 }
00560
00561
00562 uint32_t timeout = std::min(static_cast<uint32_t> (timeout_remaining_ms),
00563 timeout_.inter_byte_timeout);
00564
00565 if (waitReadable(timeout)) {
00566
00567
00568
00569 if (size > 1 && timeout_.inter_byte_timeout == Timeout::max()) {
00570 size_t bytes_available = available();
00571 if (bytes_available + bytes_read < size) {
00572 waitByteTimes(size - (bytes_available + bytes_read));
00573 }
00574 }
00575
00576
00577 ssize_t bytes_read_now =
00578 ::read (fd_, buf + bytes_read, size - bytes_read);
00579
00580
00581 if (bytes_read_now < 1) {
00582
00583
00584
00585 throw SerialException ("device reports readiness to read but "
00586 "returned no data (device disconnected?)");
00587 }
00588
00589 bytes_read += static_cast<size_t> (bytes_read_now);
00590
00591 if (bytes_read == size) {
00592 break;
00593 }
00594
00595 if (bytes_read < size) {
00596 continue;
00597 }
00598
00599 if (bytes_read > size) {
00600 throw SerialException ("read over read, too many bytes where "
00601 "read, this shouldn't happen, might be "
00602 "a logical error!");
00603 }
00604 }
00605 }
00606 return bytes_read;
00607 }
00608
00609 size_t
00610 Serial::SerialImpl::write (const uint8_t *data, size_t length)
00611 {
00612 if (is_open_ == false) {
00613 throw PortNotOpenedException ("Serial::write");
00614 }
00615 fd_set writefds;
00616 size_t bytes_written = 0;
00617
00618
00619 long total_timeout_ms = timeout_.write_timeout_constant;
00620 total_timeout_ms += timeout_.write_timeout_multiplier * static_cast<long> (length);
00621 MillisecondTimer total_timeout(total_timeout_ms);
00622
00623 bool first_iteration = true;
00624 while (bytes_written < length) {
00625 int64_t timeout_remaining_ms = total_timeout.remaining();
00626
00627
00628 if (!first_iteration && (timeout_remaining_ms <= 0)) {
00629
00630 break;
00631 }
00632 first_iteration = false;
00633
00634 timespec timeout(timespec_from_ms(timeout_remaining_ms));
00635
00636 FD_ZERO (&writefds);
00637 FD_SET (fd_, &writefds);
00638
00639
00640 int r = pselect (fd_ + 1, NULL, &writefds, NULL, &timeout, NULL);
00641
00642
00644 if (r < 0) {
00645
00646 if (errno == EINTR) {
00647 continue;
00648 }
00649
00650 THROW (IOException, errno);
00651 }
00653 if (r == 0) {
00654 break;
00655 }
00657 if (r > 0) {
00658
00659 if (FD_ISSET (fd_, &writefds)) {
00660
00661 ssize_t bytes_written_now =
00662 ::write (fd_, data + bytes_written, length - bytes_written);
00663
00664
00665 if (bytes_written_now < 1) {
00666
00667
00668
00669 throw SerialException ("device reports readiness to write but "
00670 "returned no data (device disconnected?)");
00671 }
00672
00673 bytes_written += static_cast<size_t> (bytes_written_now);
00674
00675 if (bytes_written == length) {
00676 break;
00677 }
00678
00679 if (bytes_written < length) {
00680 continue;
00681 }
00682
00683 if (bytes_written > length) {
00684 throw SerialException ("write over wrote, too many bytes where "
00685 "written, this shouldn't happen, might be "
00686 "a logical error!");
00687 }
00688 }
00689
00690 THROW (IOException, "select reports ready to write, but our fd isn't"
00691 " in the list, this shouldn't happen!");
00692 }
00693 }
00694 return bytes_written;
00695 }
00696
00697 void
00698 Serial::SerialImpl::setPort (const string &port)
00699 {
00700 port_ = port;
00701 }
00702
00703 string
00704 Serial::SerialImpl::getPort () const
00705 {
00706 return port_;
00707 }
00708
00709 void
00710 Serial::SerialImpl::setTimeout (serial::Timeout &timeout)
00711 {
00712 timeout_ = timeout;
00713 }
00714
00715 serial::Timeout
00716 Serial::SerialImpl::getTimeout () const
00717 {
00718 return timeout_;
00719 }
00720
00721 void
00722 Serial::SerialImpl::setBaudrate (unsigned long baudrate)
00723 {
00724 baudrate_ = baudrate;
00725 if (is_open_)
00726 reconfigurePort ();
00727 }
00728
00729 unsigned long
00730 Serial::SerialImpl::getBaudrate () const
00731 {
00732 return baudrate_;
00733 }
00734
00735 void
00736 Serial::SerialImpl::setBytesize (serial::bytesize_t bytesize)
00737 {
00738 bytesize_ = bytesize;
00739 if (is_open_)
00740 reconfigurePort ();
00741 }
00742
00743 serial::bytesize_t
00744 Serial::SerialImpl::getBytesize () const
00745 {
00746 return bytesize_;
00747 }
00748
00749 void
00750 Serial::SerialImpl::setParity (serial::parity_t parity)
00751 {
00752 parity_ = parity;
00753 if (is_open_)
00754 reconfigurePort ();
00755 }
00756
00757 serial::parity_t
00758 Serial::SerialImpl::getParity () const
00759 {
00760 return parity_;
00761 }
00762
00763 void
00764 Serial::SerialImpl::setStopbits (serial::stopbits_t stopbits)
00765 {
00766 stopbits_ = stopbits;
00767 if (is_open_)
00768 reconfigurePort ();
00769 }
00770
00771 serial::stopbits_t
00772 Serial::SerialImpl::getStopbits () const
00773 {
00774 return stopbits_;
00775 }
00776
00777 void
00778 Serial::SerialImpl::setFlowcontrol (serial::flowcontrol_t flowcontrol)
00779 {
00780 flowcontrol_ = flowcontrol;
00781 if (is_open_)
00782 reconfigurePort ();
00783 }
00784
00785 serial::flowcontrol_t
00786 Serial::SerialImpl::getFlowcontrol () const
00787 {
00788 return flowcontrol_;
00789 }
00790
00791 void
00792 Serial::SerialImpl::flush ()
00793 {
00794 if (is_open_ == false) {
00795 throw PortNotOpenedException ("Serial::flush");
00796 }
00797 tcdrain (fd_);
00798 }
00799
00800 void
00801 Serial::SerialImpl::flushInput ()
00802 {
00803 if (is_open_ == false) {
00804 throw PortNotOpenedException ("Serial::flushInput");
00805 }
00806 tcflush (fd_, TCIFLUSH);
00807 }
00808
00809 void
00810 Serial::SerialImpl::flushOutput ()
00811 {
00812 if (is_open_ == false) {
00813 throw PortNotOpenedException ("Serial::flushOutput");
00814 }
00815 tcflush (fd_, TCOFLUSH);
00816 }
00817
00818 void
00819 Serial::SerialImpl::sendBreak (int duration)
00820 {
00821 if (is_open_ == false) {
00822 throw PortNotOpenedException ("Serial::sendBreak");
00823 }
00824 tcsendbreak (fd_, static_cast<int> (duration / 4));
00825 }
00826
00827 void
00828 Serial::SerialImpl::setBreak (bool level)
00829 {
00830 if (is_open_ == false) {
00831 throw PortNotOpenedException ("Serial::setBreak");
00832 }
00833
00834 if (level) {
00835 if (-1 == ioctl (fd_, TIOCSBRK))
00836 {
00837 stringstream ss;
00838 ss << "setBreak failed on a call to ioctl(TIOCSBRK): " << errno << " " << strerror(errno);
00839 throw(SerialException(ss.str().c_str()));
00840 }
00841 } else {
00842 if (-1 == ioctl (fd_, TIOCCBRK))
00843 {
00844 stringstream ss;
00845 ss << "setBreak failed on a call to ioctl(TIOCCBRK): " << errno << " " << strerror(errno);
00846 throw(SerialException(ss.str().c_str()));
00847 }
00848 }
00849 }
00850
00851 void
00852 Serial::SerialImpl::setRTS (bool level)
00853 {
00854 if (is_open_ == false) {
00855 throw PortNotOpenedException ("Serial::setRTS");
00856 }
00857
00858 int command = TIOCM_RTS;
00859
00860 if (level) {
00861 if (-1 == ioctl (fd_, TIOCMBIS, &command))
00862 {
00863 stringstream ss;
00864 ss << "setRTS 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 << "setRTS failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
00872 throw(SerialException(ss.str().c_str()));
00873 }
00874 }
00875 }
00876
00877 void
00878 Serial::SerialImpl::setDTR (bool level)
00879 {
00880 if (is_open_ == false) {
00881 throw PortNotOpenedException ("Serial::setDTR");
00882 }
00883
00884 int command = TIOCM_DTR;
00885
00886 if (level) {
00887 if (-1 == ioctl (fd_, TIOCMBIS, &command))
00888 {
00889 stringstream ss;
00890 ss << "setDTR failed on a call to ioctl(TIOCMBIS): " << errno << " " << strerror(errno);
00891 throw(SerialException(ss.str().c_str()));
00892 }
00893 } else {
00894 if (-1 == ioctl (fd_, TIOCMBIC, &command))
00895 {
00896 stringstream ss;
00897 ss << "setDTR failed on a call to ioctl(TIOCMBIC): " << errno << " " << strerror(errno);
00898 throw(SerialException(ss.str().c_str()));
00899 }
00900 }
00901 }
00902
00903 bool
00904 Serial::SerialImpl::waitForChange ()
00905 {
00906 #ifndef TIOCMIWAIT
00907
00908 while (is_open_ == true) {
00909
00910 int status;
00911
00912 if (-1 == ioctl (fd_, TIOCMGET, &status))
00913 {
00914 stringstream ss;
00915 ss << "waitForChange failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00916 throw(SerialException(ss.str().c_str()));
00917 }
00918 else
00919 {
00920 if (0 != (status & TIOCM_CTS)
00921 || 0 != (status & TIOCM_DSR)
00922 || 0 != (status & TIOCM_RI)
00923 || 0 != (status & TIOCM_CD))
00924 {
00925 return true;
00926 }
00927 }
00928
00929 usleep(1000);
00930 }
00931
00932 return false;
00933 #else
00934 int command = (TIOCM_CD|TIOCM_DSR|TIOCM_RI|TIOCM_CTS);
00935
00936 if (-1 == ioctl (fd_, TIOCMIWAIT, &command)) {
00937 stringstream ss;
00938 ss << "waitForDSR failed on a call to ioctl(TIOCMIWAIT): "
00939 << errno << " " << strerror(errno);
00940 throw(SerialException(ss.str().c_str()));
00941 }
00942 return true;
00943 #endif
00944 }
00945
00946 bool
00947 Serial::SerialImpl::getCTS ()
00948 {
00949 if (is_open_ == false) {
00950 throw PortNotOpenedException ("Serial::getCTS");
00951 }
00952
00953 int status;
00954
00955 if (-1 == ioctl (fd_, TIOCMGET, &status))
00956 {
00957 stringstream ss;
00958 ss << "getCTS failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00959 throw(SerialException(ss.str().c_str()));
00960 }
00961 else
00962 {
00963 return 0 != (status & TIOCM_CTS);
00964 }
00965 }
00966
00967 bool
00968 Serial::SerialImpl::getDSR ()
00969 {
00970 if (is_open_ == false) {
00971 throw PortNotOpenedException ("Serial::getDSR");
00972 }
00973
00974 int status;
00975
00976 if (-1 == ioctl (fd_, TIOCMGET, &status))
00977 {
00978 stringstream ss;
00979 ss << "getDSR failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
00980 throw(SerialException(ss.str().c_str()));
00981 }
00982 else
00983 {
00984 return 0 != (status & TIOCM_DSR);
00985 }
00986 }
00987
00988 bool
00989 Serial::SerialImpl::getRI ()
00990 {
00991 if (is_open_ == false) {
00992 throw PortNotOpenedException ("Serial::getRI");
00993 }
00994
00995 int status;
00996
00997 if (-1 == ioctl (fd_, TIOCMGET, &status))
00998 {
00999 stringstream ss;
01000 ss << "getRI failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
01001 throw(SerialException(ss.str().c_str()));
01002 }
01003 else
01004 {
01005 return 0 != (status & TIOCM_RI);
01006 }
01007 }
01008
01009 bool
01010 Serial::SerialImpl::getCD ()
01011 {
01012 if (is_open_ == false) {
01013 throw PortNotOpenedException ("Serial::getCD");
01014 }
01015
01016 int status;
01017
01018 if (-1 == ioctl (fd_, TIOCMGET, &status))
01019 {
01020 stringstream ss;
01021 ss << "getCD failed on a call to ioctl(TIOCMGET): " << errno << " " << strerror(errno);
01022 throw(SerialException(ss.str().c_str()));
01023 }
01024 else
01025 {
01026 return 0 != (status & TIOCM_CD);
01027 }
01028 }
01029
01030 void
01031 Serial::SerialImpl::readLock ()
01032 {
01033 int result = pthread_mutex_lock(&this->read_mutex);
01034 if (result) {
01035 THROW (IOException, result);
01036 }
01037 }
01038
01039 void
01040 Serial::SerialImpl::readUnlock ()
01041 {
01042 int result = pthread_mutex_unlock(&this->read_mutex);
01043 if (result) {
01044 THROW (IOException, result);
01045 }
01046 }
01047
01048 void
01049 Serial::SerialImpl::writeLock ()
01050 {
01051 int result = pthread_mutex_lock(&this->write_mutex);
01052 if (result) {
01053 THROW (IOException, result);
01054 }
01055 }
01056
01057 void
01058 Serial::SerialImpl::writeUnlock ()
01059 {
01060 int result = pthread_mutex_unlock(&this->write_mutex);
01061 if (result) {
01062 THROW (IOException, result);
01063 }
01064 }
01065
01066 #endif // !defined(_WIN32)