27 #include <sys/ioctl.h> 38 typedef unsigned char Byte;
52 int uartInit(
const char* comPortPath,
int baudrate) {
53 printf(
"Attempting to open port...%s\n", comPortPath);
68 printf(
"Invalid baudrate\n");
98 return read(fd_serial, bytesToRead, size);
110 return write(fd_serial, bytesToWrite, size);
123 ioctl(fd_serial, FIONREAD, &numBytes);
134 if (tcflush(fd_serial, TCIOFLUSH) == -1) {
135 printf(
"flush failed\n");
154 int port = open(comPortPath, O_RDWR | O_NOCTTY);
160 printf(
"Unable to open com Port %s\n Errno = %i\n", comPortPath, errno);
165 struct termios options;
166 tcgetattr(port, &options);
169 cfsetospeed(&options, baudRate);
170 cfsetispeed(&options, baudRate);
175 options.c_cflag &= ~CSIZE;
176 options.c_cflag |= CS8;
179 options.c_cflag &= ~CSTOPB;
182 options.c_cflag &= ~PARENB;
230 options.c_cc[VMIN] = 4;
231 options.c_cc[VTIME] =
235 options.c_cflag |= (CLOCAL | CREAD);
238 int status = tcsetattr(port, TCSANOW, &options);
242 printf(
"Configuring comport failed\n");
ComPortHandle openComPort(const char *comPortPath, speed_t baudRate)
int purgeComPort(ComPortHandle fd_serial)
int uartInit(const char *comPortPath, int baudrate)
int uartRelease(ComPortHandle fd_serial)
int readComPort(ComPortHandle fd_serial, unsigned char *bytesToRead, int size)
void seDelayMicroSecs(uint32_t micros)
int numBytesReadComPort(ComPortHandle fd_serial)
int writeComPort(ComPortHandle fd_serial, unsigned char *bytesToWrite, int size)
void closeComPort(ComPortHandle fd_serial)