SerialIO.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016  
00017 
00018 //#include "stdafx.h"
00019 #include "cob_sick_s300/SerialIO.h"
00020 #include <math.h>
00021 #include <iostream>
00022 #include <unistd.h>
00023 
00024 #include <errno.h>
00025 #include <sys/types.h>
00026 #include <sys/stat.h>
00027 #include <fcntl.h>
00028 #include <sys/ioctl.h>
00029 #include <linux/serial.h>
00030 
00031 
00032 //#define _PRINT_BYTES
00033 
00034 /*
00035 #ifdef _DEBUG
00036 #define new DEBUG_NEW
00037 #undef THIS_FILE
00038 static char THIS_FILE[] = __FILE__;
00039 #endif
00040 */
00041 
00042 
00043 bool getBaudrateCode(int iBaudrate, int* iBaudrateCode)
00044 {
00045         // baudrate codes are defined in termios.h
00046         // currently upto B1000000
00047         const int baudTable[] = {
00048                 0, 50, 75, 110, 134, 150, 200, 300, 600,
00049                 1200, 1800, 2400, 4800,
00050                 9600, 19200, 38400, 57600, 115200, 230400,
00051                 460800, 500000, 576000, 921600, 1000000
00052         };
00053         const int baudCodes[] = {
00054                 B0, B50, B75, B110, B134, B150, B200, B300, B600,
00055                 B1200, B1800, B2400, B4800,
00056                 B9600, B19200, B38400, B57600, B115200, B230400,
00057                 B460800, B500000, B576000, B921600, B1000000
00058         };
00059         const int iBaudsLen = sizeof(baudTable) / sizeof(int);
00060 
00061         bool ret = false;
00062         *iBaudrateCode = B38400;
00063         int i;
00064         for( i=0; i<iBaudsLen; i++ ) {
00065                 if( baudTable[i] == iBaudrate ) {
00066                         *iBaudrateCode = baudCodes[i];
00067                         ret = true;
00068                         break;
00069                 }
00070         }
00071         /*
00072         int iStart = 0;
00073         int iEnd = iBaudsLen;
00074         int iPos = (iStart + iEnd) / 2;
00075         while (  iPos + 1 < iBaudsLen
00076                && (iBaudrate < baudTable[iPos] || iBaudrate >= baudTable[iPos + 1])
00077                && iPos != 0)
00078         {
00079                 if (iBaudrate < baudTable[iPos])
00080                 {
00081                         iEnd = iPos;
00082                 }
00083                 else
00084                 {
00085                         iStart = iPos;
00086                 }
00087                 iPos = (iStart + iEnd) / 2;
00088         }
00089 
00090         return baudCodes[iPos];
00091         */
00092         return ret;
00093 }
00094 
00095 
00096 
00097 
00099 // Konstruktion/Destruktion
00101 
00102 SerialIO::SerialIO()
00103         : m_DeviceName(""),
00104           m_Device(-1),
00105           m_BaudRate(9600),
00106           m_Multiplier(1.0),
00107           m_ByteSize(8),
00108           m_StopBits(SB_ONE),
00109           m_Parity(PA_NONE),
00110           m_Handshake(HS_NONE),
00111           m_ReadBufSize(1024),
00112           m_WriteBufSize(m_ReadBufSize),
00113           m_Timeout(0),
00114           m_ShortBytePeriod(false)
00115 {
00116         m_BytePeriod.tv_sec = 0;
00117         m_BytePeriod.tv_usec = 0;
00118 }
00119 
00120 SerialIO::~SerialIO()
00121 {
00122         closeIO();
00123 }
00124 
00125 int SerialIO::openIO()
00126 {
00127         int Res;
00128 
00129         // open device
00130         m_Device = open(m_DeviceName.c_str(), O_RDWR | O_NOCTTY /*| O_NONBLOCK*/);
00131 
00132         if(m_Device < 0)
00133         {
00134                 //RF_ERR("Open " << m_DeviceName << " failed, error code " << errno);
00135                 std::cout << "Trying to open " << m_DeviceName << " failed: "
00136                         << strerror(errno) << " (Error code " << errno << ")" << std::endl;
00137 
00138                 return -1;
00139         }
00140 
00141         // set parameters
00142         Res = tcgetattr(m_Device, &m_tio);
00143         if (Res == -1)
00144         {
00145                 std::cout << "tcgetattr of " << m_DeviceName << " failed: "
00146                         << strerror(errno) << " (Error code " << errno << ")" << std::endl;
00147 
00148                 close(m_Device);
00149                 m_Device = -1;
00150 
00151                 return -1;
00152         }
00153 
00154         // Default values
00155         m_tio.c_iflag = 0;
00156         m_tio.c_oflag = 0;
00157         m_tio.c_cflag = B9600 | CS8 | CREAD | HUPCL | CLOCAL;
00158         m_tio.c_lflag = 0;
00159         cfsetispeed(&m_tio, B9600);
00160         cfsetospeed(&m_tio, B9600);
00161 
00162         m_tio.c_cc[VINTR] = 3;  // Interrupt
00163         m_tio.c_cc[VQUIT] = 28; // Quit
00164         m_tio.c_cc[VERASE] = 127;       // Erase
00165         m_tio.c_cc[VKILL] = 21; // Kill-line
00166         m_tio.c_cc[VEOF] = 4;   // End-of-file
00167         m_tio.c_cc[VTIME] = 0;  // Time to wait for data (tenths of seconds)
00168         m_tio.c_cc[VMIN] = 1;   // Minimum number of characters to read
00169         m_tio.c_cc[VSWTC] = 0;
00170         m_tio.c_cc[VSTART] = 17;
00171         m_tio.c_cc[VSTOP] = 19;
00172         m_tio.c_cc[VSUSP] = 26;
00173         m_tio.c_cc[VEOL] = 0;   // End-of-line
00174         m_tio.c_cc[VREPRINT] = 18;
00175         m_tio.c_cc[VDISCARD] = 15;
00176         m_tio.c_cc[VWERASE] = 23;
00177         m_tio.c_cc[VLNEXT] = 22;
00178         m_tio.c_cc[VEOL2] = 0;  // Second end-of-line
00179 
00180 
00181         // set baud rate
00182         int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
00183         std::cout << "Setting Baudrate to " << iNewBaudrate << std::endl;
00184 
00185         int iBaudrateCode = 0;
00186         bool bBaudrateValid = getBaudrateCode(iNewBaudrate, &iBaudrateCode);
00187 
00188         cfsetispeed(&m_tio, iBaudrateCode);
00189         cfsetospeed(&m_tio, iBaudrateCode);
00190 
00191         if( !bBaudrateValid ) {
00192                 std::cout << "Baudrate code not available - setting baudrate directly" << std::endl;
00193                 struct serial_struct ss;
00194                 ioctl( m_Device, TIOCGSERIAL, &ss );
00195                 ss.flags |= ASYNC_SPD_CUST;
00196                 ss.custom_divisor = ss.baud_base / iNewBaudrate;
00197                 ioctl( m_Device, TIOCSSERIAL, &ss );
00198         }
00199 
00200 
00201         // set data format
00202         m_tio.c_cflag &= ~CSIZE;
00203         switch (m_ByteSize)
00204         {
00205                 case 5:
00206                         m_tio.c_cflag |= CS5;
00207                         break;
00208                 case 6:
00209                         m_tio.c_cflag |= CS6;
00210                         break;
00211                 case 7:
00212                         m_tio.c_cflag |= CS7;
00213                         break;
00214                 case 8:
00215                 default:
00216                         m_tio.c_cflag |= CS8;
00217         }
00218 
00219         m_tio.c_cflag &= ~ (PARENB | PARODD);
00220 
00221         switch (m_Parity)
00222         {
00223                 case PA_ODD:
00224                         m_tio.c_cflag |= PARODD;
00225                         //break;  // break must not be active here as we need the combination of PARODD and PARENB on odd parity.
00226 
00227                 case PA_EVEN:
00228                         m_tio.c_cflag |= PARENB;
00229                         break;
00230 
00231                 case PA_NONE:
00232                 default: {}
00233         }
00234 
00235         switch (m_StopBits)
00236         {
00237                 case SB_TWO:
00238                         m_tio.c_cflag |= CSTOPB;
00239                         break;
00240 
00241                 case SB_ONE:
00242                 default:
00243                         m_tio.c_cflag &= ~CSTOPB;
00244         }
00245 
00246         // hardware handshake
00247         switch (m_Handshake)
00248         {
00249                 case HS_NONE:
00250                         m_tio.c_cflag &= ~CRTSCTS;
00251                         m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
00252                         break;
00253                 case HS_HARDWARE:
00254                         m_tio.c_cflag |= CRTSCTS;
00255                         m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
00256                         break;
00257                 case HS_XONXOFF:
00258                         m_tio.c_cflag &= ~CRTSCTS;
00259                         m_tio.c_iflag |= (IXON | IXOFF | IXANY);
00260                         break;
00261         }
00262 
00263         m_tio.c_oflag &= ~OPOST;
00264         m_tio.c_lflag &= ~ICANON;
00265 
00266         // write parameters
00267         Res = tcsetattr(m_Device, TCSANOW, &m_tio);
00268 
00269         if (Res == -1)
00270         {
00271                 std::cout << "tcsetattr " << m_DeviceName << " failed: "
00272                         << strerror(errno) << " (Error code " << errno << ")" << std::endl;
00273 
00274                 close(m_Device);
00275                 m_Device = -1;
00276 
00277                 return -1;
00278         }
00279 
00280         // set buffer sizes
00281         // SetupComm(m_Device, m_ReadBufSize, m_WriteBufSize);
00282 
00283         // set timeout
00284         setTimeout(m_Timeout);
00285 
00286         return 0;
00287 }
00288 
00289 void SerialIO::closeIO()
00290 {
00291         if (m_Device != -1)
00292         {
00293                 close(m_Device);
00294                 m_Device = -1;
00295         }
00296 }
00297 
00298 void SerialIO::setTimeout(double Timeout)
00299 {
00300         m_Timeout = Timeout;
00301         if (m_Device != -1)
00302         {
00303                 m_tio.c_cc[VTIME] = cc_t(ceil(m_Timeout * 10.0));
00304                 tcsetattr(m_Device, TCSANOW, &m_tio);
00305         }
00306 
00307 }
00308 
00309 void SerialIO::setBytePeriod(double Period)
00310 {
00311         m_ShortBytePeriod = false;
00312         m_BytePeriod.tv_sec = time_t(Period);
00313         m_BytePeriod.tv_usec = suseconds_t((Period - m_BytePeriod.tv_sec) * 1000);
00314 }
00315 
00316 //-----------------------------------------------
00317 void SerialIO::changeBaudRate(int iBaudRate)
00318 {
00319         /*
00320         int iRetVal;
00321 
00322         m_BaudRate = iBaudRate;
00323 
00324         int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
00325         int iBaudrateCode = getBaudrateCode(iNewBaudrate);
00326         cfsetispeed(&m_tio, iBaudrateCode);
00327         cfsetospeed(&m_tio, iBaudrateCode);
00328 
00329         iRetVal = tcsetattr(m_Device, TCSANOW, &m_tio);
00330         if(iRetVal == -1)
00331         {
00332                 std::cout << "error in SerialCom::changeBaudRate()" << std::endl;
00333                 char c;
00334                 std::cin >> c;
00335                 exit(0);
00336         }*/
00337 }
00338 
00339 
00340 int SerialIO::readBlocking(char *Buffer, int Length)
00341 {
00342         ssize_t BytesRead;
00343         BytesRead = read(m_Device, Buffer, Length);
00344 #ifdef PRINT_BYTES
00345         printf("%2d Bytes read:", BytesRead);
00346         for(int i=0; i<BytesRead; i++)
00347                 printf(" %.2x", (unsigned char)Buffer[i]);
00348         printf("\n");
00349 #endif
00350         return BytesRead;
00351 }
00352 
00353 int SerialIO::readNonBlocking(char *Buffer, int Length)
00354 {
00355         int iAvaibleBytes = getSizeRXQueue();
00356         int iBytesToRead = (Length < iAvaibleBytes) ? Length : iAvaibleBytes;
00357         ssize_t BytesRead;
00358 
00359 
00360         BytesRead = read(m_Device, Buffer, iBytesToRead);
00361 
00362 
00363         // Debug
00364 //      printf("%2d Bytes read:", BytesRead);
00365 //      for(int i=0; i<BytesRead; i++)
00366 //      {
00367 //              unsigned char uc = (unsigned char)Buffer[i];
00368 //              printf(" %u", (unsigned int) uc );
00369 //      }
00370 //      printf("\n");
00371 
00372 
00373         return BytesRead;
00374 }
00375 
00376 int SerialIO::writeIO(const char *Buffer, int Length)
00377 {
00378         ssize_t BytesWritten;
00379 
00380         if (m_BytePeriod.tv_usec || m_BytePeriod.tv_sec)
00381         {
00382                 int i;
00383                 for (i = 0; i < Length; i++)
00384                 {
00385                         BytesWritten = write(m_Device, Buffer + i, 1);
00386                         if (BytesWritten != 1)
00387                                 break;
00388                         select(0, 0, 0, 0, &m_BytePeriod);
00389                 }
00390                 BytesWritten = i;
00391         }
00392         else
00393                 BytesWritten = write(m_Device, Buffer, Length);
00394 #ifdef PRINT_BYTES
00395         printf("%2d Bytes sent:", BytesWritten);
00396         for(int i=0; i<BytesWritten; i++)
00397                 printf(" %.2x", (unsigned char)Buffer[i]);
00398         printf("\n");
00399 #endif
00400 
00401         return BytesWritten;
00402 }
00403 
00404 int SerialIO::getSizeRXQueue()
00405 {
00406         int cbInQue;
00407         int Res = ioctl(m_Device, FIONREAD, &cbInQue);
00408         if (Res == -1) {
00409                 return 0;
00410         }
00411         return cbInQue;
00412 }
00413 
00414 


cob_sick_s300
Author(s): Florian Weisshardt
autogenerated on Sat Jun 8 2019 21:02:23