serialPortPlatform.c
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright (c) 2014-2021 Inertial Sense, Inc. - http://inertialsense.com
5 
6 Permission is hereby granted, free of charge, to any person obtaining a copy of this software and associated documentation files(the "Software"), to deal in the Software without restriction, including without limitation the rights to use, copy, modify, merge, publish, distribute, sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is furnished to do so, subject to the following conditions :
7 
8 The above copyright notice and this permission notice shall be included in all copies or substantial portions of the Software.
9 
10 THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT.IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE.
11 */
12 
13 #include "serialPort.h"
14 #include "serialPortPlatform.h"
15 #include "ISConstants.h"
16 
17 #if PLATFORM_IS_LINUX || PLATFORM_IS_APPLE
18 
19 #include <stdio.h>
20 #include <stdlib.h>
21 #include <fcntl.h>
22 #include <sys/ioctl.h>
23 #include <sys/types.h>
24 #include <sys/time.h>
25 #include <sys/stat.h>
26 #include <sys/statvfs.h>
27 #include <errno.h>
28 #include <termios.h>
29 #include <unistd.h>
30 #include <poll.h>
31 
32 // cygwin defines FIONREAD in socket.h instead of ioctl.h
33 #ifndef FIONREAD
34 #include <sys/socket.h>
35 #endif
36 
37 #if PLATFORM_IS_APPLE
38 
39 #include <CoreFoundation/CoreFoundation.h>
40 #include <IOKit/IOKitLib.h>
41 #include <IOKit/serial/IOSerialKeys.h>
42 #include <IOKit/serial/ioss.h>
43 #include <IOKit/IOBSD.h>
44 
45 #endif
46 
47 #ifndef error_message
48 #define error_message printf
49 #endif
50 
51 #ifndef B460800
52 #define B460800 460800
53 #endif
54 #ifndef B921600
55 #define B921600 921600
56 #endif
57 #ifndef B1500000
58 #define B1500000 1500000
59 #endif
60 #ifndef B2000000
61 #define B2000000 2000000
62 #endif
63 #ifndef B2500000
64 #define B2500000 2500000
65 #endif
66 #ifndef B3000000
67 #define B3000000 3000000
68 #endif
69 
70 #endif
71 
72 typedef struct
73 {
74  int blocking;
75 
76 #if PLATFORM_IS_WINDOWS
77 
78  void* platformHandle;
79  OVERLAPPED ovRead;
80  OVERLAPPED ovWrite;
81 
82 #else
83 
84  int fd;
85 
86 #endif
87 
89 
90 #if PLATFORM_IS_WINDOWS
91 
92 #define WINDOWS_OVERLAPPED_BUFFER_SIZE 8192
93 
94 typedef struct
95 {
96  OVERLAPPED ov;
97  pfnSerialPortAsyncReadCompletion externalCompletion;
98  serial_port_t* serialPort;
99  unsigned char* buffer;
100 } readFileExCompletionStruct;
101 
102 static void CALLBACK readFileExCompletion(DWORD errorCode, DWORD bytesTransferred, LPOVERLAPPED ov)
103 {
104  readFileExCompletionStruct* c = (readFileExCompletionStruct*)ov;
105  c->externalCompletion(c->serialPort, c->buffer, bytesTransferred, errorCode);
106  free(c);
107 }
108 
109 #else
110 
111 static int get_baud_speed(int baudRate)
112 {
113  switch (baudRate)
114  {
115  default: return 0;
116  case 300: return B300;
117  case 600: return B600;
118  case 1200: return B1200;
119  case 2400: return B2400;
120  case 4800: return B4800;
121  case 9600: return B9600;
122  case 19200: return B19200;
123  case 38400: return B38400;
124  case 57600: return B57600;
125  case 115200: return B115200;
126  case 230400: return B230400;
127  case 460800: return B460800;
128  case 921600: return B921600;
129  case 1500000: return B1500000;
130  case 2000000: return B2000000;
131  case 2500000: return B2500000;
132  case 3000000: return B3000000;
133  }
134 }
135 
136 static int set_interface_attribs(int fd, int speed, int parity)
137 {
138  struct termios tty;
139  memset(&tty, 0, sizeof tty);
140  if (tcgetattr(fd, &tty) != 0)
141  {
142  error_message("error %d from tcgetattr", errno);
143  return -1;
144  }
145 
146 #if PLATFORM_IS_APPLE
147 
148  // set a valid speed for MAC, serial won't open otherwise
149  cfsetospeed(&tty, 230400);
150  cfsetispeed(&tty, 230400);
151 
152  // HACK: Set the actual speed, allows higher than 230400 baud
153  if (ioctl(fd, IOSSIOSPEED, &speed) == -1)
154  {
155  error_message("error %d from ioctl IOSSIOSPEED", errno);
156  }
157 
158 #else
159 
160  speed = get_baud_speed(speed);
161  cfsetospeed(&tty, speed);
162  cfsetispeed(&tty, speed);
163 
164 #endif
165 
166  tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8; // 8-bit chars
167  // disable IGNBRK for mismatched speed tests; otherwise receive break
168  // as \000 chars
169  tty.c_iflag &= ~IGNBRK; // disable break processing
170  tty.c_lflag = 0; // no signaling chars, no echo,
171  // no canonical processing
172  tty.c_oflag = 0; // no remapping, no delays
173  tty.c_cc[VMIN] = 0; // read doesn't block
174  tty.c_cc[VTIME] = 0; // no timeout
175 
176  tty.c_iflag &= ~(IXON | IXOFF | IXANY); // shut off xon/xoff ctrl
177 
178  tty.c_cflag |= (CLOCAL | CREAD);// ignore modem controls,
179  // enable reading
180  tty.c_cflag &= ~(PARENB | PARODD); // shut off parity
181  tty.c_cflag |= parity;
182  tty.c_cflag &= ~CSTOPB;
183  tty.c_cflag &= ~CRTSCTS;
184 
185  if (tcsetattr(fd, TCSANOW, &tty) != 0)
186  {
187  error_message("error %d from tcsetattr", errno);
188  return -1;
189  }
190 
191  // re-open and remove additional flags
192  memset(&tty, 0, sizeof(tty));
193 
194  // Check if the file descriptor is pointing to a TTY device or not.
195  if (!isatty(fd))
196  {
197  return -1;
198  }
199 
200  // Get the current configuration of the serial interface
201  if (tcgetattr(fd, &tty) < 0)
202  {
203  return -1;
204  }
205 
206  // Input flags - Turn off input processing
207  //
208  // convert break to null byte, no CR to NL translation,
209  // no NL to CR translation, don't mark parity errors or breaks
210  // no input parity check, don't strip high bit off,
211  // no XON/XOFF software flow control
212  //
213  // config.c_iflag &= ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON);
214  tty.c_iflag = 0;
215 
216  // Output flags - Turn off output processing
217  //
218  // no CR to NL translation, no NL to CR-NL translation,
219  // no NL to CR translation, no column 0 CR suppression,
220  // no Ctrl-D suppression, no fill characters, no case mapping,
221  // no local output processing
222  //
223  // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
224  // config.c_oflag &= ~(OCRNL | ONLCR | ONLRET | ONOCR | ONOEOT| OFILL | OLCUC | OPOST);
225  tty.c_oflag = 0;
226 
227  // No line processing
228  //
229  // echo off, echo newline off, canonical mode off,
230  // extended input processing off, signal chars off
231  //
232  // config.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
233  tty.c_lflag = 0;
234 
235  // Turn off character processing
236  //
237  // clear current char size mask, no parity checking,
238  // no output processing, force 8 bit input
239  tty.c_cflag &= ~(CSIZE | PARENB);
240  tty.c_cflag |= CS8;
241 
242  // One input byte is enough to return from read()
243  // Inter-character timer off
244  tty.c_cc[VMIN] = 1;
245  tty.c_cc[VTIME] = 0;
246 
247  // Communication speed (simple version, using the predefined
248  // constants)
249  //
250  // if(cfsetispeed(&config, B9600) < 0 || cfsetospeed(&config, B9600) < 0)
251  // return 0;
252 
253  // Finally, apply the configuration
254  if (tcsetattr(fd, TCSAFLUSH, &tty) < 0)
255  {
256  return -1;
257  }
258 
259  return 0;
260 }
261 
262 #endif
263 
264 static int serialPortOpenPlatform(serial_port_t* serialPort, const char* port, int baudRate, int blocking)
265 {
266  if (serialPort->handle != 0)
267  {
268  // already open
269  return 0;
270  }
271 
272  serialPortSetPort(serialPort, port);
273 
274 #if PLATFORM_IS_WINDOWS
275 
276  void* platformHandle = 0;
277  platformHandle = CreateFileA(serialPort->port, GENERIC_READ | GENERIC_WRITE, 0, 0, OPEN_EXISTING, blocking ? FILE_FLAG_OVERLAPPED : 0, 0);
278  if (platformHandle == INVALID_HANDLE_VALUE)
279  {
280  // don't modify the originally requested port value, just create a new value that Windows needs for COM10 and above
281  char tmpPort[MAX_SERIAL_PORT_NAME_LENGTH];
282  sprintf_s(tmpPort, sizeof(tmpPort), "\\\\.\\%s", port);
283  platformHandle = CreateFileA(tmpPort, GENERIC_READ | GENERIC_WRITE, 0, 0, OPEN_EXISTING, blocking ? FILE_FLAG_OVERLAPPED : 0, 0);
284  if (platformHandle == INVALID_HANDLE_VALUE)
285  {
286  return 0;
287  }
288  }
289 
290  DCB serialParams;
291  serialParams.DCBlength = sizeof(DCB);
292  if (GetCommState(platformHandle, &serialParams))
293  {
294  serialParams.BaudRate = baudRate;
295  serialParams.ByteSize = DATABITS_8;
296  serialParams.StopBits = ONESTOPBIT;
297  serialParams.Parity = NOPARITY;
298  serialParams.fBinary = 1;
299  serialParams.fInX = 0;
300  serialParams.fOutX = 0;
301  serialParams.fAbortOnError = 0;
302  serialParams.fNull = 0;
303  serialParams.fErrorChar = 0;
304  serialParams.fDtrControl = DTR_CONTROL_ENABLE;
305  serialParams.fRtsControl = RTS_CONTROL_ENABLE;
306  if (!SetCommState(platformHandle, &serialParams))
307  {
308  serialPortClose(serialPort);
309  return 0;
310  }
311  }
312  else
313  {
314  serialPortClose(serialPort);
315  return 0;
316  }
317  COMMTIMEOUTS timeouts = { (blocking ? 1 : MAXDWORD), (blocking ? 1 : 0), (blocking ? 1 : 0), 0, 0 };
318  if (!SetCommTimeouts(platformHandle, &timeouts))
319  {
320  serialPortClose(serialPort);
321  return 0;
322  }
324  handle->blocking = blocking;
325  handle->platformHandle = platformHandle;
326  if (blocking)
327  {
328  handle->ovRead.hEvent = CreateEvent(0, 1, 0, 0);
329  handle->ovWrite.hEvent = CreateEvent(0, 1, 0, 0);
330  }
331  serialPort->handle = handle;
332 
333 #else
334 
335  int fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
336  if (fd < 0 || set_interface_attribs(fd, baudRate, 0) != 0)
337  {
338  return 0;
339  }
341  handle->fd = fd;
342  handle->blocking = blocking;
343  serialPort->handle = handle;
344 
345 #endif
346 
347  return 1; // success
348 }
349 
351 {
352 
353 #if PLATFORM_IS_WINDOWS
354 
355  DCB serialParams;
356  serialParams.DCBlength = sizeof(DCB);
357  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
358  return GetCommState(handle->platformHandle, &serialParams);
359 
360 #else
361 
362  struct stat sb;
363  return (stat(serialPort->port, &sb) == 0);
364 
365 #endif
366 
367 }
368 
369 static int serialPortClosePlatform(serial_port_t* serialPort)
370 {
371  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
372  if (handle == 0)
373  {
374  // not open, no close needed
375  return 0;
376  }
377 
378 #if PLATFORM_IS_WINDOWS
379 
380  CancelIo(handle->platformHandle);
381  if (handle->blocking)
382  {
383  CloseHandle(handle->ovRead.hEvent);
384  CloseHandle(handle->ovWrite.hEvent);
385  }
386  CloseHandle(handle->platformHandle);
387  handle->platformHandle = 0;
388 
389 #else
390 
391  close(handle->fd);
392  handle->fd = 0;
393 
394 #endif
395 
396  free(handle);
397  serialPort->handle = 0;
398 
399  return 1;
400 }
401 
402 static int serialPortFlushPlatform(serial_port_t* serialPort)
403 {
404  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
405 
406 #if PLATFORM_IS_WINDOWS
407 
408  if (!PurgeComm(handle->platformHandle, PURGE_RXABORT | PURGE_RXCLEAR | PURGE_TXABORT | PURGE_TXCLEAR))
409  {
410  return 0;
411  }
412 
413 #else
414 
415  tcflush(handle->fd, TCIOFLUSH);
416 
417 #endif
418 
419  return 1;
420 }
421 
422 #if PLATFORM_IS_WINDOWS
423 
424 static int serialPortReadTimeoutPlatformWindows(serialPortHandle* handle, unsigned char* buffer, int readCount, int timeoutMilliseconds)
425 {
426  if (readCount < 1)
427  {
428  return 0;
429  }
430 
431  DWORD dwRead = 0;
432  int totalRead = 0;
433  ULONGLONG startTime = GetTickCount64();
434  do
435  {
436  if (ReadFile(handle->platformHandle, buffer + totalRead, readCount - totalRead, &dwRead, handle->blocking ? &handle->ovRead : 0))
437  {
438  if (handle->blocking)
439  {
440  GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 1);
441  }
442  totalRead += dwRead;
443  }
444  else if (handle->blocking)
445  {
446  DWORD dwRes = GetLastError();
447  if (dwRes == ERROR_IO_PENDING)
448  {
449  dwRes = WaitForSingleObject(handle->ovRead.hEvent, _MAX(1, timeoutMilliseconds - (int)(GetTickCount64() - startTime)));
450  switch (dwRes)
451  {
452  case WAIT_OBJECT_0:
453  if (!GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 0))
454  {
455  CancelIo(handle->platformHandle);
456  }
457  else
458  {
459  totalRead += dwRead;
460  }
461  break;
462 
463  default:
464  // cancel io and just take whatever was in the buffer
465  CancelIo(handle->platformHandle);
466  GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 1);
467  totalRead += dwRead;
468  break;
469  }
470  }
471  else
472  {
473  CancelIo(handle->platformHandle);
474  }
475  }
476 // #if _DEBUG
477 // else
478 // {
479 // DWORD dRes = GetLastError();
480 // int a = 5; a++;
481 // }
482 // #endif
483  if (!handle->blocking && totalRead < readCount && timeoutMilliseconds > 0)
484  {
485  Sleep(1);
486  }
487  }
488  while (totalRead < readCount && GetTickCount64() - startTime < timeoutMilliseconds);
489  return totalRead;
490 }
491 
492 #else
493 
494 static int serialPortReadTimeoutPlatformLinux(serialPortHandle* handle, unsigned char* buffer, int readCount, int timeoutMilliseconds)
495 {
496  int totalRead = 0;
497  int dtMs;
498  int n;
499  struct timeval start, curr;
500  if (timeoutMilliseconds > 0)
501  {
502  gettimeofday(&start, NULL);
503  }
504 
505  while (1)
506  {
507  if (timeoutMilliseconds > 0)
508  {
509  struct pollfd fds[1];
510  fds[0].fd = handle->fd;
511  fds[0].events = POLLIN;
512  int pollrc = poll(fds, 1, timeoutMilliseconds);
513  if (pollrc <= 0 || !(fds[0].revents & POLLIN))
514  {
515  break;
516  }
517  }
518  n = read(handle->fd, buffer + totalRead, readCount - totalRead);
519  if (n < -1)
520  {
521  error_message("error %d from read, fd %d", errno, handle->fd);
522  return 0;
523  }
524  else if (n != -1)
525  {
526  totalRead += n;
527  }
528  if (timeoutMilliseconds > 0 && totalRead < readCount)
529  {
530  gettimeofday(&curr, NULL);
531  dtMs = ((curr.tv_sec - start.tv_sec) * 1000) + ((curr.tv_usec - start.tv_usec) / 1000);
532  if (dtMs >= timeoutMilliseconds)
533  {
534  break;
535  }
536 
537  // try for another loop around with a lower timeout
538  timeoutMilliseconds = _MAX(0, timeoutMilliseconds - dtMs);
539  }
540  else
541  {
542  break;
543  }
544  }
545  return totalRead;
546 }
547 
548 #endif
549 
550 static int serialPortReadTimeoutPlatform(serial_port_t* serialPort, unsigned char* buffer, int readCount, int timeoutMilliseconds)
551 {
552  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
553  if (timeoutMilliseconds < 0)
554  {
555  timeoutMilliseconds = (handle->blocking ? SERIAL_PORT_DEFAULT_TIMEOUT : 0);
556  }
557 
558 #if PLATFORM_IS_WINDOWS
559 
560  return serialPortReadTimeoutPlatformWindows(handle, buffer, readCount, timeoutMilliseconds);
561 
562 #else
563 
564  return serialPortReadTimeoutPlatformLinux(handle, buffer, readCount, timeoutMilliseconds);
565 
566 #endif
567 
568 }
569 
570 static int serialPortAsyncReadPlatform(serial_port_t* serialPort, unsigned char* buffer, int readCount, pfnSerialPortAsyncReadCompletion completion)
571 {
572  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
573 
574 #if PLATFORM_IS_WINDOWS
575 
576  readFileExCompletionStruct c;
577  c.externalCompletion = completion;
578  c.serialPort = serialPort;
579  c.buffer = buffer;
580  memset(&(c.ov), 0, sizeof(c.ov));
581 
582  if (!ReadFileEx(handle->platformHandle, buffer, readCount, (LPOVERLAPPED)&c, readFileExCompletion))
583  {
584  return 0;
585  }
586 
587 #else
588 
589  // no support for async, just call the completion right away
590  int n = read(handle->fd, buffer, readCount);
591  completion(serialPort, buffer, (n < 0 ? 0 : n), (n >= 0 ? 0 : n));
592 
593 #endif
594 
595  return 1;
596 }
597 
598 static int serialPortWritePlatform(serial_port_t* serialPort, const unsigned char* buffer, int writeCount)
599 {
600  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
601 
602 #if PLATFORM_IS_WINDOWS
603 
604  DWORD dwWritten;
605  if (!WriteFile(handle->platformHandle, buffer, writeCount, &dwWritten, handle->blocking ? &handle->ovWrite : 0))
606  {
607  DWORD result = GetLastError();
608  if (result != ERROR_IO_PENDING)
609  {
610  CancelIo(handle->platformHandle);
611  return 0;
612  }
613  }
614 
615  if (handle->blocking)
616  {
617  if (!GetOverlappedResult(handle->platformHandle, &handle->ovWrite, &dwWritten, 1))
618  {
619  CancelIo(handle->platformHandle);
620  return 0;
621  }
622  }
623  return dwWritten;
624 
625 
626 #else
627 
628  return write(handle->fd, buffer, writeCount);
629 
630  // if desired in the future, this will block until the data has been successfully written to the serial port
631  /*
632  int count = write(handle->fd, buffer, writeCount);
633  int error = tcdrain(handle->fd);
634 
635  if (error != 0)
636  {
637  error_message("error %d from tcdrain", errno);
638  return 0;
639  }
640 
641  return count;
642  */
643 
644  if (serialPort->pfnWrite)
645  {
646  return serialPort->pfnWrite(serialPort, buffer, writeCount);
647  }
648  return 0;
649 
650 #endif
651 
652 }
653 
655 {
656  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
657 
658 
659 #if PLATFORM_IS_WINDOWS
660 
661  COMSTAT commStat;
662  if (ClearCommError(handle->platformHandle, 0, &commStat))
663  {
664  return commStat.cbInQue;
665  }
666  return 0;
667 
668 #else
669 
670  int bytesAvailable;
671  ioctl(handle->fd, FIONREAD, &bytesAvailable);
672  return bytesAvailable;
673 
674 #endif
675 
676 }
677 
679 {
680  // serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
681  (void)serialPort;
682 
683  return 65536;
684 
685  /*
686  int bytesUsed;
687  struct serial_struct serinfo;
688  memset(&serinfo, 0, sizeof(serial_struct));
689  ioctl(handle->fd, TIOCGSERIAL, &serinfo);
690  ioctl(handle->fd, TIOCOUTQ, &bytesUsed);
691  return serinfo.xmit_fifo_size - bytesUsed;
692  */
693 }
694 
695 static int serialPortSleepPlatform(int sleepMilliseconds)
696 {
697 #if PLATFORM_IS_WINDOWS
698 
699  Sleep(sleepMilliseconds);
700 
701 #else
702 
703  usleep(sleepMilliseconds * 1000);
704 
705 #endif
706 
707  return 1;
708 }
709 
711 {
712  // very important - the serial port must be initialized to zeros
713  memset(serialPort, 0, sizeof(serial_port_t));
714 
715  serialPort->pfnClose = serialPortClosePlatform;
716  serialPort->pfnFlush = serialPortFlushPlatform;
717  serialPort->pfnOpen = serialPortOpenPlatform;
718  serialPort->pfnIsOpen = serialPortIsOpenPlatform;
721  serialPort->pfnWrite = serialPortWritePlatform;
724  serialPort->pfnSleep = serialPortSleepPlatform;
725  return 0;
726 }
pfnSerialPortIsOpen pfnIsOpen
Definition: serialPort.h:82
pfnSerialPortAsyncRead pfnAsyncRead
Definition: serialPort.h:88
static int serialPortClosePlatform(serial_port_t *serialPort)
void(* pfnSerialPortAsyncReadCompletion)(serial_port_t *serialPort, unsigned char *buf, int len, int errorCode)
Definition: serialPort.h:54
if(udd_ctrl_interrupt())
Definition: usbhs_device.c:688
pfnSerialPortGetByteCountAvailableToWrite pfnGetByteCountAvailableToWrite
Definition: serialPort.h:103
void serialPortSetPort(serial_port_t *serialPort, const char *port)
Definition: serialPort.c:18
#define NULL
Definition: nm_bsp.h:52
int serialPortPlatformInit(serial_port_t *serialPort)
pfnSerialPortOpen pfnOpen
Definition: serialPort.h:79
pfnSerialPortRead pfnRead
Definition: serialPort.h:85
static int serialPortOpenPlatform(serial_port_t *serialPort, const char *port, int baudRate, int blocking)
static int serialPortFlushPlatform(serial_port_t *serialPort)
unsigned long DWORD
Definition: integer.h:33
pfnSerialPortFlush pfnFlush
Definition: serialPort.h:97
void free(void *ptr)
char port[MAX_SERIAL_PORT_NAME_LENGTH+1]
Definition: serialPort.h:70
#define MAX_SERIAL_PORT_NAME_LENGTH
Definition: serialPort.h:26
int SERIAL_PORT_DEFAULT_TIMEOUT
Definition: serialPort.c:16
int serialPortClose(serial_port_t *serialPort)
Definition: serialPort.c:66
static int serialPortIsOpenPlatform(serial_port_t *serialPort)
static int set_interface_attribs(int fd, int speed, int parity)
void * handle
Definition: serialPort.h:67
static int get_baud_speed(int baudRate)
pfnSerialPortSleep pfnSleep
Definition: serialPort.h:106
static int serialPortWritePlatform(serial_port_t *serialPort, const unsigned char *buffer, int writeCount)
#define _MAX(a, b)
Definition: ISConstants.h:294
static int serialPortGetByteCountAvailableToReadPlatform(serial_port_t *serialPort)
NMI_API sint8 close(SOCKET sock)
Definition: socket.c:879
pfnSerialPortClose pfnClose
Definition: serialPort.h:94
static int serialPortSleepPlatform(int sleepMilliseconds)
static int serialPortGetByteCountAvailableToWritePlatform(serial_port_t *serialPort)
pfnSerialPortGetByteCountAvailableToRead pfnGetByteCountAvailableToRead
Definition: serialPort.h:100
static int serialPortReadTimeoutPlatformLinux(serialPortHandle *handle, unsigned char *buffer, int readCount, int timeoutMilliseconds)
static int serialPortAsyncReadPlatform(serial_port_t *serialPort, unsigned char *buffer, int readCount, pfnSerialPortAsyncReadCompletion completion)
int errno
pfnSerialPortWrite pfnWrite
Definition: serialPort.h:91
void * calloc(size_t nitems, size_t size)
static int serialPortReadTimeoutPlatform(serial_port_t *serialPort, unsigned char *buffer, int readCount, int timeoutMilliseconds)


inertial_sense_ros
Author(s):
autogenerated on Sun Feb 28 2021 03:17:58