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


cob_relayboard
Author(s): Christian Connette
autogenerated on Fri Mar 1 2013 17:46:29