30 #include <sys/types.h> 37 : baudrate_(baudrate_index), parity_(parity) {
46 tcflush(
fd_, TCOFLUSH);
47 tcflush(
fd_, TCIFLUSH);
54 fd_ = open(filename, O_RDWR | O_NOCTTY);
56 printf(
"Open %s fail!\n", filename);
59 chmod(filename, S_IRWXU | S_IRWXG | S_IRWXO);
60 printf(
"Open %s success!\n", filename);
78 tcflush(
fd_, TCOFLUSH);
79 tcflush(
fd_, TCIFLUSH);
89 B2400, B4800, B9600, B19200, B38400, B57600, B115200,
90 B230400, B460800, B500000, B576000, B921600, B1152000, B1500000,
91 B2000000, B2500000, B3000000, B3500000, B4000000};
93 struct termios options;
100 tcgetattr(
fd_, &options);
101 memset(&options, 0,
sizeof(options));
102 tcflush(
fd_, TCIOFLUSH);
103 tcsetattr(
fd_, TCSANOW, &options);
107 options.c_cflag |= (CLOCAL | CREAD);
118 options.c_cflag &= ~CBAUD;
119 baudrate = baud_map[baudrate_index];
120 options.c_cflag |= baudrate;
125 options.c_cflag &= ~PARENB;
126 options.c_cflag &= ~CSTOPB;
127 options.c_cflag &= ~CSIZE;
128 options.c_cflag |= CS8;
132 options.c_cflag |= PARENB;
133 options.c_cflag &= ~PARODD;
134 options.c_cflag &= ~CSTOPB;
135 options.c_cflag &= ~CSIZE;
136 options.c_cflag |= CS7;
140 options.c_cflag |= PARENB;
141 options.c_cflag |= PARODD;
142 options.c_cflag &= ~CSTOPB;
143 options.c_cflag &= ~CSIZE;
144 options.c_cflag |= CS7;
148 options.c_cflag &= ~PARENB;
149 options.c_cflag &= ~CSTOPB;
150 options.c_cflag &= ~CSIZE;
151 options.c_cflag |= CS8;
158 options.c_iflag &= ~INPCK;
164 options.c_cc[VTIME] = 1;
167 options.c_cc[VMIN] = 1;
170 tcflush(
fd_, TCIOFLUSH);
173 tcsetattr(
fd_, TCSANOW, &options);
180 return write(
fd_, buffer, size);
188 return read(
fd_, buffer, size);
int Open(const char *filename)
ssize_t Read(char *buffer, size_t size)
int Setup(uint8_t baudrate_index, uint8_t parity)
UserUart(uint8_t baudrate_index, uint8_t parity)
ssize_t Write(const char *buffer, size_t size)