13 #include <sys/ioctl.h>
14 #include <sys/signal.h>
19 #include <sys/param.h>
22 #if defined(__linux__)
23 # include <linux/serial.h>
26 #include <sys/select.h>
30 #include <AvailabilityMacros.h>
31 #include <mach/clock.h>
32 #include <mach/mach.h>
39 #define TIOCINQ FIONREAD
41 #define TIOCINQ 0x541B
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>
50 using std::stringstream;
51 using std::invalid_argument;
59 MillisecondTimer::MillisecondTimer (
const uint32_t millis)
60 : expiry(timespec_now())
62 int64_t tv_nsec =
expiry.tv_nsec + (millis * 1e6);
64 int64_t sec_diff = tv_nsec /
static_cast<int> (1e9);
65 expiry.tv_nsec = tv_nsec -
static_cast<int> (1e9 * sec_diff);
76 int64_t millis = (
expiry.tv_sec - now.tv_sec) * 1e3;
77 millis += (
expiry.tv_nsec - now.tv_nsec) / 1e6;
85 # ifdef __MACH__ // OS X does not have clock_gettime, use clock_get_time
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;
94 clock_gettime(CLOCK_REALTIME, &time);
103 time.tv_sec = millis / 1e3;
104 time.tv_nsec = (millis - (time.tv_sec * 1e3)) * 1e6;
112 : port_ (port), fd_ (-1), is_open_ (false), xonxoff_ (false), rtscts_ (false),
113 baudrate_ (baudrate), parity_ (parity),
114 bytesize_ (bytesize), stopbits_ (stopbits), flowcontrol_ (flowcontrol)
118 if (
port_.empty () ==
false)
125 pthread_mutex_destroy(&this->read_mutex);
126 pthread_mutex_destroy(&this->write_mutex);
132 if (port_.empty ()) {
133 throw invalid_argument (
"Empty port is invalid.");
135 if (is_open_ ==
true) {
139 fd_ =
::open (port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
167 struct termios options;
169 if (tcgetattr(fd_, &options) == -1) {
174 options.c_cflag |= (tcflag_t) (CLOCAL | CREAD);
175 options.c_lflag &= (tcflag_t) ~(ICANON | ECHO | ECHOE | ECHOK | ECHONL |
178 options.c_oflag &= (tcflag_t) ~(OPOST);
179 options.c_iflag &= (tcflag_t) ~(INLCR | IGNCR | ICRNL | IGNBRK);
181 options.c_iflag &= (tcflag_t) ~IUCLC;
184 options.c_iflag &= (tcflag_t) ~PARMRK;
188 bool custom_baud =
false;
192 case 0: baud = B0;
break;
195 case 50: baud = B50;
break;
198 case 75: baud = B75;
break;
201 case 110: baud = B110;
break;
204 case 134: baud = B134;
break;
207 case 150: baud = B150;
break;
210 case 200: baud = B200;
break;
213 case 300: baud = B300;
break;
216 case 600: baud = B600;
break;
219 case 1200: baud = B1200;
break;
222 case 1800: baud = B1800;
break;
225 case 2400: baud = B2400;
break;
228 case 4800: baud = B4800;
break;
231 case 7200: baud = B7200;
break;
234 case 9600: baud = B9600;
break;
237 case 14400: baud = B14400;
break;
240 case 19200: baud = B19200;
break;
243 case 28800: baud = B28800;
break;
246 case 57600: baud = B57600;
break;
249 case 76800: baud = B76800;
break;
252 case 38400: baud = B38400;
break;
255 case 115200: baud = B115200;
break;
258 case 128000: baud = B128000;
break;
261 case 153600: baud = B153600;
break;
264 case 230400: baud = B230400;
break;
267 case 256000: baud = B256000;
break;
270 case 460800: baud = B460800;
break;
273 case 576000: baud = B576000;
break;
276 case 921600: baud = B921600;
break;
279 case 1000000: baud = B1000000;
break;
282 case 1152000: baud = B1152000;
break;
285 case 1500000: baud = B1500000;
break;
288 case 2000000: baud = B2000000;
break;
291 case 2500000: baud = B2500000;
break;
294 case 3000000: baud = B3000000;
break;
297 case 3500000: baud = B3500000;
break;
300 case 4000000: baud = B4000000;
break;
305 #if defined(MAC_OS_X_VERSION_10_4) && (MAC_OS_X_VERSION_MIN_REQUIRED >= MAC_OS_X_VERSION_10_4)
310 speed_t new_baud =
static_cast<speed_t
> (baudrate_);
311 if (-1 == ioctl (fd_, IOSSIOSPEED, &new_baud, 1)) {
315 #elif defined(__linux__) && defined (TIOCSSERIAL)
316 struct serial_struct
ser;
318 if (-1 == ioctl (fd_, TIOCGSERIAL, &
ser)) {
323 ser.custom_divisor =
ser.baud_base /
static_cast<int> (baudrate_);
325 ser.flags &= ~ASYNC_SPD_MASK;
326 ser.flags |= ASYNC_SPD_CUST;
328 if (-1 == ioctl (fd_, TIOCSSERIAL, &
ser)) {
332 throw invalid_argument (
"OS does not currently support custom bauds");
335 if (custom_baud ==
false) {
337 ::cfsetspeed(&options, baud);
339 ::cfsetispeed(&options, baud);
340 ::cfsetospeed(&options, baud);
345 options.c_cflag &= (tcflag_t) ~CSIZE;
347 options.c_cflag |= CS8;
349 options.c_cflag |= CS7;
351 options.c_cflag |= CS6;
353 options.c_cflag |= CS5;
355 throw invalid_argument (
"invalid char len");
358 options.c_cflag &= (tcflag_t) ~(CSTOPB);
361 options.c_cflag |= (CSTOPB);
363 options.c_cflag |= (CSTOPB);
365 throw invalid_argument (
"invalid stop bit");
367 options.c_iflag &= (tcflag_t) ~(INPCK | ISTRIP);
369 options.c_cflag &= (tcflag_t) ~(PARENB | PARODD);
371 options.c_cflag &= (tcflag_t) ~(PARODD);
372 options.c_cflag |= (PARENB);
374 options.c_cflag |= (PARENB | PARODD);
378 options.c_cflag |= (PARENB | CMSPAR | PARODD);
381 options.c_cflag |= (PARENB | CMSPAR);
382 options.c_cflag &= (tcflag_t) ~(PARODD);
387 throw invalid_argument (
"OS does not support mark or space parity");
389 #endif // ifdef CMSPAR
391 throw invalid_argument (
"invalid parity");
409 options.c_iflag |= (IXON | IXOFF);
411 options.c_iflag &= (tcflag_t) ~(IXON | IXOFF | IXANY);
414 options.c_iflag |= (IXON | IXOFF);
416 options.c_iflag &= (tcflag_t) ~(IXON | IXOFF);
421 options.c_cflag |= (CRTSCTS);
423 options.c_cflag &= (
unsigned long) ~(CRTSCTS);
424 #elif defined CNEW_RTSCTS
426 options.c_cflag |= (CNEW_RTSCTS);
428 options.c_cflag &= (
unsigned long) ~(CNEW_RTSCTS);
430 #error "OS Support seems wrong."
437 options.c_cc[VMIN] = 0;
438 options.c_cc[VTIME] = 0;
441 ::tcsetattr (fd_, TCSANOW, &options);
444 uint32_t bit_time_ns = 1e9 / baudrate_;
445 byte_time_ns_ = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
457 if (is_open_ ==
true) {
484 if (-1 == ioctl (fd_,
TIOCINQ, &count)) {
487 return static_cast<size_t> (count);
497 FD_SET (fd_, &readfds);
499 int r = pselect (fd_ + 1, &readfds, NULL, NULL, &timeout_ts, NULL);
503 if (errno == EINTR) {
514 if (!FD_ISSET (fd_, &readfds)) {
516 " in the list, this shouldn't happen!");
525 timespec wait_time = { 0,
static_cast<long>(byte_time_ns_ * count)};
526 pselect (0, NULL, NULL, NULL, &wait_time, NULL);
536 size_t bytes_read = 0;
539 long total_timeout_ms = timeout_.read_timeout_constant;
540 total_timeout_ms += timeout_.read_timeout_multiplier *
static_cast<long> (size);
545 ssize_t bytes_read_now =
::read (fd_, buf, size);
546 if (bytes_read_now > 0) {
547 bytes_read = bytes_read_now;
551 while (bytes_read < size) {
552 int64_t timeout_remaining_ms = total_timeout.
remaining();
553 if (timeout_remaining_ms <= 0) {
559 uint32_t
timeout = std::min(
static_cast<uint32_t
> (timeout_remaining_ms),
560 timeout_.inter_byte_timeout);
566 if (size > 1 && timeout_.inter_byte_timeout ==
Timeout::max()) {
568 if (bytes_available + bytes_read < size) {
574 ssize_t bytes_read_now =
575 ::read (fd_, buf + bytes_read, size - bytes_read);
578 if (bytes_read_now < 1) {
583 "returned no data (device disconnected?)");
586 bytes_read +=
static_cast<size_t> (bytes_read_now);
588 if (bytes_read == size) {
592 if (bytes_read < size) {
596 if (bytes_read > size) {
598 "read, this shouldn't happen, might be "
609 if (is_open_ ==
false) {
613 size_t bytes_written = 0;
616 long total_timeout_ms = timeout_.write_timeout_constant;
617 total_timeout_ms += timeout_.write_timeout_multiplier *
static_cast<long> (
length);
620 while (bytes_written <
length) {
621 int64_t timeout_remaining_ms = total_timeout.
remaining();
622 if (timeout_remaining_ms <= 0) {
629 FD_SET (fd_, &writefds);
632 int r = pselect (fd_ + 1, NULL, &writefds, NULL, &
timeout, NULL);
638 if (errno == EINTR) {
651 if (FD_ISSET (fd_, &writefds)) {
653 ssize_t bytes_written_now =
657 if (bytes_written_now < 1) {
662 "returned no data (device disconnected?)");
665 bytes_written +=
static_cast<size_t> (bytes_written_now);
667 if (bytes_written ==
length) {
671 if (bytes_written <
length) {
675 if (bytes_written >
length) {
677 "written, this shouldn't happen, might be "
683 " in the list, this shouldn't happen!");
686 return bytes_written;
716 baudrate_ = baudrate;
730 bytesize_ = bytesize;
758 stopbits_ = stopbits;
772 flowcontrol_ = flowcontrol;
786 if (is_open_ ==
false) {
795 if (is_open_ ==
false) {
798 tcflush (fd_, TCIFLUSH);
804 if (is_open_ ==
false) {
807 tcflush (fd_, TCOFLUSH);
813 if (is_open_ ==
false) {
816 tcsendbreak (fd_,
static_cast<int> (duration / 4));
822 if (is_open_ ==
false) {
827 if (-1 == ioctl (fd_, TIOCSBRK))
830 ss <<
"setBreak failed on a call to ioctl(TIOCSBRK): " << errno <<
" " << strerror(errno);
834 if (-1 == ioctl (fd_, TIOCCBRK))
837 ss <<
"setBreak failed on a call to ioctl(TIOCCBRK): " << errno <<
" " << strerror(errno);
846 if (is_open_ ==
false) {
853 if (-1 == ioctl (fd_, TIOCMBIS, &
command))
856 ss <<
"setRTS failed on a call to ioctl(TIOCMBIS): " << errno <<
" " << strerror(errno);
860 if (-1 == ioctl (fd_, TIOCMBIC, &
command))
863 ss <<
"setRTS failed on a call to ioctl(TIOCMBIC): " << errno <<
" " << strerror(errno);
872 if (is_open_ ==
false) {
879 if (-1 == ioctl (fd_, TIOCMBIS, &
command))
882 ss <<
"setDTR failed on a call to ioctl(TIOCMBIS): " << errno <<
" " << strerror(errno);
886 if (-1 == ioctl (fd_, TIOCMBIC, &
command))
889 ss <<
"setDTR failed on a call to ioctl(TIOCMBIC): " << errno <<
" " << strerror(errno);
900 while (is_open_ ==
true) {
904 if (-1 == ioctl (fd_, TIOCMGET, &status))
907 ss <<
"waitForChange failed on a call to ioctl(TIOCMGET): " << errno <<
" " << strerror(errno);
912 if (0 != (status & TIOCM_CTS)
913 || 0 != (status & TIOCM_DSR)
914 || 0 != (status & TIOCM_RI)
915 || 0 != (status & TIOCM_CD))
926 int command = (TIOCM_CD|TIOCM_DSR|TIOCM_RI|TIOCM_CTS);
928 if (-1 == ioctl (fd_, TIOCMIWAIT, &
command)) {
930 ss <<
"waitForDSR failed on a call to ioctl(TIOCMIWAIT): "
931 << errno <<
" " << strerror(errno);
941 if (is_open_ ==
false) {
947 if (-1 == ioctl (fd_, TIOCMGET, &status))
950 ss <<
"getCTS failed on a call to ioctl(TIOCMGET): " << errno <<
" " << strerror(errno);
955 return 0 != (status & TIOCM_CTS);
962 if (is_open_ ==
false) {
968 if (-1 == ioctl (fd_, TIOCMGET, &status))
971 ss <<
"getDSR failed on a call to ioctl(TIOCMGET): " << errno <<
" " << strerror(errno);
976 return 0 != (status & TIOCM_DSR);
983 if (is_open_ ==
false) {
989 if (-1 == ioctl (fd_, TIOCMGET, &status))
992 ss <<
"getRI failed on a call to ioctl(TIOCMGET): " << errno <<
" " << strerror(errno);
997 return 0 != (status & TIOCM_RI);
1004 if (is_open_ ==
false) {
1010 if (-1 == ioctl (fd_, TIOCMGET, &status))
1013 ss <<
"getCD failed on a call to ioctl(TIOCMGET): " << errno <<
" " << strerror(errno);
1018 return 0 != (status & TIOCM_CD);
1025 int result = pthread_mutex_lock(&this->read_mutex);
1034 int result = pthread_mutex_unlock(&this->read_mutex);
1043 int result = pthread_mutex_lock(&this->write_mutex);
1052 int result = pthread_mutex_unlock(&this->write_mutex);
1058 #endif // !defined(_WIN32)