SerialIO.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 //#include "stdafx.h"
19 #include "cob_sick_s300/SerialIO.h"
20 #include <math.h>
21 #include <iostream>
22 #include <unistd.h>
23 
24 #include <errno.h>
25 #include <sys/types.h>
26 #include <sys/stat.h>
27 #include <fcntl.h>
28 #include <sys/ioctl.h>
29 #include <linux/serial.h>
30 
31 
32 //#define _PRINT_BYTES
33 
34 /*
35 #ifdef _DEBUG
36 #define new DEBUG_NEW
37 #undef THIS_FILE
38 static char THIS_FILE[] = __FILE__;
39 #endif
40 */
41 
42 
43 bool getBaudrateCode(int iBaudrate, int* iBaudrateCode)
44 {
45  // baudrate codes are defined in termios.h
46  // currently upto B1000000
47  const int baudTable[] = {
48  0, 50, 75, 110, 134, 150, 200, 300, 600,
49  1200, 1800, 2400, 4800,
50  9600, 19200, 38400, 57600, 115200, 230400,
51  460800, 500000, 576000, 921600, 1000000
52  };
53  const int baudCodes[] = {
54  B0, B50, B75, B110, B134, B150, B200, B300, B600,
55  B1200, B1800, B2400, B4800,
56  B9600, B19200, B38400, B57600, B115200, B230400,
57  B460800, B500000, B576000, B921600, B1000000
58  };
59  const int iBaudsLen = sizeof(baudTable) / sizeof(int);
60 
61  bool ret = false;
62  *iBaudrateCode = B38400;
63  int i;
64  for( i=0; i<iBaudsLen; i++ ) {
65  if( baudTable[i] == iBaudrate ) {
66  *iBaudrateCode = baudCodes[i];
67  ret = true;
68  break;
69  }
70  }
71  /*
72  int iStart = 0;
73  int iEnd = iBaudsLen;
74  int iPos = (iStart + iEnd) / 2;
75  while ( iPos + 1 < iBaudsLen
76  && (iBaudrate < baudTable[iPos] || iBaudrate >= baudTable[iPos + 1])
77  && iPos != 0)
78  {
79  if (iBaudrate < baudTable[iPos])
80  {
81  iEnd = iPos;
82  }
83  else
84  {
85  iStart = iPos;
86  }
87  iPos = (iStart + iEnd) / 2;
88  }
89 
90  return baudCodes[iPos];
91  */
92  return ret;
93 }
94 
95 
96 
97 
99 // Konstruktion/Destruktion
101 
103  : m_DeviceName(""),
104  m_Device(-1),
105  m_BaudRate(9600),
106  m_Multiplier(1.0),
107  m_ByteSize(8),
108  m_StopBits(SB_ONE),
109  m_Parity(PA_NONE),
110  m_Handshake(HS_NONE),
111  m_ReadBufSize(1024),
112  m_WriteBufSize(m_ReadBufSize),
113  m_Timeout(0),
114  m_ShortBytePeriod(false)
115 {
116  m_BytePeriod.tv_sec = 0;
117  m_BytePeriod.tv_usec = 0;
118 }
119 
121 {
122  closeIO();
123 }
124 
126 {
127  int Res;
128 
129  // open device
130  m_Device = open(m_DeviceName.c_str(), O_RDWR | O_NOCTTY /*| O_NONBLOCK*/);
131 
132  if(m_Device < 0)
133  {
134  //RF_ERR("Open " << m_DeviceName << " failed, error code " << errno);
135  std::cout << "Trying to open " << m_DeviceName << " failed: "
136  << strerror(errno) << " (Error code " << errno << ")" << std::endl;
137 
138  return -1;
139  }
140 
141  // set parameters
142  Res = tcgetattr(m_Device, &m_tio);
143  if (Res == -1)
144  {
145  std::cout << "tcgetattr of " << m_DeviceName << " failed: "
146  << strerror(errno) << " (Error code " << errno << ")" << std::endl;
147 
148  close(m_Device);
149  m_Device = -1;
150 
151  return -1;
152  }
153 
154  // Default values
155  m_tio.c_iflag = 0;
156  m_tio.c_oflag = 0;
157  m_tio.c_cflag = B9600 | CS8 | CREAD | HUPCL | CLOCAL;
158  m_tio.c_lflag = 0;
159  cfsetispeed(&m_tio, B9600);
160  cfsetospeed(&m_tio, B9600);
161 
162  m_tio.c_cc[VINTR] = 3; // Interrupt
163  m_tio.c_cc[VQUIT] = 28; // Quit
164  m_tio.c_cc[VERASE] = 127; // Erase
165  m_tio.c_cc[VKILL] = 21; // Kill-line
166  m_tio.c_cc[VEOF] = 4; // End-of-file
167  m_tio.c_cc[VTIME] = 0; // Time to wait for data (tenths of seconds)
168  m_tio.c_cc[VMIN] = 1; // Minimum number of characters to read
169  m_tio.c_cc[VSWTC] = 0;
170  m_tio.c_cc[VSTART] = 17;
171  m_tio.c_cc[VSTOP] = 19;
172  m_tio.c_cc[VSUSP] = 26;
173  m_tio.c_cc[VEOL] = 0; // End-of-line
174  m_tio.c_cc[VREPRINT] = 18;
175  m_tio.c_cc[VDISCARD] = 15;
176  m_tio.c_cc[VWERASE] = 23;
177  m_tio.c_cc[VLNEXT] = 22;
178  m_tio.c_cc[VEOL2] = 0; // Second end-of-line
179 
180 
181  // set baud rate
182  int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
183  std::cout << "Setting Baudrate to " << iNewBaudrate << std::endl;
184 
185  int iBaudrateCode = 0;
186  bool bBaudrateValid = getBaudrateCode(iNewBaudrate, &iBaudrateCode);
187 
188  cfsetispeed(&m_tio, iBaudrateCode);
189  cfsetospeed(&m_tio, iBaudrateCode);
190 
191  if( !bBaudrateValid ) {
192  std::cout << "Baudrate code not available - setting baudrate directly" << std::endl;
193  struct serial_struct ss;
194  ioctl( m_Device, TIOCGSERIAL, &ss );
195  ss.flags |= ASYNC_SPD_CUST;
196  ss.custom_divisor = ss.baud_base / iNewBaudrate;
197  ioctl( m_Device, TIOCSSERIAL, &ss );
198  }
199 
200 
201  // set data format
202  m_tio.c_cflag &= ~CSIZE;
203  switch (m_ByteSize)
204  {
205  case 5:
206  m_tio.c_cflag |= CS5;
207  break;
208  case 6:
209  m_tio.c_cflag |= CS6;
210  break;
211  case 7:
212  m_tio.c_cflag |= CS7;
213  break;
214  case 8:
215  default:
216  m_tio.c_cflag |= CS8;
217  }
218 
219  m_tio.c_cflag &= ~ (PARENB | PARODD);
220 
221  switch (m_Parity)
222  {
223  case PA_ODD:
224  m_tio.c_cflag |= PARODD;
225  //break; // break must not be active here as we need the combination of PARODD and PARENB on odd parity.
226 
227  case PA_EVEN:
228  m_tio.c_cflag |= PARENB;
229  break;
230 
231  case PA_NONE:
232  default: {}
233  }
234 
235  switch (m_StopBits)
236  {
237  case SB_TWO:
238  m_tio.c_cflag |= CSTOPB;
239  break;
240 
241  case SB_ONE:
242  default:
243  m_tio.c_cflag &= ~CSTOPB;
244  }
245 
246  // hardware handshake
247  switch (m_Handshake)
248  {
249  case HS_NONE:
250  m_tio.c_cflag &= ~CRTSCTS;
251  m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
252  break;
253  case HS_HARDWARE:
254  m_tio.c_cflag |= CRTSCTS;
255  m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
256  break;
257  case HS_XONXOFF:
258  m_tio.c_cflag &= ~CRTSCTS;
259  m_tio.c_iflag |= (IXON | IXOFF | IXANY);
260  break;
261  }
262 
263  m_tio.c_oflag &= ~OPOST;
264  m_tio.c_lflag &= ~ICANON;
265 
266  // write parameters
267  Res = tcsetattr(m_Device, TCSANOW, &m_tio);
268 
269  if (Res == -1)
270  {
271  std::cout << "tcsetattr " << m_DeviceName << " failed: "
272  << strerror(errno) << " (Error code " << errno << ")" << std::endl;
273 
274  close(m_Device);
275  m_Device = -1;
276 
277  return -1;
278  }
279 
280  // set buffer sizes
281  // SetupComm(m_Device, m_ReadBufSize, m_WriteBufSize);
282 
283  // set timeout
285 
286  return 0;
287 }
288 
290 {
291  if (m_Device != -1)
292  {
293  close(m_Device);
294  m_Device = -1;
295  }
296 }
297 
298 void SerialIO::setTimeout(double Timeout)
299 {
300  m_Timeout = Timeout;
301  if (m_Device != -1)
302  {
303  m_tio.c_cc[VTIME] = cc_t(ceil(m_Timeout * 10.0));
304  tcsetattr(m_Device, TCSANOW, &m_tio);
305  }
306 
307 }
308 
309 void SerialIO::setBytePeriod(double Period)
310 {
311  m_ShortBytePeriod = false;
312  m_BytePeriod.tv_sec = time_t(Period);
313  m_BytePeriod.tv_usec = suseconds_t((Period - m_BytePeriod.tv_sec) * 1000);
314 }
315 
316 //-----------------------------------------------
317 void SerialIO::changeBaudRate(int iBaudRate)
318 {
319  /*
320  int iRetVal;
321 
322  m_BaudRate = iBaudRate;
323 
324  int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
325  int iBaudrateCode = getBaudrateCode(iNewBaudrate);
326  cfsetispeed(&m_tio, iBaudrateCode);
327  cfsetospeed(&m_tio, iBaudrateCode);
328 
329  iRetVal = tcsetattr(m_Device, TCSANOW, &m_tio);
330  if(iRetVal == -1)
331  {
332  std::cout << "error in SerialCom::changeBaudRate()" << std::endl;
333  char c;
334  std::cin >> c;
335  exit(0);
336  }*/
337 }
338 
339 
340 int SerialIO::readBlocking(char *Buffer, int Length)
341 {
342  ssize_t BytesRead;
343  BytesRead = read(m_Device, Buffer, Length);
344 #ifdef PRINT_BYTES
345  printf("%2d Bytes read:", BytesRead);
346  for(int i=0; i<BytesRead; i++)
347  printf(" %.2x", (unsigned char)Buffer[i]);
348  printf("\n");
349 #endif
350  return BytesRead;
351 }
352 
353 int SerialIO::readNonBlocking(char *Buffer, int Length)
354 {
355  int iAvaibleBytes = getSizeRXQueue();
356  int iBytesToRead = (Length < iAvaibleBytes) ? Length : iAvaibleBytes;
357  ssize_t BytesRead;
358 
359 
360  BytesRead = read(m_Device, Buffer, iBytesToRead);
361 
362 
363  // Debug
364 // printf("%2d Bytes read:", BytesRead);
365 // for(int i=0; i<BytesRead; i++)
366 // {
367 // unsigned char uc = (unsigned char)Buffer[i];
368 // printf(" %u", (unsigned int) uc );
369 // }
370 // printf("\n");
371 
372 
373  return BytesRead;
374 }
375 
376 int SerialIO::writeIO(const char *Buffer, int Length)
377 {
378  ssize_t BytesWritten;
379 
380  if (m_BytePeriod.tv_usec || m_BytePeriod.tv_sec)
381  {
382  int i;
383  for (i = 0; i < Length; i++)
384  {
385  BytesWritten = write(m_Device, Buffer + i, 1);
386  if (BytesWritten != 1)
387  break;
388  select(0, 0, 0, 0, &m_BytePeriod);
389  }
390  BytesWritten = i;
391  }
392  else
393  BytesWritten = write(m_Device, Buffer, Length);
394 #ifdef PRINT_BYTES
395  printf("%2d Bytes sent:", BytesWritten);
396  for(int i=0; i<BytesWritten; i++)
397  printf(" %.2x", (unsigned char)Buffer[i]);
398  printf("\n");
399 #endif
400 
401  return BytesWritten;
402 }
403 
405 {
406  int cbInQue;
407  int Res = ioctl(m_Device, FIONREAD, &cbInQue);
408  if (Res == -1) {
409  return 0;
410  }
411  return cbInQue;
412 }
413 
414 
int getSizeRXQueue()
Definition: SerialIO.cpp:404
void setBytePeriod(double Period)
Definition: SerialIO.cpp:309
int m_Device
Definition: SerialIO.h:200
std::string m_DeviceName
Definition: SerialIO.h:199
int m_StopBits
Definition: SerialIO.h:203
void closeIO()
Definition: SerialIO.cpp:289
virtual ~SerialIO()
Destructor.
Definition: SerialIO.cpp:120
HandshakeFlags m_Handshake
Definition: SerialIO.h:205
void setTimeout(double Timeout)
Definition: SerialIO.cpp:298
int m_BaudRate
Definition: SerialIO.h:201
::termios m_tio
Definition: SerialIO.h:198
void changeBaudRate(int BaudRate)
Definition: SerialIO.cpp:317
int writeIO(const char *Buffer, int Length)
Definition: SerialIO.cpp:376
int readBlocking(char *Buffer, int Length)
Definition: SerialIO.cpp:340
bool m_ShortBytePeriod
Definition: SerialIO.h:209
SerialIO()
Default constructor.
Definition: SerialIO.cpp:102
double m_Timeout
Definition: SerialIO.h:207
int readNonBlocking(char *Buffer, int Length)
Definition: SerialIO.cpp:353
ParityFlags m_Parity
Definition: SerialIO.h:204
int m_ByteSize
Definition: SerialIO.h:203
double m_Multiplier
Definition: SerialIO.h:202
int openIO()
Definition: SerialIO.cpp:125
::timeval m_BytePeriod
Definition: SerialIO.h:208
bool getBaudrateCode(int iBaudrate, int *iBaudrateCode)
Definition: SerialIO.cpp:43


cob_sick_s300
Author(s): Florian Weisshardt
autogenerated on Wed Apr 7 2021 02:11:50