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