serial/serialPortPlatform.c
Go to the documentation of this file.
1 /*
2 MIT LICENSE
3 
4 Copyright 2014 Inertial Sense, LLC - 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 
318  DWORD timeout = (blocking ? 1 : 0);
319  COMMTIMEOUTS timeouts = { MAXDWORD, timeout, timeout, 0, 0 };
320  if (!SetCommTimeouts(platformHandle, &timeouts))
321  {
322  serialPortClose(serialPort);
323  return 0;
324  }
325 
327  handle->blocking = blocking;
328  handle->platformHandle = platformHandle;
329  if (blocking)
330  {
331  handle->ovRead.hEvent = CreateEvent(0, 1, 0, 0);
332  handle->ovWrite.hEvent = CreateEvent(0, 1, 0, 0);
333  }
334  serialPort->handle = handle;
335 
336 #else
337 
338  int fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
339  if (fd < 0 || set_interface_attribs(fd, baudRate, 0) != 0)
340  {
341  return 0;
342  }
344  handle->fd = fd;
345  handle->blocking = blocking;
346  serialPort->handle = handle;
347 
348 #endif
349 
350  return 1; // success
351 }
352 
354 {
355 
356 #if PLATFORM_IS_WINDOWS
357 
358  DCB serialParams;
359  serialParams.DCBlength = sizeof(DCB);
360  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
361  return GetCommState(handle->platformHandle, &serialParams);
362 
363 #else
364 
365  struct stat sb;
366  return (stat(serialPort->port, &sb) == 0);
367 
368 #endif
369 
370 }
371 
372 static int serialPortClosePlatform(serial_port_t* serialPort)
373 {
374  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
375  if (handle == 0)
376  {
377  // not open, no close needed
378  return 0;
379  }
380 
381 #if PLATFORM_IS_WINDOWS
382 
383  CancelIo(handle->platformHandle);
384  if (handle->blocking)
385  {
386  CloseHandle(handle->ovRead.hEvent);
387  CloseHandle(handle->ovWrite.hEvent);
388  }
389  CloseHandle(handle->platformHandle);
390  handle->platformHandle = 0;
391 
392 #else
393 
394  close(handle->fd);
395  handle->fd = 0;
396 
397 #endif
398 
399  free(handle);
400  serialPort->handle = 0;
401 
402  return 1;
403 }
404 
405 static int serialPortFlushPlatform(serial_port_t* serialPort)
406 {
407  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
408 
409 #if PLATFORM_IS_WINDOWS
410 
411  if (!PurgeComm(handle->platformHandle, PURGE_RXABORT | PURGE_RXCLEAR | PURGE_TXABORT | PURGE_TXCLEAR))
412  {
413  return 0;
414  }
415 
416 #else
417 
418  tcflush(handle->fd, TCIOFLUSH);
419 
420 #endif
421 
422  return 1;
423 }
424 
425 #if PLATFORM_IS_WINDOWS
426 
427 static int serialPortReadTimeoutPlatformWindows(serialPortHandle* handle, unsigned char* buffer, int readCount, int timeoutMilliseconds)
428 {
429  DWORD dwRead = 0;
430  int totalRead = 0;
431  ULONGLONG startTime = GetTickCount64();
432  while (totalRead < readCount && GetTickCount64() - startTime <= timeoutMilliseconds)
433  {
434  if (ReadFile(handle->platformHandle, buffer + totalRead, readCount - totalRead, &dwRead, handle->blocking ? &handle->ovRead : 0))
435  {
436  if (handle->blocking)
437  {
438  GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 1);
439  }
440  totalRead += dwRead;
441  }
442  else if (handle->blocking)
443  {
444  DWORD dwRes = GetLastError();
445  if (dwRes == ERROR_IO_PENDING)
446  {
447  dwRes = WaitForSingleObject(handle->ovRead.hEvent, timeoutMilliseconds);
448  switch (dwRes)
449  {
450  case WAIT_OBJECT_0:
451  if (!GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 0))
452  {
453  CancelIo(handle->platformHandle);
454  }
455  else
456  {
457  totalRead += dwRead;
458  }
459  break;
460 
461  default:
462  CancelIo(handle->platformHandle);
463  break;
464  }
465  }
466  else
467  {
468  CancelIo(handle->platformHandle);
469  }
470  }
471  if (!handle->blocking && totalRead == 0)
472  {
473  Sleep(2);
474  }
475  }
476  return totalRead;
477 }
478 
479 #else
480 
481 static int serialPortReadTimeoutPlatformLinux(serialPortHandle* handle, unsigned char* buffer, int readCount, int timeoutMilliseconds)
482 {
483  int totalRead = 0;
484  int dtMs;
485  int n;
486  struct timeval start, curr;
487  if (timeoutMilliseconds > 0)
488  {
489  gettimeofday(&start, NULL);
490  }
491 
492  while (1)
493  {
494  if (timeoutMilliseconds > 0)
495  {
496  struct pollfd fds[1];
497  fds[0].fd = handle->fd;
498  fds[0].events = POLLIN;
499  int pollrc = poll(fds, 1, timeoutMilliseconds);
500  if (pollrc <= 0 || !(fds[0].revents & POLLIN))
501  {
502  break;
503  }
504  }
505  n = read(handle->fd, buffer + totalRead, readCount - totalRead);
506  if (n < -1)
507  {
508  error_message("error %d from read, fd %d", errno, handle->fd);
509  return 0;
510  }
511  else if (n != -1)
512  {
513  totalRead += n;
514  }
515  if (timeoutMilliseconds > 0 && totalRead < readCount)
516  {
517  gettimeofday(&curr, NULL);
518  dtMs = ((curr.tv_sec - start.tv_sec) * 1000) + ((curr.tv_usec - start.tv_usec) / 1000);
519  if (dtMs >= timeoutMilliseconds)
520  {
521  break;
522  }
523 
524  // try for another loop around with a lower timeout
525  timeoutMilliseconds = _MAX(0, timeoutMilliseconds - dtMs);
526  }
527  else
528  {
529  break;
530  }
531  }
532  return totalRead;
533 }
534 
535 #endif
536 
537 static int serialPortReadTimeoutPlatform(serial_port_t* serialPort, unsigned char* buffer, int readCount, int timeoutMilliseconds)
538 {
539  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
540  if (timeoutMilliseconds < 0)
541  {
542  timeoutMilliseconds = (handle->blocking ? SERIAL_PORT_DEFAULT_TIMEOUT : 0);
543  }
544 
545 #if PLATFORM_IS_WINDOWS
546 
547  return serialPortReadTimeoutPlatformWindows(handle, buffer, readCount, timeoutMilliseconds);
548 
549 #else
550 
551  return serialPortReadTimeoutPlatformLinux(handle, buffer, readCount, timeoutMilliseconds);
552 
553 #endif
554 
555 }
556 
557 static int serialPortAsyncReadPlatform(serial_port_t* serialPort, unsigned char* buffer, int readCount, pfnSerialPortAsyncReadCompletion completion)
558 {
559  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
560 
561 #if PLATFORM_IS_WINDOWS
562 
563  readFileExCompletionStruct* c = (readFileExCompletionStruct*)malloc(sizeof(readFileExCompletionStruct));
564  c->externalCompletion = completion;
565  c->serialPort = serialPort;
566  c->buffer = buffer;
567  memset(&c->ov, 0, sizeof(c->ov));
568 
569  if (!ReadFileEx(handle->platformHandle, buffer, readCount, (LPOVERLAPPED)c, readFileExCompletion))
570  {
571  return 0;
572  }
573 
574 #else
575 
576  // no support for async, just call the completion right away
577  int n = read(handle->fd, buffer, readCount);
578  completion(serialPort, buffer, (n < 0 ? 0 : n), (n >= 0 ? 0 : n));
579 
580 #endif
581 
582  return 1;
583 }
584 
585 static int serialPortWritePlatform(serial_port_t* serialPort, const unsigned char* buffer, int writeCount)
586 {
587  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
588 
589 #if PLATFORM_IS_WINDOWS
590 
591  DWORD dwWritten;
592  if (!WriteFile(handle->platformHandle, buffer, writeCount, &dwWritten, handle->blocking ? &handle->ovWrite : 0))
593  {
594  DWORD result = GetLastError();
595  if (result != ERROR_IO_PENDING)
596  {
597  CancelIo(handle->platformHandle);
598  return 0;
599  }
600  }
601 
602  if (handle->blocking)
603  {
604  if (!GetOverlappedResult(handle->platformHandle, &handle->ovWrite, &dwWritten, 1))
605  {
606  CancelIo(handle->platformHandle);
607  return 0;
608  }
609  }
610  return dwWritten;
611 
612 
613 #else
614 
615  return write(handle->fd, buffer, writeCount);
616 
617  // if desired in the future, this will block until the data has been successfully written to the serial port
618  /*
619  int count = write(handle->fd, buffer, writeCount);
620  int error = tcdrain(handle->fd);
621 
622  if (error != 0)
623  {
624  error_message("error %d from tcdrain", errno);
625  return 0;
626  }
627 
628  return count;
629  */
630 
631 #endif
632 
633  if (serialPort->pfnWrite)
634  {
635  return serialPort->pfnWrite(serialPort, buffer, writeCount);
636  }
637 
638  return 0;
639 }
640 
642 {
643  serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
644 
645 
646 #if PLATFORM_IS_WINDOWS
647 
648  COMSTAT commStat;
649  if (ClearCommError(handle->platformHandle, 0, &commStat))
650  {
651  return commStat.cbInQue;
652  }
653  return 0;
654 
655 #else
656 
657  int bytesAvailable;
658  ioctl(handle->fd, FIONREAD, &bytesAvailable);
659  return bytesAvailable;
660 
661 #endif
662 
663 }
664 
666 {
667  // serialPortHandle* handle = (serialPortHandle*)serialPort->handle;
668  (void)serialPort;
669 
670  return 65536;
671 
672  /*
673  int bytesUsed;
674  struct serial_struct serinfo;
675  memset(&serinfo, 0, sizeof(serial_struct));
676  ioctl(handle->fd, TIOCGSERIAL, &serinfo);
677  ioctl(handle->fd, TIOCOUTQ, &bytesUsed);
678  return serinfo.xmit_fifo_size - bytesUsed;
679  */
680 }
681 
682 static int serialPortSleepPlatform(serial_port_t* serialPort, int sleepMilliseconds)
683 {
684  (void)serialPort;
685 
686 #if PLATFORM_IS_WINDOWS
687 
688  Sleep(sleepMilliseconds);
689 
690 #else
691 
692  usleep(sleepMilliseconds * 1000);
693 
694 #endif
695 
696  return 1;
697 }
698 
700 {
701  serialPort->pfnClose = serialPortClosePlatform;
702  serialPort->pfnFlush = serialPortFlushPlatform;
703  serialPort->pfnOpen = serialPortOpenPlatform;
704  serialPort->pfnIsOpen = serialPortIsOpenPlatform;
707  serialPort->pfnWrite = serialPortWritePlatform;
710  serialPort->pfnSleep = serialPortSleepPlatform;
711  return 0;
712 }
static int get_baud_speed(int baudRate)
char port[MAX_SERIAL_PORT_NAME_LENGTH+1]
static int serialPortAsyncReadPlatform(serial_port_t *serialPort, unsigned char *buffer, int readCount, pfnSerialPortAsyncReadCompletion completion)
pfnSerialPortAsyncRead pfnAsyncRead
static int serialPortReadTimeoutPlatformLinux(serialPortHandle *handle, unsigned char *buffer, int readCount, int timeoutMilliseconds)
static int set_interface_attribs(int fd, int speed, int parity)
#define MAX_SERIAL_PORT_NAME_LENGTH
if(udd_ctrl_interrupt())
Definition: usbhs_device.c:688
pfnSerialPortGetByteCountAvailableToWrite pfnGetByteCountAvailableToWrite
void serialPortSetPort(serial_port_t *serialPort, const char *port)
#define NULL
Definition: nm_bsp.h:52
void(* pfnSerialPortAsyncReadCompletion)(serial_port_t *serialPort, unsigned char *buf, int len, int errorCode)
static int serialPortWritePlatform(serial_port_t *serialPort, const unsigned char *buffer, int writeCount)
static int serialPortGetByteCountAvailableToReadPlatform(serial_port_t *serialPort)
unsigned long DWORD
Definition: integer.h:33
void free(void *ptr)
static int serialPortSleepPlatform(serial_port_t *serialPort, int sleepMilliseconds)
static int serialPortGetByteCountAvailableToWritePlatform(serial_port_t *serialPort)
static int serialPortIsOpenPlatform(serial_port_t *serialPort)
int serialPortClose(serial_port_t *serialPort)
#define _MAX(a, b)
Definition: ISConstants.h:294
void * malloc(size_t size)
NMI_API sint8 close(SOCKET sock)
Definition: socket.c:879
static int serialPortFlushPlatform(serial_port_t *serialPort)
pfnSerialPortGetByteCountAvailableToRead pfnGetByteCountAvailableToRead
static int serialPortReadTimeoutPlatform(serial_port_t *serialPort, unsigned char *buffer, int readCount, int timeoutMilliseconds)
int errno
static int serialPortOpenPlatform(serial_port_t *serialPort, const char *port, int baudRate, int blocking)
static int serialPortClosePlatform(serial_port_t *serialPort)
int serialPortPlatformInit(serial_port_t *serialPort)
void * calloc(size_t nitems, size_t size)


inertial_sense_ros
Author(s):
autogenerated on Sat Sep 19 2020 03:19:05