17 #if PLATFORM_IS_LINUX || PLATFORM_IS_APPLE 22 #include <sys/ioctl.h> 23 #include <sys/types.h> 26 #include <sys/statvfs.h> 34 #include <sys/socket.h> 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> 48 #define error_message printf 52 #define B460800 460800 55 #define B921600 921600 58 #define B1500000 1500000 61 #define B2000000 2000000 64 #define B2500000 2500000 67 #define B3000000 3000000 76 #if PLATFORM_IS_WINDOWS 90 #if PLATFORM_IS_WINDOWS 92 #define WINDOWS_OVERLAPPED_BUFFER_SIZE 8192 99 unsigned char* buffer;
100 } readFileExCompletionStruct;
102 static void CALLBACK readFileExCompletion(
DWORD errorCode,
DWORD bytesTransferred, LPOVERLAPPED ov)
104 readFileExCompletionStruct* c = (readFileExCompletionStruct*)ov;
105 c->externalCompletion(c->serialPort, c->buffer, bytesTransferred, errorCode);
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;
139 memset(&tty, 0,
sizeof tty);
140 if (tcgetattr(fd, &tty) != 0)
142 error_message(
"error %d from tcgetattr",
errno);
146 #if PLATFORM_IS_APPLE 149 cfsetospeed(&tty, 230400);
150 cfsetispeed(&tty, 230400);
153 if (ioctl(fd, IOSSIOSPEED, &speed) == -1)
155 error_message(
"error %d from ioctl IOSSIOSPEED",
errno);
161 cfsetospeed(&tty, speed);
162 cfsetispeed(&tty, speed);
166 tty.c_cflag = (tty.c_cflag & ~CSIZE) | CS8;
169 tty.c_iflag &= ~IGNBRK;
176 tty.c_iflag &= ~(IXON | IXOFF | IXANY);
178 tty.c_cflag |= (CLOCAL | CREAD);
180 tty.c_cflag &= ~(PARENB | PARODD);
181 tty.c_cflag |= parity;
182 tty.c_cflag &= ~CSTOPB;
183 tty.c_cflag &= ~CRTSCTS;
185 if (tcsetattr(fd, TCSANOW, &tty) != 0)
187 error_message(
"error %d from tcsetattr",
errno);
192 memset(&tty, 0,
sizeof(tty));
201 if (tcgetattr(fd, &tty) < 0)
239 tty.c_cflag &= ~(CSIZE | PARENB);
254 if (tcsetattr(fd, TCSAFLUSH, &tty) < 0)
266 if (serialPort->
handle != 0)
274 #if PLATFORM_IS_WINDOWS 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)
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)
291 serialParams.DCBlength =
sizeof(DCB);
292 if (GetCommState(platformHandle, &serialParams))
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))
318 DWORD timeout = (blocking ? 1 : 0);
319 COMMTIMEOUTS timeouts = { MAXDWORD, timeout, timeout, 0, 0 };
320 if (!SetCommTimeouts(platformHandle, &timeouts))
328 handle->platformHandle = platformHandle;
331 handle->ovRead.hEvent = CreateEvent(0, 1, 0, 0);
332 handle->ovWrite.hEvent = CreateEvent(0, 1, 0, 0);
334 serialPort->
handle = handle;
338 int fd = open(port, O_RDWR | O_NOCTTY | O_NDELAY);
346 serialPort->
handle = handle;
356 #if PLATFORM_IS_WINDOWS 359 serialParams.DCBlength =
sizeof(DCB);
361 return GetCommState(handle->platformHandle, &serialParams);
366 return (stat(serialPort->
port, &sb) == 0);
381 #if PLATFORM_IS_WINDOWS 383 CancelIo(handle->platformHandle);
386 CloseHandle(handle->ovRead.hEvent);
387 CloseHandle(handle->ovWrite.hEvent);
389 CloseHandle(handle->platformHandle);
390 handle->platformHandle = 0;
409 #
if PLATFORM_IS_WINDOWS
411 if (!PurgeComm(handle->platformHandle, PURGE_RXABORT | PURGE_RXCLEAR | PURGE_TXABORT | PURGE_TXCLEAR))
418 tcflush(handle->
fd, TCIOFLUSH);
425 #if PLATFORM_IS_WINDOWS 427 static int serialPortReadTimeoutPlatformWindows(
serialPortHandle* handle,
unsigned char* buffer,
int readCount,
int timeoutMilliseconds)
431 ULONGLONG startTime = GetTickCount64();
432 while (totalRead < readCount && GetTickCount64() - startTime <= timeoutMilliseconds)
434 if (ReadFile(handle->platformHandle, buffer + totalRead, readCount - totalRead, &dwRead, handle->
blocking ? &handle->ovRead : 0))
438 GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 1);
444 DWORD dwRes = GetLastError();
445 if (dwRes == ERROR_IO_PENDING)
447 dwRes = WaitForSingleObject(handle->ovRead.hEvent, timeoutMilliseconds);
451 if (!GetOverlappedResult(handle->platformHandle, &handle->ovRead, &dwRead, 0))
453 CancelIo(handle->platformHandle);
462 CancelIo(handle->platformHandle);
468 CancelIo(handle->platformHandle);
471 if (!handle->
blocking && totalRead == 0)
486 struct timeval start, curr;
487 if (timeoutMilliseconds > 0)
489 gettimeofday(&start,
NULL);
494 if (timeoutMilliseconds > 0)
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))
505 n = read(handle->
fd, buffer + totalRead, readCount - totalRead);
508 error_message(
"error %d from read, fd %d",
errno, handle->
fd);
515 if (timeoutMilliseconds > 0 && totalRead < readCount)
517 gettimeofday(&curr,
NULL);
518 dtMs = ((curr.tv_sec - start.tv_sec) * 1000) + ((curr.tv_usec - start.tv_usec) / 1000);
519 if (dtMs >= timeoutMilliseconds)
525 timeoutMilliseconds =
_MAX(0, timeoutMilliseconds - dtMs);
540 if (timeoutMilliseconds < 0)
545 #if PLATFORM_IS_WINDOWS 547 return serialPortReadTimeoutPlatformWindows(handle, buffer, readCount, timeoutMilliseconds);
561 #
if PLATFORM_IS_WINDOWS
563 readFileExCompletionStruct* c = (readFileExCompletionStruct*)
malloc(
sizeof(readFileExCompletionStruct));
564 c->externalCompletion = completion;
565 c->serialPort = serialPort;
567 memset(&c->ov, 0,
sizeof(c->ov));
569 if (!ReadFileEx(handle->platformHandle, buffer, readCount, (LPOVERLAPPED)c, readFileExCompletion))
577 int n = read(handle->
fd, buffer, readCount);
578 completion(serialPort, buffer, (n < 0 ? 0 : n), (n >= 0 ? 0 : n));
589 #
if PLATFORM_IS_WINDOWS
592 if (!WriteFile(handle->platformHandle, buffer, writeCount, &dwWritten, handle->
blocking ? &handle->ovWrite : 0))
594 DWORD result = GetLastError();
595 if (result != ERROR_IO_PENDING)
597 CancelIo(handle->platformHandle);
604 if (!GetOverlappedResult(handle->platformHandle, &handle->ovWrite, &dwWritten, 1))
606 CancelIo(handle->platformHandle);
615 return write(handle->
fd, buffer, writeCount);
635 return serialPort->
pfnWrite(serialPort, buffer, writeCount);
646 #
if PLATFORM_IS_WINDOWS
649 if (ClearCommError(handle->platformHandle, 0, &commStat))
651 return commStat.cbInQue;
658 ioctl(handle->
fd, FIONREAD, &bytesAvailable);
659 return bytesAvailable;
686 #if PLATFORM_IS_WINDOWS 688 Sleep(sleepMilliseconds);
692 usleep(sleepMilliseconds * 1000);
pfnSerialPortIsOpen pfnIsOpen
char port[MAX_SERIAL_PORT_NAME_LENGTH+1]
pfnSerialPortAsyncRead pfnAsyncRead
#define MAX_SERIAL_PORT_NAME_LENGTH
pfnSerialPortGetByteCountAvailableToWrite pfnGetByteCountAvailableToWrite
void serialPortSetPort(serial_port_t *serialPort, const char *port)
pfnSerialPortOpen pfnOpen
void(* pfnSerialPortAsyncReadCompletion)(serial_port_t *serialPort, unsigned char *buf, int len, int errorCode)
pfnSerialPortRead pfnRead
pfnSerialPortFlush pfnFlush
int SERIAL_PORT_DEFAULT_TIMEOUT
int serialPortClose(serial_port_t *serialPort)
pfnSerialPortSleep pfnSleep
void * malloc(size_t size)
NMI_API sint8 close(SOCKET sock)
pfnSerialPortClose pfnClose
pfnSerialPortGetByteCountAvailableToRead pfnGetByteCountAvailableToRead
pfnSerialPortWrite pfnWrite
void * calloc(size_t nitems, size_t size)