47 #if !defined(LINUX_SERIAL_H) && !defined(win_x86) 48 #define LINUX_SERIAL_H 65 fd = open(port_name, O_RDWR | O_NOCTTY | O_NDELAY);
68 fprintf(
stderr,
"Unable to open %s\n\r", port_name);
76 fprintf(
stderr,
"%s is not a serial port\n", port_name);
80 *handle = (
int *) malloc(
sizeof(
int));
81 **(
int **) handle = fd;
87 struct termios options;
90 tcgetattr(*(
int *) handle, &options);
94 options.c_cflag |= CS8;
97 options.c_cflag |= (CLOCAL | CREAD);
100 cfsetispeed(&options, B115200);
101 cfsetospeed(&options, B115200);
113 options.c_cc[VMIN] = 0;
114 options.c_cc[VTIME] = 1;
117 tcsetattr(*(
int *) handle, TCSAFLUSH, &options);
122 int WriteData(
void *handle,
const char *buffer,
int length)
124 int n = write(*(
int *) handle, buffer, length);
127 fprintf(
stderr,
"Error in serial write\r\n");
136 for (i=0; i<length; ++i) printf(
" %x", (
unsigned char)(buffer[i]));
143 int ReadData(
void *handle,
char *buffer,
int length)
145 int bytesRead = read(*(
int *) handle, buffer, length);
156 for (i=0; i<bytesRead; ++i) printf(
" %x", (
unsigned char)buffer[i]);
169 close(*(
int *) handle);
174 #endif // LINUX_SERIAL int SetupSerial(void *handle)
int OpenSerial(void **handle, const char *port_name)
int WriteData(void *handle, const char *buffer, int length)
int ReadData(void *handle, char *buffer, int length)
int CloseSerial(void *handle)