26 #include <sys/ioctl.h>
38 int openComPort(
const char* comPortPath, speed_t baudRate);
50 int uartInit(
const char* comPortPath,
int baudrate) {
51 printf(
"Attempting to open port...%s", comPortPath);
75 printf(
"Invalid baudrate\n");
84 printf(
"Invalid device response\n");
112 return read(
fd_serial, bytesToRead, size);
123 return write(
fd_serial, bytesToWrite, size);
147 if (tcflush(
fd_serial, TCIOFLUSH) == -1) {
148 printf(
"flush failed\n");
167 fd_serial = open(comPortPath, O_RDWR | O_NOCTTY);
171 printf(
"...Unable to open com Port %s\n", comPortPath);
176 struct termios options;
180 cfsetospeed(&options, baudRate);
181 cfsetispeed(&options, baudRate);
190 ~(IGNBRK | BRKINT | ICRNL | INLCR | PARMRK | INPCK | ISTRIP | IXON);
198 options.c_lflag &= ~(ECHO | ECHONL | ICANON | IEXTEN | ISIG);
204 options.c_cflag &= ~(CSIZE | PARENB);
205 options.c_cflag |= CS8;
224 options.c_cc[VMIN] = 0;
225 options.c_cc[VTIME] = 20;
228 options.c_cflag |= (CLOCAL | CREAD);
231 int status = tcsetattr(
fd_serial, TCSAFLUSH, &options);
235 printf(
"Configuring comport failed\n");
267 unsigned char SET_WIN_ID0[] = {0xFE, 0x00, 0x0D};
268 unsigned char SET_CONFIG_MODE[] = {0x83, 0x02, 0x0D};
269 unsigned char GET_ID[] = {0x4C, 0x00, 0x0D};
270 unsigned char DELIMITER_[] = {0x0D};
271 const unsigned short ID_VAL_ = 0x5345;
272 unsigned short resp16;
274 while (retry_count > 0) {
287 if (num_rcv_bytes == 0) {
292 if (num_rcv_bytes == 4) {
294 if (resp16 == ID_VAL_) {