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


cob_relayboard
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:18