Go to the documentation of this file.00001
00047 #include "serial.h"
00048 #include <stdio.h>
00049 #include <string.h>
00050 #include <unistd.h>
00051 #include <fcntl.h>
00052 #include <errno.h>
00053 #include <termios.h>
00054 #include <stdlib.h>
00055
00056
00057 int OpenSerial(int* fd, const char* port_name)
00058 {
00059 *fd = open(port_name, O_RDWR | O_NOCTTY | O_NDELAY | O_NONBLOCK);
00060 if (*fd == -1) {
00061 fprintf(stderr, "Unable to open %s\n\r", port_name);
00062 return -3;
00063 }
00064
00065
00066 if (!isatty(*fd)) {
00067 close(*fd);
00068 fprintf(stderr, "%s is not a serial port\n", port_name);
00069 return -3;
00070 }
00071
00072 return *fd;
00073 }
00074
00075 int SetupSerial(int fd, int baudrate)
00076 {
00077 struct termios options;
00078
00079
00080 tcgetattr(fd, &options);
00081
00082
00083 options.c_cflag = 0;
00084 options.c_cflag |= CS8;
00085
00086
00087 options.c_cflag |= (CLOCAL | CREAD);
00088
00089
00090
00091
00092
00093 if( (baudrate == 0) || (baudrate==115200) ) {
00094 cfsetispeed(&options, B115200);
00095 cfsetospeed(&options, B115200);
00096 } else if( (baudrate==57600) ) {
00097 cfsetispeed(&options, B57600);
00098 cfsetospeed(&options, B57600);
00099 } else if( (baudrate==38400) ) {
00100 cfsetispeed(&options, B38400);
00101 cfsetospeed(&options, B38400);
00102 } else if( (baudrate==19200) ) {
00103 cfsetispeed(&options, B19200);
00104 cfsetospeed(&options, B19200);
00105 } else if( (baudrate==9600) ) {
00106 cfsetispeed(&options, B9600);
00107 cfsetospeed(&options, B9600);
00108 } else {
00109
00110 return -1;
00111 }
00112
00113
00114 options.c_iflag = 0;
00115
00116
00117 options.c_oflag = 0;
00118
00119
00120 options.c_lflag = 0;
00121
00122
00123 options.c_cc[VMIN] = 0;
00124 options.c_cc[VTIME] = 1;
00125
00126
00127 tcsetattr(fd, TCSAFLUSH, &options);
00128
00129 return 0;
00130 }