23 #include <sys/ioctl.h> 38 typedef unsigned char Byte;
49 if (tcflush(comPortHandle,TCIOFLUSH)==-1)
51 printf(
"flush failed\n");
74 printf(
"Unable to open com Port %s\n Errno = %i\n", comPortPath, errno);
79 struct termios options;
80 tcgetattr(comPort, &options);
83 cfsetospeed(&options, baudRate);
84 cfsetispeed(&options, baudRate);
89 options.c_cflag &= ~CSIZE;
90 options.c_cflag |= CS8;
93 options.c_cflag &= ~CSTOPB;
96 options.c_cflag &= ~PARENB;
138 options.c_cc[VMIN] = 4;
139 options.c_cc[VTIME] = 20;
142 options.c_cflag |= (CLOCAL | CREAD);
148 int status=tcsetattr(comPort, TCSANOW, &options);
152 printf(
"Configuring comport failed\n");
183 int bytesRead = read(comPort, bytes, bytesToRead);
196 return write(comPort, bytesToWrite, size);
211 ioctl(comPort, FIONREAD, &numBytes);
222 int uartInit(
const char* comPortPath,
int baudRate)
224 printf(
"Attempting to open port...%s\n",comPortPath);
void closeComPort(ComPortHandle comPort)
int uartInit(const char *comPortPath, int baudRate)
int numBytesReadComPort(ComPortHandle comPort)
void seDelayMicroSecs(uint32_t micros)
int writeComPort(ComPortHandle comPort, unsigned char *bytesToWrite, int size)
int readComPort(ComPortHandle comPort, unsigned char *bytes, int bytesToRead)
int uartRelease(ComPortHandle comPort)
ComPortHandle openComPort(const char *comPortPath, int baudRate)
int purgeComPort(ComPortHandle comPortHandle)