73 #include <sys/ioctl.h>
76 #include <sys/param.h>
79 #if !defined(__APPLE__) && !defined(ANDROID)
80 #include <linux/serial.h>
87 #ifndef _CRT_SECURE_NO_DEPRECATE
88 #define _CRT_SECURE_NO_DEPRECATE
90 #pragma warning(disable:4996)
150 if (::GetCommTimeouts(
m_handle, &cto))
152 cto.ReadIntervalTimeout = MAXDWORD;
153 cto.ReadTotalTimeoutConstant = 0;
154 cto.ReadTotalTimeoutMultiplier = 0;
155 if (::SetCommTimeouts(
m_handle, &cto))
202 rv = EscapeCommFunction(
m_handle, SETDTR);
204 rv = EscapeCommFunction(
m_handle, CLRDTR);
210 rv = EscapeCommFunction(
m_handle, SETRTS);
212 rv = EscapeCommFunction(
m_handle, CLRRTS);
223 if (ioctl(
m_handle, TIOCMGET, &status) == -1)
228 status &= ~TIOCM_DTR;
229 rv = (ioctl(
m_handle, TIOCMSET, &status) == -1);
236 if (ioctl(
m_handle, TIOCMGET, &status) == -1)
241 status &= ~TIOCM_RTS;
242 rv = (ioctl(
m_handle, TIOCMSET, &status) == -1);
263 if (!PurgeComm(
m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR))
314 return m_handle != INVALID_HANDLE_VALUE;
321 template <
typename T>
353 JLALERTG(
"Port " << portInfo.portName() <<
" is already open");
359 JLTRACEG(
"Requested RTS/CTS flow control");
361 JLTRACEG(
"Requested DTR/DSR flow control");
363 JLTRACEG(
"Requested Xon/Xoff flow control");
367 char winPortName[256];
370 sprintf(winPortName,
"\\\\.\\%s", portInfo.portName_c_str());
371 m_handle = CreateFileA(winPortName, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL);
372 if (
m_handle == INVALID_HANDLE_VALUE)
374 JLDEBUGG(
"Port " << portInfo.portName() <<
" cannot be opened");
380 commState.DCBlength =
sizeof(DCB);
383 if (!GetCommState(
m_handle, &commState))
386 commState.BaudRate = (DWORD) portInfo.baudrate();
387 commState.Parity = NOPARITY;
388 commState.ByteSize = 8;
389 commState.StopBits = (options &
PO_TwoStopBits) ? TWOSTOPBITS : ONESTOPBIT;
393 commState.fOutxDsrFlow = (options &
PO_DtrDsrFlowControl) ? DTR_CONTROL_HANDSHAKE : DTR_CONTROL_DISABLE;
399 commState.fInX = commState.fOutX;
401 if (!SetCommState(
m_handle, (LPDCB)&commState))
405 commState.StopBits = ONESTOPBIT;
406 if (!SetCommState(
m_handle, (LPDCB)&commState))
409 char const* tmp = portInfo.portName_c_str();
410 m_port = (uint16_t) atoi(&tmp[3]);
421 if (!SetupComm(
m_handle, (DWORD) readBufSize, (DWORD) writeBufSize))
426 if (!PurgeComm(
m_handle, PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR))
440 std::string pn = portInfo.portName().toStdString();
454 if (flock(
m_handle, LOCK_EX | LOCK_NB))
466 if (cfsetispeed(&
m_commState, portInfo.baudrate()) != 0)
469 if (cfsetospeed(&
m_commState, portInfo.baudrate()) != 0)
486 m_commState.c_lflag &= ~(ECHO | ECHOE | ECHOK | ECHONL | ICANON | ISIG | IEXTEN);
488 m_commState.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | INPCK | ISTRIP | INLCR | IGNCR | ICRNL);
500 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_ALERT
501 termios checkCommState;
502 if (tcgetattr(
m_handle, &checkCommState) != 0)
505 if (cfgetispeed(&checkCommState) != portInfo.baudrate())
506 JLALERTG(
"Set baudrate doesn't match requested baudrate");
508 if (cfgetospeed(&checkCommState) != portInfo.baudrate())
509 JLALERTG(
"Set baudrate doesn't match requested baudrate");
512 JLALERTG(
"Requested RTS/CTS flow control, but could not be set.");
516 !(checkCommState.c_cflag & CDTRDSR)
521 JLALERTG(
"Requested DTR/DSR flow control, but could not be set.");
523 if (options &
PO_XonXoffFlowControl && !((checkCommState.c_iflag & (IXON | IXOFF)) == (IXON | IXOFF)))
524 JLALERTG(
"Requested Xon/Xoff flow control, but could not be set.");
525 #endif // JLDEF_BUILD < JLL_ALERT
527 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_DEBUG
528 #define CHECK_COMMSTATE(req, res, field)\
529 if (req.field != res.field) \
531 JLDEBUGG("field " << #field << " does not match");\
532 JLDEBUGG("actual : " << std::oct << (uint64_t)res.field);\
533 JLDEBUGG("expected: " << std::oct << (uint64_t)req.field);\
536 #define CHECK_COMMSTATE(req, res, field)
551 if (ioctl(
m_handle, TIOCMGET, &cmbits) < 0)
552 JLDEBUGG(
"TIOCMGET failed, which is OK for USB connected MkIV devices");
557 if (ioctl(
m_handle, TIOCMSET, &cmbits) < 0)
558 JLDEBUGG(
"TIOCMSET failed, which is OK for USB connected MkIV devices");
561 JLDEBUGG(
"Port " << portInfo.portName().toStdString() <<
" opened");
587 DWORD wErr = ::GetLastError();
588 JLALERTG(
"ReadFile returned windows error " << wErr);
589 if (wErr == ERROR_ACCESS_DENIED)
591 if (wErr >= ERROR_INVALID_FUNCTION && wErr <= ERROR_INVALID_HANDLE)
608 timeout.tv_usec = (
m_timeout - (timeout.tv_sec * 1000)) * 1000;
610 int res = select(FD_SETSIZE, &fd, NULL, &err, &timeout);
611 if (res < 0 || FD_ISSET(
m_handle, &err))
622 data.setSize(maxLength);
634 #if defined(EWOULDBLOCK) && EWOULDBLOCK != EAGAIN
646 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_TRACE && !defined(ANDROID)
647 serial_icounter_struct ic;
648 res = ioctl(
m_handle, TIOCGICOUNT, &ic);
655 JLTRACEG(
"buf_overrun " << ic.buf_overrun);
672 sprintf(fname,
"rx_%s_%d.log", devname + 1, XsBaud::rateToNumeric(
m_baudrate));
674 makeFilenameUnique(fname, state);
679 #ifdef LOG_RX_TX_FLUSH
699 JLDEBUGG(
"Setting timeout to " << ms <<
" ms");
704 COMMTIMEOUTS commTimeouts;
706 if (!GetCommTimeouts(
m_handle, &commTimeouts))
712 commTimeouts.ReadIntervalTimeout = 0;
713 commTimeouts.ReadTotalTimeoutConstant =
m_timeout;
714 commTimeouts.ReadTotalTimeoutMultiplier = 0;
715 commTimeouts.WriteTotalTimeoutConstant =
m_timeout;
716 commTimeouts.WriteTotalTimeoutMultiplier = 0;
721 commTimeouts.ReadIntervalTimeout = MAXDWORD;
722 commTimeouts.ReadTotalTimeoutConstant = 0;
723 commTimeouts.ReadTotalTimeoutMultiplier = 0;
724 commTimeouts.WriteTotalTimeoutConstant = 0;
725 commTimeouts.WriteTotalTimeoutMultiplier = 0;
728 if (!SetCommTimeouts(
m_handle, &commTimeouts))
771 JLTRACEG(
"Read " <<
data.size() <<
" of " << maxLength <<
" bytes");
795 if (WriteFile(
m_handle,
data.data(), (DWORD)
data.size(), &lwritten, NULL) == 0)
797 DWORD wErr = ::GetLastError();
798 JLALERTG(
"WriteFile returned windows error " << wErr);
799 if (wErr == ERROR_ACCESS_DENIED)
814 #if defined(EWOULDBLOCK) && EWOULDBLOCK != EAGAIN
845 sprintf(fname,
"tx_%s_%d.log", devname + 1, XsBaud::rateToNumeric(
m_baudrate));
847 makeFilenameUnique(fname, state);
852 #ifdef LOG_RX_TX_FLUSH
908 if (!EscapeCommFunction(
m_handle, SETDTR))
918 if (!EscapeCommFunction(
m_handle, SETDTR))
923 if (!EscapeCommFunction(
m_handle, SETDTR))
931 if (!EscapeCommFunction(
m_handle, CLRDTR))
950 if (!EscapeCommFunction(
m_handle, SETRTS))
958 if (!EscapeCommFunction(
m_handle, CLRRTS))