16 #ifndef DUMPBOT_SERIAL_FUNC_HPP_ 17 #define DUMPBOT_SERIAL_FUNC_HPP_ 52 int UART0_Set(
int fd,
int speed,
int flow_ctrl,
int databits,
int stopbits,
int parity){
56 int speed_arr[] = { B115200, B19200, B9600, B4800, B2400, B1200, B300};
57 int name_arr[] = {115200, 19200, 9600, 4800, 2400, 1200, 300};
59 struct termios options;
63 if ( tcgetattr( fd,&options) != 0){
64 perror(
"SetupSerial 1");
69 for ( i= 0; i <
sizeof(speed_arr) /
sizeof(
int); i++){
70 if (speed == name_arr[i]){
71 cfsetispeed(&options, speed_arr[i]);
72 cfsetospeed(&options, speed_arr[i]);
77 options.c_cflag |= CLOCAL;
79 options.c_cflag |= CREAD;
84 options.c_cflag &= ~CRTSCTS;
87 options.c_cflag |= CRTSCTS;
90 options.c_cflag |= IXON | IXOFF | IXANY;
95 options.c_cflag &= ~CSIZE;
98 options.c_cflag |= CS5;
101 options.c_cflag |= CS6;
104 options.c_cflag |= CS7;
107 options.c_cflag |= CS8;
110 fprintf(stderr,
"Unsupported data size\n");
118 options.c_cflag &= ~PARENB;
119 options.c_iflag &= ~INPCK;
123 options.c_cflag |= (PARODD | PARENB);
124 options.c_iflag |= INPCK;
128 options.c_cflag |= PARENB;
129 options.c_cflag &= ~PARODD;
130 options.c_iflag |= INPCK;
134 options.c_cflag &= ~PARENB;
135 options.c_cflag &= ~CSTOPB;
138 fprintf(stderr,
"Unsupported parity\n");
145 options.c_cflag &= ~CSTOPB;
break;
147 options.c_cflag |= CSTOPB;
break;
149 fprintf(stderr,
"Unsupported stop bits\n");
154 options.c_oflag &= ~OPOST;
156 options.c_lflag &= ~(ICANON | ECHO | ECHOE | ISIG);
160 options.c_cc[VTIME] = 1;
161 options.c_cc[VMIN] = 1;
164 tcflush(fd,TCIFLUSH);
167 if (tcsetattr(fd,TCSANOW,&options) != 0)
169 perror(
"com set error!\n");
187 int UART0_Init(
int fd,
int speed,
int flow_ctrl,
int databits,
int stopbits,
int parity){
190 if (UART0_Set(fd,speed,flow_ctrl,databits,stopbits,
'N') ==
FALSE){
219 fs_sel = select(fd+1,&fs_read,NULL,NULL,&time);
221 len = read(fd,rcv_buf,data_len);
226 printf(
"Sorry,I am wrong!");
242 len = write(fd,send_buf,data_len);
243 if (len == data_len ){
247 tcflush(fd,TCOFLUSH);
int UART0_Recv(int fd, char *rcv_buf, int data_len)
int UART0_Set(int fd, int speed, int flow_ctrl, int databits, int stopbits, int parity)
int UART0_Init(int fd, int speed, int flow_ctrl, int databits, int stopbits, int parity)
int UART0_Send(int fd, char *send_buf, int data_len)