30 : port_(
std::move(port)),
38 flowcontrol_(flowcontrol) {
56 fd_ =
::open(port_.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK | O_CLOEXEC);
66 if (::ioctl(fd_, TIOCEXCL) == -1) {
72 if(::fcntl(fd_, F_SETFL, 0) == -1) {
85 struct termios options{0};
86 if (::tcgetattr(fd_, &options) == -1) {
91 options.c_iflag &= ~(IGNBRK | BRKINT | IGNPAR | PARMRK | INPCK | ISTRIP | INLCR | IGNCR | ICRNL | IXON | IXOFF | IXANY);
93 options.c_iflag &= ~IUCLC;
96 options.c_iflag &= ~IMAXBEL;
100 options.c_oflag &= ~(OPOST | ONLCR | OCRNL | ONOCR | ONLRET | OFILL);
102 options.c_oflag &= ~OLCUC;
105 options.c_oflag &= ~NLDLY;
108 options.c_oflag &= ~CRDLY;
111 options.c_oflag &= ~TABDLY;
114 options.c_oflag &= ~BSDLY;
117 options.c_oflag &= ~VTDLY;
120 options.c_oflag &= ~FFDLY;
124 options.c_cflag &= (CSIZE | CSTOPB | PARENB | PARODD);
125 options.c_cflag |= (CREAD | HUPCL | CLOCAL);
127 options.c_cflag &= ~CMSPAR;
130 options.c_cflag &= ~CRTSCTS;
134 options.c_lflag &= ~(ISIG | ICANON | ECHO | ECHOE | ECHOK | ECHONL | IEXTEN);
136 options.c_lflag &= ~ECHOCTL;
139 options.c_lflag &= ~ECHOPRT;
142 options.c_lflag &= ~ECHOKE;
146 options.c_cc[VMIN] = 0;
147 options.c_cc[VTIME] = 0;
149 struct serial_struct serinfo;
151 ::ioctl(fd_, TIOCGSERIAL, &serinfo);
152 serinfo.flags |= ASYNC_LOW_LATENCY;
153 ::ioctl(fd_, TIOCSSERIAL, &serinfo);
155 bool use_custom_baudrate =
false;
156 speed_t baudrate = 0;
159 case 0: baudrate = B0;
break;
162 case 50: baudrate = B50;
break;
165 case 75: baudrate = B75;
break;
168 case 110: baudrate = B110;
break;
171 case 134: baudrate = B134;
break;
174 case 150: baudrate = B150;
break;
177 case 200: baudrate = B200;
break;
180 case 300: baudrate = B300;
break;
183 case 600: baudrate = B600;
break;
186 case 1200: baudrate = B1200;
break;
189 case 1800: baudrate = B1800;
break;
192 case 2400: baudrate = B2400;
break;
195 case 4800: baudrate = B4800;
break;
198 case 7200: baudrate = B7200;
break;
201 case 9600: baudrate = B9600;
break;
204 case 14400: baudrate = B14400;
break;
207 case 19200: baudrate = B19200;
break;
210 case 28800: baudrate = B28800;
break;
213 case 57600: baudrate = B57600;
break;
216 case 76800: baudrate = B76800;
break;
219 case 38400: baudrate = B38400;
break;
222 case 115200: baudrate = B115200;
break;
225 case 128000: baudrate = B128000;
break;
228 case 153600: baudrate = B153600;
break;
231 case 230400: baudrate = B230400;
break;
234 case 256000: baudrate = B256000;
break;
237 case 460800: baudrate = B460800;
break;
240 case 500000: baudrate = B500000;
break;
243 case 576000: baudrate = B576000;
break;
246 case 921600: baudrate = B921600;
break;
249 case 1000000: baudrate = B1000000;
break;
252 case 1152000: baudrate = B1152000;
break;
255 case 1500000: baudrate = B1500000;
break;
258 case 2000000: baudrate = B2000000;
break;
261 case 2500000: baudrate = B2500000;
break;
264 case 3000000: baudrate = B3000000;
break;
267 case 3500000: baudrate = B3500000;
break;
270 case 4000000: baudrate = B4000000;
break;
273 baudrate = baudrate_;
274 use_custom_baudrate =
true;
277 if (!use_custom_baudrate) {
278 if (::cfsetispeed(&options, baudrate) == -1) {
281 if (::cfsetospeed(&options, baudrate) == -1) {
287 case eightbits: options.c_cflag |= CS8;
break;
288 case sevenbits: options.c_cflag |= CS7;
break;
289 case sixbits: options.c_cflag |= CS6;
break;
290 case fivebits: options.c_cflag |= CS5;
break;
304 case parity_none: options.c_iflag |= IGNPAR;
break;
305 case parity_even: options.c_cflag |= PARENB;
break;
306 case parity_odd: options.c_cflag |= (PARENB | PARODD);
break;
308 case parity_mark: options.c_cflag |= (PARENB | PARODD | CMSPAR);
break;
309 case parity_space: options.c_cflag |= (PARENB | CMSPAR);
break;
315 switch (flowcontrol_) {
326 if (::tcsetattr(fd_, TCSANOW, &options) != 0) {
330 if (use_custom_baudrate) {
331 #if defined(__APPLE__)
332 if (::ioctl(fd_, IOSSIOSPEED, &baudrate) == -1) {
335 #elif defined(__linux__) && defined (TIOCSSERIAL) //TODO: maybe termios2 could be an alternative
336 struct serial_struct
serial {0};
337 if (::ioctl(fd_, TIOCGSERIAL, &
serial) == -1) {
342 serial.flags &= ~ASYNC_SPD_MASK;
343 serial.flags |= ASYNC_SPD_CUST;
344 serial.custom_divisor =
static_cast<int>((
serial.baud_base + baudrate_ / 2) / baudrate_);
345 int closest_baudrate =
serial.baud_base /
serial.custom_divisor;
346 if (std::abs(
static_cast<int>(closest_baudrate - baudrate_)) < 0.02) {
347 throw SerialIOException(
"cannot set baudrate to " + std::to_string(baudrate_) +
" (the closest possible value is " + std::to_string(closest_baudrate) +
")");
350 if (::ioctl(fd_, TIOCSSERIAL, &
serial) == -1) {
360 if (is_open_ && fd_ != -1 && ::
close(fd_) != 0) {
376 if (::ioctl(fd_, TIOCINQ, &count) == -1) {
379 return static_cast<size_t>(count);
382 bool waitOnPoll(std::chrono::milliseconds timeout_ms, std::unique_ptr<pollfd> fds) {
383 int r = ::poll(fds.get(), 1, timeout_ms.count());
384 if (r < 0 && errno != EINTR) {
387 if (fds->revents == POLLERR || fds->revents == POLLHUP || fds->revents == POLLNVAL) {
388 throw SerialIOException(
"failure during ::poll(), revents has been set to '" + std::to_string(fds->revents) +
"'.");
397 return waitOnPoll(timeout_ms, std::unique_ptr<pollfd>(
new pollfd{fd_, POLLIN, 0}));
404 return waitOnPoll(timeout_ms, std::unique_ptr<pollfd>(
new pollfd{fd_, POLLOUT, 0}));
408 auto start = std::chrono::steady_clock::now();
409 uint32_t bit_time_ns = 1e9 / baudrate_;
410 uint32_t byte_time_ns = bit_time_ns * (1 + bytesize_ + parity_ + stopbits_);
412 std::this_thread::sleep_until(
start + std::chrono::nanoseconds(byte_time_ns * count));
419 auto read_deadline = timeout_.getReadDeadline(size);
420 size_t total_bytes_read =
::read(fd_, buf, size);
421 if (total_bytes_read == -1) {
424 while (total_bytes_read < size) {
426 if (remaining_time.count() <= 0) {
429 if (
waitReadable(std::min(std::chrono::duration_cast<std::chrono::milliseconds>(remaining_time), timeout_.getInterByte()))) {
430 if (size - total_bytes_read > 1 && timeout_.getInterByteMilliseconds() == std::numeric_limits<uint32_t>::max()) {
432 if (bytes_available + total_bytes_read < size) {
436 size_t bytes_read =
::read(fd_, buf + total_bytes_read, size - total_bytes_read);
437 if (bytes_read < 1) {
440 total_bytes_read += bytes_read;
443 return total_bytes_read;
450 auto write_deadline = timeout_.getWriteDeadline(size);
451 size_t total_bytes_written =
::write(fd_, data, size);
452 if (total_bytes_written == -1) {
455 while (total_bytes_written < size) {
457 if (remaining_time.count() <= 0) {
460 if (
waitWritable(std::chrono::duration_cast<std::chrono::milliseconds>(remaining_time))) {
461 size_t bytes_written =
::write(fd_, data + total_bytes_written, size - total_bytes_written);
462 if (bytes_written < 1) {
465 total_bytes_written += bytes_written;
468 return total_bytes_written;
488 baudrate_ = baudrate;
499 bytesize_ = bytesize;
521 stopbits_ = stopbits;
532 flowcontrol_ = flowcontrol;
546 if (::tcflush(fd_, TCIOFLUSH) == -1) {
555 if (::tcflush(fd_, TCIFLUSH) == -1) {
564 if (::tcflush(fd_, TCOFLUSH) == -1) {
573 if (::tcsendbreak(fd_, duration_ms) == -1) {
579 setModemStatus(level ? TIOCSBRK : TIOCCBRK);
586 if (::ioctl(fd_, request, &
command) == -1) {
592 setModemStatus(level ? TIOCMBIS : TIOCMBIC, TIOCM_RTS);
596 setModemStatus(level ? TIOCMBIS : TIOCMBIC, TIOCM_DTR);
607 if (::ioctl(fd_, TIOCMIWAIT, TIOCM_CTS | TIOCM_DSR | TIOCM_RI | TIOCM_CD) == -1) {
617 uint32_t modem_status;
618 if (::ioctl(fd_, TIOCMGET, &modem_status) == -1) {
625 return getModemStatus() & TIOCM_CTS;
629 return getModemStatus() & TIOCM_DSR;
633 return getModemStatus() & TIOCM_RI;
637 return getModemStatus() & TIOCM_CD;
640 #endif // !defined(_WIN32)