SerialIO.cpp
Go to the documentation of this file.
00001 /****************************************************************
00002  *
00003  * Copyright (c) 2010
00004  *
00005  * Fraunhofer Institute for Manufacturing Engineering   
00006  * and Automation (IPA)
00007  *
00008  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00009  *
00010  * Project name: care-o-bot
00011  * ROS stack name: cob_driver
00012  * ROS package name: cob_relayboard
00013  * Description: Class for general Serial communication under Linux OS.
00014  *                                                              
00015  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00016  *                      
00017  * Author: Philipp Koehler
00018  * Supervised by: Christian Connette, email:christian.connette@ipa.fhg.de
00019  *
00020  * Date of creation: March 2010
00021  * ToDo:
00022  *
00023  * +++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++++
00024  *
00025  * Redistribution and use in source and binary forms, with or without
00026  * modification, are permitted provided that the following conditions are met:
00027  *
00028  *     * Redistributions of source code must retain the above copyright
00029  *       notice, this list of conditions and the following disclaimer.
00030  *     * Redistributions in binary form must reproduce the above copyright
00031  *       notice, this list of conditions and the following disclaimer in the
00032  *       documentation and/or other materials provided with the distribution.
00033  *     * Neither the name of the Fraunhofer Institute for Manufacturing 
00034  *       Engineering and Automation (IPA) nor the names of its
00035  *       contributors may be used to endorse or promote products derived from
00036  *       this software without specific prior written permission.
00037  *
00038  * This program is free software: you can redistribute it and/or modify
00039  * it under the terms of the GNU Lesser General Public License LGPL as 
00040  * published by the Free Software Foundation, either version 3 of the 
00041  * License, or (at your option) any later version.
00042  * 
00043  * This program is distributed in the hope that it will be useful,
00044  * but WITHOUT ANY WARRANTY; without even the implied warranty of
00045  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00046  * GNU Lesser General Public License LGPL for more details.
00047  * 
00048  * You should have received a copy of the GNU Lesser General Public 
00049  * License LGPL along with this program. 
00050  * If not, see <http://www.gnu.org/licenses/>.
00051  *
00052  ****************************************************************/
00053 
00054 //#include "stdafx.h"
00055 #include <../include/SerialIO.h>
00056 #include <math.h>
00057 #include <string.h>
00058 #include <iostream>
00059 
00060 #include <errno.h>
00061 #include <sys/types.h>
00062 #include <sys/stat.h>
00063 #include <fcntl.h>
00064 #include <unistd.h>
00065 #include <sys/ioctl.h>
00066 #include <linux/serial.h>
00067 #include <unistd.h>
00068 #include <termios.h>
00069 
00070 
00071 
00072 //#define _PRINT_BYTES
00073 #include <stdio.h>
00074 FILE * log_file;
00075 FILE * log_file2;
00076 /*
00077 #ifdef _DEBUG
00078 #define new DEBUG_NEW
00079 #undef THIS_FILE
00080 static char THIS_FILE[] = __FILE__;
00081 #endif
00082 */
00083 
00084 
00085 bool getBaudrateCode(int iBaudrate, int* iBaudrateCode)
00086 {
00087         // baudrate codes are defined in termios.h
00088         // currently upto B1000000
00089         const int baudTable[] = {
00090                 0, 50, 75, 110, 134, 150, 200, 300, 600,
00091                 1200, 1800, 2400, 4800,
00092                 9600, 19200, 38400, 57600, 115200, 230400,
00093                 460800, 500000, 576000, 921600, 1000000
00094         };
00095         const int baudCodes[] = {
00096                 B0, B50, B75, B110, B134, B150, B200, B300, B600,
00097                 B1200, B1800, B2400, B4800,
00098                 B9600, B19200, B38400, B57600, B115200, B230400,
00099                 B460800, B500000, B576000, B921600, B1000000
00100         };
00101         const int iBaudsLen = sizeof(baudTable) / sizeof(int);
00102 
00103         bool ret = false;
00104         *iBaudrateCode = B38400;
00105         int i;
00106         for( i=0; i<iBaudsLen; i++ ) {
00107                 if( baudTable[i] == iBaudrate ) {
00108                         *iBaudrateCode = baudCodes[i];
00109                         ret = true;
00110                         break;
00111                 }
00112         }
00113         /*
00114         int iStart = 0;
00115         int iEnd = iBaudsLen;
00116         int iPos = (iStart + iEnd) / 2;
00117         while (  iPos + 1 < iBaudsLen
00118                && (iBaudrate < baudTable[iPos] || iBaudrate >= baudTable[iPos + 1])
00119                && iPos != 0)
00120         {
00121                 if (iBaudrate < baudTable[iPos])
00122                 {
00123                         iEnd = iPos;
00124                 }
00125                 else
00126                 {
00127                         iStart = iPos;
00128                 }
00129                 iPos = (iStart + iEnd) / 2;
00130         }
00131 
00132         return baudCodes[iPos];
00133         */
00134         return ret;
00135 }
00136 
00137 
00138 
00139 
00141 // Konstruktion/Destruktion
00143 
00144 SerialIO::SerialIO()
00145         : m_DeviceName("/dev/ttyUSB0"),
00146           m_Device(-1),
00147           m_BaudRate(9600),
00148           m_Multiplier(1.0),
00149           m_ByteSize(8),
00150           m_StopBits(SB_ONE),
00151           m_Parity(PA_NONE),
00152           m_Handshake(HS_NONE),
00153           m_ReadBufSize(1024),
00154           m_WriteBufSize(m_ReadBufSize),
00155           m_Timeout(0),
00156           m_ShortBytePeriod(false)
00157 {
00158         m_BytePeriod.tv_sec = 0;
00159         m_BytePeriod.tv_usec = 0;
00160 }
00161 
00162 SerialIO::~SerialIO()
00163 {
00164         closeIO();
00165 }
00166 
00167 int SerialIO::openIO()
00168 {
00169         int Res;
00170 
00171         // open device
00172         m_Device = open(m_DeviceName.c_str(), O_RDWR | O_NOCTTY | O_NONBLOCK);
00173 
00174         if(m_Device < 0)
00175         {       
00176                 //RF_ERR("Open " << m_DeviceName << " failed, error code " << errno);
00177                 std::cout << "Trying to open " << m_DeviceName << " failed: "
00178                         << strerror(errno) << " (Error code " << errno << ")";
00179 
00180                 return -1;
00181         }
00182 
00183         // set parameters
00184         Res = tcgetattr(m_Device, &m_tio);
00185         if (Res == -1)
00186         {
00187                 std::cerr << "tcgetattr of " << m_DeviceName << " failed: "
00188                         << strerror(errno) << " (Error code " << errno << ")\n";
00189 
00190                 close(m_Device);
00191                 m_Device = -1;
00192 
00193                 return -1;
00194         }
00195 
00196         // Default values
00197         m_tio.c_iflag = 0;
00198         m_tio.c_oflag = 0;
00199         m_tio.c_cflag = B9600 | CS8 | CREAD | HUPCL | CLOCAL;
00200         m_tio.c_lflag = 0;
00201         cfsetispeed(&m_tio, B9600);
00202         cfsetospeed(&m_tio, B9600);
00203 
00204         m_tio.c_cc[VINTR] = 3;  // Interrupt
00205         m_tio.c_cc[VQUIT] = 28; // Quit
00206         m_tio.c_cc[VERASE] = 127;       // Erase
00207         m_tio.c_cc[VKILL] = 21; // Kill-line
00208         m_tio.c_cc[VEOF] = 4;   // End-of-file
00209         m_tio.c_cc[VTIME] = 0;  // Time to wait for data (tenths of seconds)
00210         m_tio.c_cc[VMIN] = 1;   // Minimum number of characters to read
00211         m_tio.c_cc[VSWTC] = 0;
00212         m_tio.c_cc[VSTART] = 17;
00213         m_tio.c_cc[VSTOP] = 19;
00214         m_tio.c_cc[VSUSP] = 26;
00215         m_tio.c_cc[VEOL] = 0;   // End-of-line
00216         m_tio.c_cc[VREPRINT] = 18;
00217         m_tio.c_cc[VDISCARD] = 15;
00218         m_tio.c_cc[VWERASE] = 23;
00219         m_tio.c_cc[VLNEXT] = 22;
00220         m_tio.c_cc[VEOL2] = 0;  // Second end-of-line
00221 
00222 
00223         // set baud rate
00224         int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
00225         std::cerr << "Setting Baudrate to " << iNewBaudrate << "\n";
00226 
00227         int iBaudrateCode = 0;
00228         bool bBaudrateValid = getBaudrateCode(iNewBaudrate, &iBaudrateCode);
00229         
00230         cfsetispeed(&m_tio, iBaudrateCode);
00231         cfsetospeed(&m_tio, iBaudrateCode);
00232 
00233         if( !bBaudrateValid ) {
00234                 std::cerr << "Baudrate code not available - setting baudrate directly\n";
00235                 struct serial_struct ss;
00236                 ioctl( m_Device, TIOCGSERIAL, &ss );
00237                 ss.flags |= ASYNC_SPD_CUST;
00238                 ss.custom_divisor = ss.baud_base / iNewBaudrate;
00239                 ioctl( m_Device, TIOCSSERIAL, &ss );
00240         }
00241 
00242 
00243         // set data format
00244         m_tio.c_cflag &= ~CSIZE;
00245         switch (m_ByteSize)
00246         {
00247                 case 5:
00248                         m_tio.c_cflag |= CS5;
00249                         break;
00250                 case 6:
00251                         m_tio.c_cflag |= CS6;
00252                         break;
00253                 case 7:
00254                         m_tio.c_cflag |= CS7;
00255                         break;
00256                 case 8:
00257                 default:
00258                         m_tio.c_cflag |= CS8;
00259         }
00260 
00261         m_tio.c_cflag &= ~ (PARENB | PARODD);
00262 
00263         switch (m_Parity)
00264         {
00265                 case PA_ODD:
00266                         m_tio.c_cflag |= PARODD;
00267                         //break;  // break must not be active here as we need the combination of PARODD and PARENB on odd parity.
00268                         
00269                 case PA_EVEN:
00270                         m_tio.c_cflag |= PARENB;
00271                         break;
00272                         
00273                 case PA_NONE:
00274                 default: {}
00275         }
00276         
00277         switch (m_StopBits)
00278         {
00279                 case SB_TWO:
00280                         m_tio.c_cflag |= CSTOPB;
00281                         break;
00282                         
00283                 case SB_ONE:
00284                 default:
00285                         m_tio.c_cflag &= ~CSTOPB;
00286         }
00287 
00288         // hardware handshake
00289         switch (m_Handshake)
00290         {
00291                 case HS_NONE:
00292                         m_tio.c_cflag &= ~CRTSCTS;
00293                         m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
00294                         break;
00295                 case HS_HARDWARE:
00296                         m_tio.c_cflag |= CRTSCTS;
00297                         m_tio.c_iflag &= ~(IXON | IXOFF | IXANY);
00298                         break;
00299                 case HS_XONXOFF:
00300                         m_tio.c_cflag &= ~CRTSCTS;
00301                         m_tio.c_iflag |= (IXON | IXOFF | IXANY);
00302                         break;
00303         }
00304 
00305         m_tio.c_oflag &= ~OPOST;
00306         m_tio.c_lflag &= ~ICANON;
00307 
00308         // write parameters
00309         Res = tcsetattr(m_Device, TCSANOW, &m_tio);
00310 
00311         if (Res == -1)
00312         {
00313                 std::cerr << "tcsetattr " << m_DeviceName << " failed: "
00314                         << strerror(errno) << " (Error code " << errno << ")\n";
00315 
00316                 close(m_Device);
00317                 m_Device = -1;
00318 
00319                 return -1;
00320         }
00321 
00322         // set buffer sizes
00323 //      SetupComm(m_Device, m_ReadBufSize, m_WriteBufSize);
00324 
00325         // set timeout
00326         setTimeout(m_Timeout);
00327 
00328         return 0;
00329 }
00330 
00331 void SerialIO::closeIO()
00332 {
00333         if (m_Device != -1)
00334         {
00335                 close(m_Device);
00336                 m_Device = -1;
00337         }
00338 }
00339 
00340 void SerialIO::setTimeout(double Timeout)
00341 {
00342         m_Timeout = Timeout;
00343         if (m_Device != -1)
00344         {
00345                 m_tio.c_cc[VTIME] = cc_t(ceil(m_Timeout * 10.0));
00346                 tcsetattr(m_Device, TCSANOW, &m_tio);
00347         }
00348 
00349 }
00350 
00351 void SerialIO::setBytePeriod(double Period)
00352 {
00353         m_ShortBytePeriod = false;
00354         m_BytePeriod.tv_sec = time_t(Period);
00355         m_BytePeriod.tv_usec = suseconds_t((Period - m_BytePeriod.tv_sec) * 1000);
00356 }
00357 
00358 //-----------------------------------------------
00359 void SerialIO::changeBaudRate(int iBaudRate)
00360 {
00361         /*
00362         int iRetVal;
00363 
00364         m_BaudRate = iBaudRate;
00365 
00366         int iNewBaudrate = int(m_BaudRate * m_Multiplier + 0.5);
00367         int iBaudrateCode = getBaudrateCode(iNewBaudrate);
00368         cfsetispeed(&m_tio, iBaudrateCode);
00369         cfsetospeed(&m_tio, iBaudrateCode);
00370         
00371         iRetVal = tcsetattr(m_Device, TCSANOW, &m_tio);
00372         if(iRetVal == -1)
00373         {
00374                 LOG_OUT("error in SerialCom::changeBaudRate()");
00375                 char c;
00376                 std::cin >> c;
00377                 exit(0);
00378         }*/
00379 }
00380 
00381 
00382 int SerialIO::readBlocking(char *Buffer, int Length)
00383 {
00384         ssize_t BytesRead;
00385         BytesRead = read(m_Device, Buffer, Length);
00386 
00387         //Logfile erstellen
00388 /*
00389         log_file2 = fopen("/myLOG_reading_serial.txt","a");
00390                  fprintf(log_file2, "%2d Bytes read:", BytesRead);
00391                  for(int i=0; i<BytesRead; i++)
00392                                 fprintf(log_file2, " %.2x", (unsigned char)Buffer[i]);
00393                         fprintf(log_file2, "\n");
00394                  fclose(log_file2);
00395 */
00396         return BytesRead;
00397 }
00398 
00399 int SerialIO::readNonBlocking(char *Buffer, int Length)
00400 {
00401         int iAvaibleBytes = getSizeRXQueue();
00402         int iBytesToRead = (Length < iAvaibleBytes) ? Length : iAvaibleBytes;
00403         ssize_t BytesRead;
00404 
00405 
00406         BytesRead = read(m_Device, Buffer, iBytesToRead);
00407         
00408 
00409         // Debug
00410 //      printf("%2d Bytes read:", BytesRead);
00411 //      for(int i=0; i<BytesRead; i++)
00412 //      {
00413 //              unsigned char uc = (unsigned char)Buffer[i];
00414 //              printf(" %u", (unsigned int) uc );
00415 //      }
00416 //      printf("\n");
00417         
00418 
00419         return BytesRead;
00420 }
00421 
00422 int SerialIO::writeIO(const char *Buffer, int Length)
00423 {
00424         ssize_t BytesWritten;
00425 
00426         if (m_BytePeriod.tv_usec || m_BytePeriod.tv_sec)
00427         {
00428                 int i;
00429                 for (i = 0; i < Length; i++)
00430                 {
00431                         BytesWritten = write(m_Device, Buffer + i, 1);
00432                         if (BytesWritten != 1)
00433                                 break;
00434                         select(0, 0, 0, 0, &m_BytePeriod);
00435                 }
00436                 BytesWritten = i;
00437         }
00438         else
00439                 BytesWritten = write(m_Device, Buffer, Length);
00440 
00441 
00442 
00443         //Logfile erstellen
00444 /*
00445          log_file = fopen("/home/niklas/myLOG_serial.txt","a");
00446          fprintf(log_file, "%2d Bytes sent:", BytesWritten);
00447          for(int i=0; i<BytesWritten; i++)
00448                         fprintf(log_file, " %.2x", (unsigned char)Buffer[i]);
00449                 fprintf(log_file, "\n");
00450          fclose(log_file);
00451         return BytesWritten;
00452         */
00453 }
00454 
00455 int SerialIO::getSizeRXQueue()
00456 {
00457         int cbInQue;
00458         int Res = ioctl(m_Device, FIONREAD, &cbInQue);
00459         if (Res == -1) {
00460                 return 0;
00461         }
00462         return cbInQue;
00463 }
00464 
00465 


neo_relayboard
Author(s): Jan-Niklas Nieland
autogenerated on Thu Jun 6 2019 21:37:07