serialinterface.cpp
Go to the documentation of this file.
1 
2 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without modification,
6 // are permitted provided that the following conditions are met:
7 //
8 // 1. Redistributions of source code must retain the above copyright notice,
9 // this list of conditions, and the following disclaimer.
10 //
11 // 2. Redistributions in binary form must reproduce the above copyright notice,
12 // this list of conditions, and the following disclaimer in the documentation
13 // and/or other materials provided with the distribution.
14 //
15 // 3. Neither the names of the copyright holders nor the names of their contributors
16 // may be used to endorse or promote products derived from this software without
17 // specific prior written permission.
18 //
19 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
20 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
21 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
22 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
23 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
24 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
25 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
26 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
27 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
28 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
29 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
30 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
31 //
32 
33 
34 // Copyright (c) 2003-2021 Xsens Technologies B.V. or subsidiaries worldwide.
35 // All rights reserved.
36 //
37 // Redistribution and use in source and binary forms, with or without modification,
38 // are permitted provided that the following conditions are met:
39 //
40 // 1. Redistributions of source code must retain the above copyright notice,
41 // this list of conditions, and the following disclaimer.
42 //
43 // 2. Redistributions in binary form must reproduce the above copyright notice,
44 // this list of conditions, and the following disclaimer in the documentation
45 // and/or other materials provided with the distribution.
46 //
47 // 3. Neither the names of the copyright holders nor the names of their contributors
48 // may be used to endorse or promote products derived from this software without
49 // specific prior written permission.
50 //
51 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND ANY
52 // EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED WARRANTIES OF
53 // MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL
54 // THE COPYRIGHT HOLDERS OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
55 // SPECIAL, EXEMPLARY OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT
56 // OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION)
57 // HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY OR
58 // TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
59 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.THE LAWS OF THE NETHERLANDS
60 // SHALL BE EXCLUSIVELY APPLICABLE AND ANY DISPUTES SHALL BE FINALLY SETTLED UNDER THE RULES
61 // OF ARBITRATION OF THE INTERNATIONAL CHAMBER OF COMMERCE IN THE HAGUE BY ONE OR MORE
62 // ARBITRATORS APPOINTED IN ACCORDANCE WITH SAID RULES.
63 //
64 
65 #include "serialinterface.h"
66 #include <xstypes/xsportinfo.h>
67 #include <xstypes/xscontrolline.h>
68 #include "rx_tx_log.h"
69 
70 #include <errno.h>
71 #ifndef _WIN32
72  #include <unistd.h> // close
73  #include <sys/ioctl.h> // ioctl
74  #include <fcntl.h> // open, O_RDWR
75  #include <string.h> // strcpy
76  #include <sys/param.h>
77  #include <sys/file.h>
78  #include <stdarg.h>
79  #if !defined(__APPLE__) && !defined(ANDROID)
80  #include <linux/serial.h>
81  #endif
82 #else
83  #include <winbase.h>
84  #include <io.h>
85 #endif
86 
87 #ifndef _CRT_SECURE_NO_DEPRECATE
88  #define _CRT_SECURE_NO_DEPRECATE
89  #ifdef _WIN32
90  #pragma warning(disable:4996)
91  #endif
92 #endif
93 
97 
100 {
101  m_port = 0;
103  m_timeout = 0;
104  m_endTime = 0;
106  m_portname[0] = 0;
107 #ifdef _WIN32
108  m_handle = INVALID_HANDLE_VALUE;
109 #else
110  m_handle = -1;
111  memset(&m_commState, 0, sizeof(m_commState));
112 #endif
113 }
114 
117 {
118  try
119  {
120  closeLive();
121  }
122  catch (...)
123  {
124  }
125 }
126 
129 {
130  return closeLive();
131 }
132 
135 {
136 #ifdef LOG_RX_TX
137  rx_log.close();
138  tx_log.close();
139 #endif
140  if (!isOpen())
141  return m_lastResult = XRV_NOPORTOPEN;
142 
144 #ifdef _WIN32
145  if (::FlushFileBuffers(m_handle))
146  {
147  // read all data before closing the handle, a Flush is not enough for FTDI devices unfortunately
148  // we first need to set the COMM timeouts to instantly return when no more data is available
149  COMMTIMEOUTS cto;
150  if (::GetCommTimeouts(m_handle, &cto))
151  {
152  cto.ReadIntervalTimeout = MAXDWORD;
153  cto.ReadTotalTimeoutConstant = 0;
154  cto.ReadTotalTimeoutMultiplier = 0;
155  if (::SetCommTimeouts(m_handle, &cto))
156  {
157  char buffer[1024];
158  DWORD length;
159  do
160  {
161  if (!::ReadFile(m_handle, buffer, 1024, &length, NULL))
162  break;
163  } while (length > 0);
164  }
165  else
167  }
168  else
170  }
171  if (!::CloseHandle(m_handle))
173  m_handle = INVALID_HANDLE_VALUE;
174 #else
175  flushData();
176  ::close(m_handle);
177  m_handle = -1;
178 #endif
179  m_endTime = 0;
180 
181  return m_lastResult;
182 }
183 
194 {
195  if (!isOpen())
196  return (m_lastResult = XRV_NOPORTOPEN);
197 #ifdef _WIN32
198  BOOL rv = 0;
199  if (mask & XCL_DTR)
200  {
201  if (state & XCL_DTR)
202  rv = EscapeCommFunction(m_handle, SETDTR);
203  else
204  rv = EscapeCommFunction(m_handle, CLRDTR);
205  }
206 
207  if (mask & XCL_RTS)
208  {
209  if (state & XCL_RTS)
210  rv = EscapeCommFunction(m_handle, SETRTS);
211  else
212  rv = EscapeCommFunction(m_handle, CLRRTS);
213  }
214  if (rv)
215  return m_lastResult = XRV_OK;
216  else
217  return m_lastResult = XRV_ERROR;
218 #else
219  bool rv = true;
220  int32_t status;
221  if (mask & XCL_DTR)
222  {
223  if (ioctl(m_handle, TIOCMGET, &status) == -1)
224  {
225  if (state & XCL_DTR)
226  status |= TIOCM_DTR;
227  else
228  status &= ~TIOCM_DTR;
229  rv = (ioctl(m_handle, TIOCMSET, &status) == -1);
230  }
231  else
232  rv = false;
233  }
234  if (rv && (mask & XCL_RTS))
235  {
236  if (ioctl(m_handle, TIOCMGET, &status) == -1)
237  {
238  if (state & XCL_RTS)
239  status |= TIOCM_RTS;
240  else
241  status &= ~TIOCM_RTS;
242  rv = (ioctl(m_handle, TIOCMSET, &status) == -1);
243  }
244  else
245  rv = false;
246  }
247  if (rv)
248  return m_lastResult = XRV_OK;
249  else
250  return m_lastResult = XRV_ERROR;
251 #endif
252 }
253 
259 {
261 #ifdef _WIN32
262  // Remove any 'old' data in buffer
263  if (!PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR))
265 #else
266  tcflush(m_handle, TCIOFLUSH);
267 #endif
268  m_endTime = 0;
269  return m_lastResult;
270 }
271 
274 {
275  if (isOpen())
276  return m_baudrate;
277  return XBR_Invalid;
278 }
279 
282 {
283  return m_handle;
284 }
285 
287 uint16_t SerialInterface::getPortNumber(void) const
288 {
289  return m_port;
290 }
291 
294 {
295  portname = m_portname;
296 }
297 
300 {
301  return m_lastResult;
302 }
303 
306 {
307  return m_timeout;
308 }
309 
311 bool SerialInterface::isOpen(void) const
312 {
313 #ifdef _WIN32
314  return m_handle != INVALID_HANDLE_VALUE;
315 #else
316  return m_handle >= 0;
317 #endif
318 }
319 
320 #ifndef _WIN32
321 template <typename T>
322 static T setBitsEnabled(T field, T bits, bool cond)
323 {
324  if (cond)
325  field |= bits;
326  else
327  field &= (~bits);
328  return field;
329 }
330 #endif
331 
343  XsFilePos readBufSize,
344  XsFilePos writeBufSize,
345  PortOptions options)
346 {
347  m_endTime = 0;
348 
349  JLDEBUGG(portInfo);
350 
351  if (isOpen())
352  {
353  JLALERTG("Port " << portInfo.portName() << " is already open");
354  return (m_lastResult = XRV_ALREADYOPEN);
355  }
356  m_baudrate = portInfo.baudrate();
357 
358  if (options & PO_RtsCtsFlowControl || (portInfo.linesOptions() & XPLO_RtsCtsFlowControl))
359  JLTRACEG("Requested RTS/CTS flow control");
360  if (options & PO_DtrDsrFlowControl)
361  JLTRACEG("Requested DTR/DSR flow control");
362  if (options & PO_XonXoffFlowControl)
363  JLTRACEG("Requested Xon/Xoff flow control");
364 
365 #ifdef _WIN32
366  XsResultValue fail = XRV_OK;
367  char winPortName[256];
368 
369  // Open port
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)
373  {
374  JLDEBUGG("Port " << portInfo.portName() << " cannot be opened");
376  }
377 
378  DCB commState;
379 
380  commState.DCBlength = sizeof(DCB);
381 
382  //Get the current state & then change it
383  if (!GetCommState(m_handle, &commState)) // Get current state
384  fail = XRV_ERROR;
385 
386  commState.BaudRate = (DWORD) portInfo.baudrate(); // Setup the baud rate
387  commState.Parity = NOPARITY; // Setup the Parity
388  commState.ByteSize = 8; // Setup the data bits
389  commState.StopBits = (options & PO_TwoStopBits) ? TWOSTOPBITS : ONESTOPBIT;
390 
391  // Setup flow control
392  commState.fDsrSensitivity = (options & PO_DtrDsrFlowControl) ? TRUE : FALSE;
393  commState.fOutxDsrFlow = (options & PO_DtrDsrFlowControl) ? DTR_CONTROL_HANDSHAKE : DTR_CONTROL_DISABLE;
394 
395  commState.fOutxCtsFlow = (options & PO_RtsCtsFlowControl || (portInfo.linesOptions() & XPLO_RtsCtsFlowControl)) ? TRUE : FALSE;
396  commState.fRtsControl = (options & PO_RtsCtsFlowControl || (portInfo.linesOptions() & XPLO_RtsCtsFlowControl)) ? RTS_CONTROL_HANDSHAKE : RTS_CONTROL_ENABLE;
397 
398  commState.fOutX = (options & PO_XonXoffFlowControl) ? TRUE : FALSE;
399  commState.fInX = commState.fOutX;
400 
401  if (!SetCommState(m_handle, (LPDCB)&commState)) // Set new state
402  {
403  // Bluetooth ports cannot always be opened with 2 stopbits
404  // Now try to open port with 1 stopbit.
405  commState.StopBits = ONESTOPBIT;
406  if (!SetCommState(m_handle, (LPDCB)&commState))
408  }
409  char const* tmp = portInfo.portName_c_str();
410  m_port = (uint16_t) atoi(&tmp[3]);
411  sprintf(m_portname, "%s", tmp);
412 
413  if (setTimeout(20))
414  fail = m_lastResult;
415 
416  // Other initialization functions
417  int tmpFail = fail;
418  applyHwControlLinesOptions(options, portInfo.linesOptions(), tmpFail);
419  fail = static_cast<XsResultValue>(tmpFail);
420 
421  if (!SetupComm(m_handle, (DWORD) readBufSize, (DWORD) writeBufSize)) // Set queue size
422  fail = XRV_ERROR;
423 
424  // Remove any 'old' data in buffer
425  //PurgeComm(m_handle, PURGE_TXCLEAR | PURGE_RXCLEAR);
426  if (!PurgeComm(m_handle, PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR))
427  fail = XRV_ERROR;
428 
429  if (fail != XRV_OK)
430  {
431  CloseHandle(m_handle);
432  m_handle = INVALID_HANDLE_VALUE;
433  return (m_lastResult = fail);
434  }
435 
436 #else // !_WIN32
437  (void)readBufSize;
438  (void)writeBufSize;
439  // Open port
440  std::string pn = portInfo.portName().toStdString();
441  m_handle = ::open(pn.c_str(), O_RDWR | O_NOCTTY);
442 
443  // O_RDWR: Read+Write
444  // O_NOCTTY: Raw input, no "controlling terminal"
445  // O_NDELAY: Don't care about DCD signal
446 
447  if (m_handle < 0)
448  {
449  // Port not open
451  }
452 
453  // Check if the file is already opened by someome else (other thread/process)
454  if (flock(m_handle, LOCK_EX | LOCK_NB))
455  {
456  closeLive();
458  }
459 
460  /* Start configuring of port for non-canonical transfer mode */
461  // Get current options for the port
462  if (tcgetattr(m_handle, &m_commState) != 0)
463  return XRV_ERROR;
464 
465  // Set baudrate.
466  if (cfsetispeed(&m_commState, portInfo.baudrate()) != 0)
467  return XRV_ERROR;
468 
469  if (cfsetospeed(&m_commState, portInfo.baudrate()) != 0)
470  return XRV_ERROR;
471 
472  // Enable the receiver and set local mode
473  m_commState.c_cflag |= (CLOCAL | CREAD);
474  // Set character size to data bits and set no parity Mask the characte size bits
475  m_commState.c_cflag &= ~(CSIZE | PARENB | PARODD);
476  m_commState.c_cflag |= CS8; // Select 8 data bits
477 
478  m_commState.c_cflag = setBitsEnabled(m_commState.c_cflag, (tcflag_t)CSTOPB, (options & PO_TwoStopBits) == PO_TwoStopBits);
479 
480  // Hardware flow control
481  m_commState.c_cflag = setBitsEnabled(m_commState.c_cflag, (tcflag_t)CRTSCTS, (options & PO_RtsCtsFlowControl) == PO_RtsCtsFlowControl);
482 #ifdef CDTRDSR
483  m_commState.c_cflag = setBitsEnabled(m_commState.c_cflag, (tcflag_t)CDTRDSR, (options & PO_DtrDsrFlowControl) == PO_DtrDsrFlowControl);
484 #endif
485 
486  m_commState.c_lflag &= ~(ECHO | ECHOE | ECHOK | ECHONL | ICANON | ISIG | IEXTEN);
487  // Software flow control
488  m_commState.c_iflag &= ~(IGNBRK | BRKINT | PARMRK | INPCK | ISTRIP | INLCR | IGNCR | ICRNL);
489  m_commState.c_iflag = setBitsEnabled(m_commState.c_iflag, (tcflag_t)(IXON | IXOFF), options & PO_XonXoffFlowControl);
490  // Set Raw output
491  m_commState.c_oflag &= ~OPOST;
492  // Timeout 0.001 sec for first byte, read minimum of 0 bytes
493  m_commState.c_cc[VMIN] = 0;
494  m_commState.c_cc[VTIME] = (m_timeout + 99) / 100; // 1
495 
496  // Set the new options for the port
497  if (tcsetattr(m_handle, TCSANOW, &m_commState) != 0)
499 
500 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_ALERT
501  termios checkCommState;
502  if (tcgetattr(m_handle, &checkCommState) != 0)
503  return XRV_ERROR;
504 
505  if (cfgetispeed(&checkCommState) != portInfo.baudrate())
506  JLALERTG("Set baudrate doesn't match requested baudrate");
507 
508  if (cfgetospeed(&checkCommState) != portInfo.baudrate())
509  JLALERTG("Set baudrate doesn't match requested baudrate");
510 
511  if (options & PO_RtsCtsFlowControl && !(checkCommState.c_cflag & CRTSCTS))
512  JLALERTG("Requested RTS/CTS flow control, but could not be set.");
513 
514  if (options & PO_DtrDsrFlowControl &&
515 #ifdef CDTRDSR
516  !(checkCommState.c_cflag & CDTRDSR)
517 #else
518  false
519 #endif
520  )
521  JLALERTG("Requested DTR/DSR flow control, but could not be set.");
522 
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
526 
527 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_DEBUG
528 #define CHECK_COMMSTATE(req, res, field)\
529  if (req.field != res.field) \
530  {\
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);\
534  }
535 #else
536 #define CHECK_COMMSTATE(req, res, field)
537 #endif
538  CHECK_COMMSTATE(m_commState, checkCommState, c_cflag);
539  CHECK_COMMSTATE(m_commState, checkCommState, c_iflag);
540  CHECK_COMMSTATE(m_commState, checkCommState, c_oflag);
541  CHECK_COMMSTATE(m_commState, checkCommState, c_cc[VMIN]);
542  CHECK_COMMSTATE(m_commState, checkCommState, c_cc[VTIME]);
543 
544  m_port = 1;
545  sprintf(m_portname, "%s", pn.c_str());
546 
547  tcflush(m_handle, TCIOFLUSH);
548 
549  // setting RTS and DTR;
550  int cmbits;
551  if (ioctl(m_handle, TIOCMGET, &cmbits) < 0)
552  JLDEBUGG("TIOCMGET failed, which is OK for USB connected MkIV devices");
553 
554  // Port Lines Options
555  applyHwControlLinesOptions(options, portInfo.linesOptions(), cmbits);
556 
557  if (ioctl(m_handle, TIOCMSET, &cmbits) < 0)
558  JLDEBUGG("TIOCMSET failed, which is OK for USB connected MkIV devices");
559 #endif // !_WIN32
560 
561  JLDEBUGG("Port " << portInfo.portName().toStdString() << " opened");
562  return (m_lastResult = XRV_OK);
563 }
564 
574 {
575  if (!isOpen())
576  return (m_lastResult = XRV_NOPORTOPEN);
577 
578 #ifdef _WIN32
579  DWORD length;
580  data.setSize((XsSize) maxLength);
581  BOOL rres = ::ReadFile(m_handle, data.data(), (DWORD) maxLength, &length, NULL);
582  data.pop_back((XsSize)(maxLength - length));
583  JLTRACEG("ReadFile result " << rres << ", length " << length);
584 
585  if (!rres)
586  {
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)
593  return (m_lastResult = XRV_ERROR);
594  }
595 
596  if (length == 0)
597  return (m_lastResult = XRV_TIMEOUT);
598 #else
599  fd_set fd;
600  fd_set err;
601  timeval timeout;
602  FD_ZERO(&fd);
603  FD_ZERO(&err);
604  FD_SET(m_handle, &fd);
605  FD_SET(m_handle, &err);
606 
607  timeout.tv_sec = m_timeout / 1000;
608  timeout.tv_usec = (m_timeout - (timeout.tv_sec * 1000)) * 1000;
609 
610  int res = select(FD_SETSIZE, &fd, NULL, &err, &timeout);
611  if (res < 0 || FD_ISSET(m_handle, &err))
612  {
613  data.clear();
614  return (m_lastResult = XRV_ERROR);
615  }
616  else if (res == 0)
617  {
618  data.clear();
619  return (m_lastResult = XRV_TIMEOUT);
620  }
621 
622  data.setSize(maxLength);
623  int length = read(m_handle, (void*)data.data(), maxLength);
624  if (length > 0)
625  data.pop_back(maxLength - length);
626  else
627  {
628  int err = errno;
629 
630  data.clear();
631  switch (err)
632  {
633  case EAGAIN:
634 #if defined(EWOULDBLOCK) && EWOULDBLOCK != EAGAIN
635  case EWOULDBLOCK:
636 #endif
637  return XRV_TIMEOUT;
638 
639  case EIO:
641 
642  default:
643  break;
644  }
645  }
646 #if defined(JLDEF_BUILD) && JLDEF_BUILD <= JLL_TRACE && !defined(ANDROID)
647  serial_icounter_struct ic;
648  res = ioctl(m_handle, TIOCGICOUNT, &ic);
649  if (res == 0)
650  {
651  JLTRACEG("rx: " << ic.rx);
652  JLTRACEG("tx: " << ic.tx);
653  JLTRACEG("frame " << ic.frame);
654  JLTRACEG("overrun " << ic.overrun);
655  JLTRACEG("buf_overrun " << ic.buf_overrun);
656  }
657 #endif
658 #endif
659 
660 #ifdef LOG_RX_TX
661  if (length > 0)
662  {
663  CHECK_STATE_RX(length, data, rx_log);
664 
665  if (!rx_log.isOpen())
666  {
667  char fname[XS_MAX_FILENAME_LENGTH];
668 #ifdef _WIN32
669  sprintf(fname, "rx_%03d_%d.log", (int32_t) m_port, m_baudrate);
670 #else
671  char* devname = strrchr(m_portname, '/');
672  sprintf(fname, "rx_%s_%d.log", devname + 1, XsBaud::rateToNumeric(m_baudrate));
673 #endif
674  makeFilenameUnique(fname, state);
675 
676  rx_log.create(XsString(fname), true);
677  }
678  rx_log.write(data.data(), 1, length);
679 #ifdef LOG_RX_TX_FLUSH
680  rx_log.flush();
681 #endif
682  }
683 #endif
684 
685  JLTRACEG("returned success, read " << length << " of " << maxLength << " bytes, first: " << JLHEXLOG(data[0]));
686  return (m_lastResult = XRV_OK);
687 }
688 
698 {
699  JLDEBUGG("Setting timeout to " << ms << " ms");
700 
701  m_timeout = ms;
702 #ifdef _WIN32
703  // Set COM timeouts
704  COMMTIMEOUTS commTimeouts;
705 
706  if (!GetCommTimeouts(m_handle, &commTimeouts)) // Fill CommTimeouts structure
707  return m_lastResult = XRV_ERROR;
708 
709  // immediate return if data is available, wait 1ms otherwise
710  if (m_timeout > 0)
711  {
712  commTimeouts.ReadIntervalTimeout = 0;
713  commTimeouts.ReadTotalTimeoutConstant = m_timeout; // ms time
714  commTimeouts.ReadTotalTimeoutMultiplier = 0;
715  commTimeouts.WriteTotalTimeoutConstant = m_timeout;
716  commTimeouts.WriteTotalTimeoutMultiplier = 0;
717  }
718  else
719  {
720  // immediate return whether data is available or not
721  commTimeouts.ReadIntervalTimeout = MAXDWORD;
722  commTimeouts.ReadTotalTimeoutConstant = 0;
723  commTimeouts.ReadTotalTimeoutMultiplier = 0;
724  commTimeouts.WriteTotalTimeoutConstant = 0;
725  commTimeouts.WriteTotalTimeoutMultiplier = 0;
726  }
727 
728  if (!SetCommTimeouts(m_handle, &commTimeouts)) // Set CommTimeouts structure
729  return m_lastResult = XRV_ERROR;
730 #else
731  // Timeout 0.1 sec for first byte, read minimum of 0 bytes
732  m_commState.c_cc[VMIN] = 0;
733  m_commState.c_cc[VTIME] = (m_timeout + 99) / 100; // ds time
734 
735  // Set the new options for the port if it is open
736  if (isOpen())
737  tcsetattr(m_handle, TCSANOW, &m_commState);
738 #endif
739  return (m_lastResult = XRV_OK);
740 }
741 
752 {
753  data.clear();
754  data.reserve((XsSize) maxLength);
755 
756  //char *data = (char *)&_data[0];
757  JLTRACEG("timeout=" << m_timeout << ", maxLength=" << maxLength);
758  uint32_t timeout = m_timeout;
759 
760  uint32_t eTime = XsTime_getTimeOfDay(NULL, NULL) + timeout;
761  // uint32_t newLength = 0;
762 
763  while (((XsFilePos) data.size() < maxLength) && (XsTime_getTimeOfDay(NULL, NULL) <= eTime))
764  {
765  XsByteArray raw;
766 
767  if (readData(maxLength - (XsFilePos) data.size(), raw) != XRV_OK)
768  return m_lastResult;
769  data.append(raw);
770  }
771  JLTRACEG("Read " << data.size() << " of " << maxLength << " bytes");
772 
773  if ((XsFilePos) data.size() < maxLength)
774  return (m_lastResult = XRV_TIMEOUT);
775  else
776  return (m_lastResult = XRV_OK);
777 }
778 
783 {
784  XsFilePos bytes;
785  if (written == NULL)
786  written = &bytes;
787 
788  if (!isOpen())
789  return (m_lastResult = XRV_NOPORTOPEN);
790 
791  *written = 0;
792 
793 #ifdef _WIN32
794  DWORD lwritten = 0;
795  if (WriteFile(m_handle, data.data(), (DWORD) data.size(), &lwritten, NULL) == 0)
796  {
797  DWORD wErr = ::GetLastError();
798  JLALERTG("WriteFile returned windows error " << wErr);
799  if (wErr == ERROR_ACCESS_DENIED)
801  return (m_lastResult = XRV_ERROR);
802  }
803 
804  *written = lwritten;
805 #else
806  ssize_t result = write(m_handle, (const void*)data.data(), data.size());
807  if (result <= 0)
808  {
809  int err = errno;
810  *written = 0;
811  switch (err)
812  {
813  case EAGAIN:
814 #if defined(EWOULDBLOCK) && EWOULDBLOCK != EAGAIN
815  case EWOULDBLOCK:
816 #endif
817  return XRV_TIMEOUT;
818 
819  case EIO:
821 
822  /* we don't expect any other errors to actually occur */
823  default:
824  break;
825  }
826  }
827 
828  if (result < 0)
829  *written = 0;
830  else
831  *written = result;
832 #endif
833 
834 #ifdef LOG_RX_TX
835  if (written[0] > 0)
836  {
837  CHECK_STATE_TX(written[0], data, tx_log);
838  if (!tx_log.isOpen())
839  {
840  char fname[XS_MAX_FILENAME_LENGTH];
841 #ifdef _WIN32
842  sprintf(fname, "tx_%03d_%d.log", (int32_t) m_port, m_baudrate);
843 #else
844  char* devname = strrchr(m_portname, '/');
845  sprintf(fname, "tx_%s_%d.log", devname + 1, XsBaud::rateToNumeric(m_baudrate));
846 #endif
847  makeFilenameUnique(fname, state);
848 
849  tx_log.create(XsString(fname), true);
850  }
851  tx_log.write(data.data(), 1, *written);
852 #ifdef LOG_RX_TX_FLUSH
853  tx_log.flush();
854 #endif
855  }
856 #endif
857 
858  return (m_lastResult = XRV_OK);
859 }
860 
863 {
864 #ifdef _WIN32
865  /* This function is only available on Windows Vista and higher.
866  When a read action hangs, this function can cancel IO operations from another thread.
867  */
868  //CancelIoEx(m_handle, NULL);
869 #endif
870 }
871 
874 {
875  return static_cast<SerialInterface::PortOptions>(static_cast<unsigned int>(lhs) | static_cast<unsigned int>(rhs));
876 }
877 
880 {
881  return static_cast<SerialInterface::PortOptions>(static_cast<unsigned int>(lhs) & static_cast<unsigned int>(rhs));
882 }
883 
886 {
887  return static_cast<SerialInterface::PortOptions>(~static_cast<unsigned int>(lhs));
888 }
889 
895 void SerialInterface::applyHwControlLinesOptions(PortOptions options, int portLinesOptions, int& p)
896 {
897  const XsPortLinesOptions pLinesOpts = static_cast<XsPortLinesOptions>(portLinesOptions);
898 
899 #ifdef _WIN32
900 
901  // DTR Line Options
902  if (!(options & PO_DtrDsrFlowControl))
903  {
904  // Flow Control is disabled
905  if ((pLinesOpts == XPLO_Invalid) || (pLinesOpts & XPLO_DTR_Ignore))
906  {
907  // Default behaviour
908  if (!EscapeCommFunction(m_handle, SETDTR)) // Set DTR (Calibration sensors need DTR to startup, won't hurt otherwise)
909  p = XRV_ERROR;
910  }
911  else
912  {
913  // Handle flow control line options
914  if (((pLinesOpts & (XPLO_DTR_Set | XPLO_DTR_Clear)) == (XPLO_DTR_Set | XPLO_DTR_Clear))
915  || ((pLinesOpts & (XPLO_DTR_Set | XPLO_DTR_Clear)) == 0))
916  {
917  // Line options are not valid, both Set and Clear are high or down
918  if (!EscapeCommFunction(m_handle, SETDTR)) // Default behaviour
919  p = XRV_ERROR;
920  }
921  else if (pLinesOpts & XPLO_DTR_Set)
922  {
923  if (!EscapeCommFunction(m_handle, SETDTR)) // Set DTR
924  p = XRV_ERROR;
925  }
926  else
927  {
928  // XPLO_DTR_Clear is Set
929  assert(pLinesOpts & XPLO_DTR_Clear);
930 
931  if (!EscapeCommFunction(m_handle, CLRDTR)) // Clear DTR
932  p = XRV_ERROR;
933  }
934  }
935  }
936 
937  // RTS Line Options
938  if (!(options & PO_RtsCtsFlowControl))
939  {
940  // Flow Control is disabled
941  if ((pLinesOpts != XPLO_Invalid) && !(pLinesOpts & XPLO_RTS_Ignore))
942  {
943  bool set = !!(pLinesOpts & XPLO_RTS_Set);
944  bool clr = !!(pLinesOpts & XPLO_RTS_Clear);
945  if (set != clr)
946  {
947  // Only one between Set and Clear is high
948  if (set)
949  {
950  if (!EscapeCommFunction(m_handle, SETRTS)) // Set RTS
951  p = XRV_ERROR;
952  }
953  else
954  {
955  // XPLO_RTS_Clear is Set
956  assert(pLinesOpts & XPLO_RTS_Clear);
957 
958  if (!EscapeCommFunction(m_handle, CLRRTS)) // Clear RTS
959  p = XRV_ERROR;
960  }
961  }
962  }
963  }
964 
965 #else
966 
967  // DTR Line
968  if (!(options & PO_DtrDsrFlowControl))
969  {
970  // Flow control is disabled
971  if ((pLinesOpts != XPLO_Invalid) && !(pLinesOpts & XPLO_DTR_Ignore))
972  {
973  if (((pLinesOpts & (XPLO_DTR_Set | XPLO_DTR_Clear)) == (XPLO_DTR_Set | XPLO_DTR_Clear))
974  || ((pLinesOpts & (XPLO_DTR_Set | XPLO_DTR_Clear)) == 0))
975  {
976  // Line options are not valid, both Set and Clear are high or down
977  p = setBitsEnabled(p, TIOCM_DTR, true); // Default behaviour
978  }
979  else
980  p = setBitsEnabled(p, TIOCM_DTR, (pLinesOpts & XPLO_DTR_Set));
981  }
982  else
983  p = setBitsEnabled(p, TIOCM_DTR, true); // Default behaviour
984  }
985 
986  // RTS Line
987  if (!(options & PO_RtsCtsFlowControl))
988  {
989  if ((pLinesOpts != XPLO_Invalid) && !(pLinesOpts & XPLO_RTS_Ignore))
990  {
991  if (((pLinesOpts & (XPLO_RTS_Set | XPLO_RTS_Clear)) == (XPLO_RTS_Set | XPLO_RTS_Clear))
992  || ((pLinesOpts & (XPLO_RTS_Set | XPLO_RTS_Clear)) == 0))
993  {
994  // Line options are not valid, both Set and Clear are high or down
995  p = setBitsEnabled(p, TIOCM_RTS, true); // Default behaviour
996  }
997  else
998  p = setBitsEnabled(p, TIOCM_RTS, (pLinesOpts & XPLO_RTS_Set));
999  }
1000  else
1001  p = setBitsEnabled(p, TIOCM_RTS, true); // Default behaviour
1002  }
1003 
1004 #endif
1005 }
XRV_NOPORTOPEN
@ XRV_NOPORTOPEN
288: No serial port opened for reading/writing
Definition: xsresultvalue.h:159
XsIoHandle
int32_t XsIoHandle
The type that is used for low-level identification of an open I/O device.
Definition: xsfilepos.h:104
XsString
struct XsString XsString
Definition: xsstring.h:87
operator|
SerialInterface::PortOptions operator|(SerialInterface::PortOptions lhs, SerialInterface::PortOptions rhs)
Logical or operator for flow controls.
Definition: serialinterface.cpp:873
SerialInterface::getPortName
void getPortName(XsString &portname) const
Retrieve the port name that was last successfully opened.
Definition: serialinterface.cpp:293
IoInterface::PO_TwoStopBits
@ PO_TwoStopBits
Definition: iointerface.h:137
SerialInterface::getPortNumber
uint16_t getPortNumber(void) const
Retrieve the port number that was last successfully opened.
Definition: serialinterface.cpp:287
SerialInterface::m_port
uint16_t m_port
The opened COM port nr.
Definition: serialinterface.h:98
XsByteArray
A list of uint8_t values.
IoInterface::PO_RtsCtsFlowControl
@ PO_RtsCtsFlowControl
Definition: iointerface.h:133
SerialInterface::setTimeout
XsResultValue setTimeout(uint32_t ms)
Set the default timeout value to use in blocking operations.
Definition: serialinterface.cpp:697
operator~
SerialInterface::PortOptions operator~(SerialInterface::PortOptions lhs)
Logical inversion operator for flow controls.
Definition: serialinterface.cpp:885
XPLO_DTR_Clear
@ XPLO_DTR_Clear
Definition: xsportinfo.h:118
io.h
SerialInterface::close
XsResultValue close(void) override
Close the serial communication port.
Definition: serialinterface.cpp:128
XRV_TIMEOUT
@ XRV_TIMEOUT
258: A timeout occurred
Definition: xsresultvalue.h:128
operator&
SerialInterface::PortOptions operator&(SerialInterface::PortOptions lhs, SerialInterface::PortOptions rhs)
Logical and operator for flow controls.
Definition: serialinterface.cpp:879
XsControlLine
XsControlLine
Serial control lines.
Definition: xscontrolline.h:72
SerialInterface::m_endTime
uint32_t m_endTime
The time at which an operation will end in ms, used by several functions.
Definition: serialinterface.h:94
JLALERTG
#define JLALERTG(msg)
Definition: journaller.h:281
XCL_RTS
@ XCL_RTS
pin 7: Request To Send
Definition: xscontrolline.h:80
XRV_ALREADYOPEN
@ XRV_ALREADYOPEN
269: An I/O device is already opened with this object
Definition: xsresultvalue.h:139
SerialInterface::m_baudrate
XsBaudRate m_baudrate
The baudrate that was last set to be used by the port.
Definition: serialinterface.h:92
xsportinfo.h
XRV_ERROR
@ XRV_ERROR
256: A generic error occurred
Definition: xsresultvalue.h:126
SerialInterface::getLastResult
XsResultValue getLastResult(void) const
Return the error code of the last operation.
Definition: serialinterface.cpp:299
SerialInterface::readData
XsResultValue readData(XsFilePos maxLength, XsByteArray &data) override
Read data from the serial port and put it into the data buffer.
Definition: serialinterface.cpp:573
setBitsEnabled
static T setBitsEnabled(T field, T bits, bool cond)
Definition: serialinterface.cpp:322
data
data
IoInterface::PortOptions
PortOptions
Options for flow control and stopbits which must be used when opening a port.
Definition: iointerface.h:130
XRV_OK
@ XRV_OK
0: Operation was performed successfully
Definition: xsresultvalue.h:85
XsResultValue
XsResultValue
Xsens result values.
Definition: xsresultvalue.h:82
XsTime_getTimeOfDay
uint32_t XsTime_getTimeOfDay(struct tm *date_, time_t *secs_)
The function returns the current time of day in ms since midnight.
Definition: xstime.c:134
SerialInterface::m_lastResult
XsResultValue m_lastResult
The last result of an operation.
Definition: serialinterface.h:96
XRV_UNEXPECTED_DISCONNECT
@ XRV_UNEXPECTED_DISCONNECT
312: Motion tracker disconnected unexpectedly
Definition: xsresultvalue.h:187
SerialInterface::closeLive
XsResultValue closeLive(void)
Close the serial communication port.
Definition: serialinterface.cpp:134
XsBaudRate
enum XsBaudRate XsBaudRate
Communication speed.
Definition: xsbaud.h:81
XRV_NOFILEORPORTOPEN
@ XRV_NOFILEORPORTOPEN
289: No file or serial port opened for reading/writing
Definition: xsresultvalue.h:160
XPLO_RTS_Ignore
@ XPLO_RTS_Ignore
Definition: xsportinfo.h:115
uint32_t
unsigned int uint32_t
Definition: pstdint.h:485
SerialInterface::~SerialInterface
virtual ~SerialInterface()
Destructor, de-initializes, frees memory allocated for buffers, etc.
Definition: serialinterface.cpp:116
XsPortInfo
Contains a descriptor for opening a communication port to an Xsens device.
Definition: xsportinfo.h:128
SerialInterface::getBaudrate
XsBaudRate getBaudrate(void) const
Return the baudrate that is currently being used by the port.
Definition: serialinterface.cpp:273
XsPortLinesOptions
XsPortLinesOptions
Definition: xsportinfo.h:109
SerialInterface::applyHwControlLinesOptions
void applyHwControlLinesOptions(PortOptions options, int portLinesOptions, int &p)
Apply the specified options for the hardware control lines.
Definition: serialinterface.cpp:895
JLTRACEG
#define JLTRACEG(msg)
Definition: journaller.h:279
XsSize
size_t XsSize
XsSize must be unsigned number!
Definition: xstypedefs.h:74
serialinterface.h
SerialInterface::tx_log
XsFile tx_log
Definition: serialinterface.h:89
XRV_INPUTCANNOTBEOPENED
@ XRV_INPUTCANNOTBEOPENED
267: The specified i/o device can not be opened
Definition: xsresultvalue.h:137
xscontrolline.h
SerialInterface::open
XsResultValue open(const XsPortInfo &portInfo, XsFilePos readBufSize=XS_DEFAULT_READ_BUFFER_SIZE, XsFilePos writeBufSize=XS_DEFAULT_WRITE_BUFFER_SIZE, PortOptions options=PO_XsensDefaults) override
Open a communication channel to the given port info.
Definition: serialinterface.cpp:342
SerialInterface::flushData
XsResultValue flushData(void) override
Flush all data in the buffers to and from the device.
Definition: serialinterface.cpp:258
XPLO_DTR_Set
@ XPLO_DTR_Set
Definition: xsportinfo.h:117
set
ROSCPP_DECL void set(const std::string &key, bool b)
SerialInterface::getHandle
XsIoHandle getHandle(void) const
Return the handle of the port.
Definition: serialinterface.cpp:281
SerialInterface::SerialInterface
SerialInterface()
Default constructor, initializes all members to their default values.
Definition: serialinterface.cpp:99
SerialInterface::escape
XsResultValue escape(XsControlLine mask, XsControlLine state)
Manipulate the Serial control lines.
Definition: serialinterface.cpp:193
SerialInterface::cancelIo
void cancelIo(void) const
Cancel any pending io requests.
Definition: serialinterface.cpp:862
CHECK_COMMSTATE
#define CHECK_COMMSTATE(req, res, field)
IoInterface::PO_DtrDsrFlowControl
@ PO_DtrDsrFlowControl
Definition: iointerface.h:134
SerialInterface::isOpen
bool isOpen(void) const
Return whether the communication port is open or not.
Definition: serialinterface.cpp:311
BOOL
int BOOL
Definition: xstypedefs.h:141
JLHEXLOG
#define JLHEXLOG(d)
Definition: journaller.h:335
SerialInterface::writeData
XsResultValue writeData(const XsByteArray &data, XsFilePos *written=0) override
Write the data contained in data to the device.
Definition: serialinterface.cpp:782
XPLO_RtsCtsFlowControl
@ XPLO_RtsCtsFlowControl
Definition: xsportinfo.h:125
JLDEBUGG
#define JLDEBUGG(msg)
Definition: journaller.h:280
SerialInterface::waitForData
XsResultValue waitForData(XsFilePos maxLength, XsByteArray &data) override
Wait for data to arrive or a timeout to occur.
Definition: serialinterface.cpp:751
SerialInterface::m_timeout
uint32_t m_timeout
Definition: serialinterface.h:104
XPLO_Invalid
@ XPLO_Invalid
Definition: xsportinfo.h:111
int32_t
signed int int32_t
Definition: pstdint.h:515
XPLO_RTS_Clear
@ XPLO_RTS_Clear
Definition: xsportinfo.h:114
length
TF2SIMD_FORCE_INLINE tf2Scalar length(const Quaternion &q)
rx_tx_log.h
XPLO_RTS_Set
@ XPLO_RTS_Set
Definition: xsportinfo.h:113
SerialInterface::getTimeout
uint32_t getTimeout(void) const
Return the current timeout value.
Definition: serialinterface.cpp:305
SerialInterface::rx_log
XsFile rx_log
Definition: serialinterface.h:88
SerialInterface::m_commState
termios m_commState
Stored settings about the serial port.
Definition: serialinterface.h:109
XBR_Invalid
XBR_Invalid
Not a valid baud rate.
Definition: xsbaudrate.h:126
SerialInterface::m_handle
int32_t m_handle
The serial port handle, also indicates if the port is open or not.
Definition: serialinterface.h:110
XsFilePos
int64_t XsFilePos
The type that is used for positioning inside a file.
Definition: xsfilepos.h:102
XsString
A 0-terminated managed string of characters.
XCL_DTR
@ XCL_DTR
pin 4: Data Terminal Ready
Definition: xscontrolline.h:77
SerialInterface::m_portname
char m_portname[32]
The name of the open serial port.
Definition: serialinterface.h:100
IoInterface::PO_XonXoffFlowControl
@ PO_XonXoffFlowControl
Definition: iointerface.h:135
XS_MAX_FILENAME_LENGTH
#define XS_MAX_FILENAME_LENGTH
Definition: xsfile.h:78
XPLO_DTR_Ignore
@ XPLO_DTR_Ignore
Definition: xsportinfo.h:119


xsens_mti_driver
Author(s):
autogenerated on Sun Sep 3 2023 02:43:20