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