25 #include <sys/types.h>
28 #include <sys/ioctl.h>
29 #include <linux/serial.h>
50 const int baudTable[] = {
51 0, 50, 75, 110, 134, 150, 200, 300, 600,
52 1200, 1800, 2400, 4800,
53 9600, 19200, 38400, 57600, 115200, 230400,
54 460800, 500000, 576000, 921600, 1000000
56 const int baudCodes[] = {
57 B0, B50, B75, B110, B134, B150, B200, B300, B600,
58 B1200, B1800, B2400, B4800,
59 B9600, B19200, B38400, B57600, B115200, B230400,
60 B460800, B500000, B576000, B921600, B1000000
62 const int iBaudsLen =
sizeof(baudTable) /
sizeof(
int);
65 *iBaudrateCode = B38400;
67 for( i=0; i<iBaudsLen; i++ ) {
68 if( baudTable[i] == iBaudrate ) {
69 *iBaudrateCode = baudCodes[i];
113 m_Handshake(HS_NONE),
115 m_WriteBufSize(m_ReadBufSize),
117 m_ShortBytePeriod(false)
138 std::cout <<
"Trying to open " <<
m_DeviceName <<
" failed: "
139 << strerror(errno) <<
" (Error code " << errno <<
")";
148 std::cerr <<
"tcgetattr of " <<
m_DeviceName <<
" failed: "
149 << strerror(errno) <<
" (Error code " << errno <<
")";
160 m_tio.c_cflag = B9600 | CS8 | CREAD | HUPCL | CLOCAL;
162 cfsetispeed(&
m_tio, B9600);
163 cfsetospeed(&
m_tio, B9600);
165 m_tio.c_cc[VINTR] = 3;
166 m_tio.c_cc[VQUIT] = 28;
167 m_tio.c_cc[VERASE] = 127;
168 m_tio.c_cc[VKILL] = 21;
169 m_tio.c_cc[VEOF] = 4;
170 m_tio.c_cc[VTIME] = 0;
171 m_tio.c_cc[VMIN] = 1;
172 m_tio.c_cc[VSWTC] = 0;
173 m_tio.c_cc[VSTART] = 17;
174 m_tio.c_cc[VSTOP] = 19;
175 m_tio.c_cc[VSUSP] = 26;
176 m_tio.c_cc[VEOL] = 0;
177 m_tio.c_cc[VREPRINT] = 18;
178 m_tio.c_cc[VDISCARD] = 15;
179 m_tio.c_cc[VWERASE] = 23;
180 m_tio.c_cc[VLNEXT] = 22;
181 m_tio.c_cc[VEOL2] = 0;
186 std::cerr <<
"Setting Baudrate to " << iNewBaudrate;
188 int iBaudrateCode = 0;
191 cfsetispeed(&
m_tio, iBaudrateCode);
192 cfsetospeed(&
m_tio, iBaudrateCode);
194 if( !bBaudrateValid ) {
195 std::cerr <<
"Baudrate code not available - setting baudrate directly";
196 struct serial_struct ss;
197 ioctl(
m_Device, TIOCGSERIAL, &ss );
198 ss.flags |= ASYNC_SPD_CUST;
199 ss.custom_divisor = ss.baud_base / iNewBaudrate;
200 ioctl(
m_Device, TIOCSSERIAL, &ss );
205 m_tio.c_cflag &= ~CSIZE;
209 m_tio.c_cflag |= CS5;
212 m_tio.c_cflag |= CS6;
215 m_tio.c_cflag |= CS7;
219 m_tio.c_cflag |= CS8;
222 m_tio.c_cflag &= ~ (PARENB | PARODD);
227 m_tio.c_cflag |= PARODD;
231 m_tio.c_cflag |= PARENB;
241 m_tio.c_cflag |= CSTOPB;
246 m_tio.c_cflag &= ~CSTOPB;
253 m_tio.c_cflag &= ~CRTSCTS;
254 m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
257 m_tio.c_cflag |= CRTSCTS;
258 m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
261 m_tio.c_cflag &= ~CRTSCTS;
262 m_tio.c_iflag |= (IXON | IXOFF | IXANY);
266 m_tio.c_oflag &= ~OPOST;
267 m_tio.c_lflag &= ~ICANON;
274 std::cerr <<
"tcsetattr " <<
m_DeviceName <<
" failed: "
275 << strerror(errno) <<
" (Error code " << errno <<
")";
348 printf(
"%2d Bytes read:", BytesRead);
349 for(
int i=0; i<BytesRead; i++)
350 printf(
" %.2x", (
unsigned char)Buffer[i]);
359 int iBytesToRead = (
Length < iAvaibleBytes) ?
Length : iAvaibleBytes;
363 BytesRead = read(
m_Device, Buffer, iBytesToRead);
381 ssize_t BytesWritten;
386 for (i = 0; i <
Length; i++)
388 BytesWritten = write(
m_Device, Buffer + i, 1);
389 if (BytesWritten != 1)
398 printf(
"%2d Bytes sent:", BytesWritten);
399 for(
int i=0; i<BytesWritten; i++)
400 printf(
" %.2x", (
unsigned char)Buffer[i]);
410 int Res = ioctl(
m_Device, FIONREAD, &cbInQue);