$search
00001 /* 00002 * Katana Native Interface - A C++ interface to the robot arm Katana. 00003 * Copyright (C) 2005 Neuronics AG 00004 * Check out the AUTHORS file for detailed contact information. 00005 * 00006 * This program is free software; you can redistribute it and/or modify 00007 * it under the terms of the GNU General Public License as published by 00008 * the Free Software Foundation; either version 2 of the License, or 00009 * (at your option) any later version. 00010 * 00011 * This program is distributed in the hope that it will be useful, 00012 * but WITHOUT ANY WARRANTY; without even the implied warranty of 00013 * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the 00014 * GNU General Public License for more details. 00015 * 00016 * You should have received a copy of the GNU General Public License 00017 * along with this program; if not, write to the Free Software 00018 * Foundation, Inc., 59 Temple Place, Suite 330, Boston, MA 02111-1307 USA 00019 */ 00020 00021 00022 #include "KNI/cdlCOM.h" 00023 00024 #include "common/Timer.h" 00025 00026 #include <unistd.h> 00027 00028 #ifdef WIN32 00029 00030 CCdlCOM::CCdlCOM(TCdlCOMDesc ccd) : _deviceName(""), _ccd(), _prtHdl(INVALID_HANDLE_VALUE), _oto() { 00031 00032 DCB commDCB; //COM port parameters 00033 COMMTIMEOUTS nto; //new timeouts 00034 char comX[5]; 00035 char dcb[35]; 00036 int i, d; 00037 00038 std::string deviceName; 00039 HANDLE prtHdl; 00040 COMMTIMEOUTS oto; 00041 00042 strncpy_s(comX, "COM ", 5); 00043 comX[3] = digit(ccd.port); 00044 deviceName = comX; 00045 prtHdl = CreateFile(comX, 00046 GENERIC_READ | GENERIC_WRITE, 0, 0, OPEN_EXISTING, 00047 FILE_ATTRIBUTE_NORMAL | FILE_FLAG_WRITE_THROUGH | FILE_FLAG_NO_BUFFERING, 0 00048 ); 00049 00050 if (prtHdl == INVALID_HANDLE_VALUE) { 00051 throw CannotOpenPortException(_deviceName, "info from win32-system not yet available"); 00052 } 00053 00054 FillMemory(&commDCB, sizeof(commDCB), 0); 00055 commDCB.DCBlength = sizeof(commDCB); 00056 strncpy_s(dcb, "baud= parity= data= stop= ", 35); 00057 for(i=5,d=100000; d>=1; d=d/10) { 00058 if(d <= ccd.baud) { 00059 dcb[i++] = digit((ccd.baud/d) % 10); 00060 } 00061 } 00062 dcb[19] = ccd.parity; 00063 dcb[26] = digit(ccd.data); 00064 dcb[33] = digit(ccd.stop); 00065 if (!BuildCommDCB(dcb, &commDCB)) { 00066 CloseHandle(prtHdl); 00067 throw CannotGetSetPortAttributesException(_deviceName); 00068 } 00069 00070 commDCB.fAbortOnError = false; 00071 commDCB.fInX = false; 00072 commDCB.fOutX = false; 00073 commDCB.fOutxCtsFlow = false; 00074 if (!SetCommState(prtHdl, &commDCB)) { 00075 CloseHandle(prtHdl); 00076 throw CannotGetSetPortAttributesException(_deviceName); 00077 } 00078 00079 PurgeComm( prtHdl, PURGE_TXABORT | PURGE_RXABORT | PURGE_TXCLEAR | PURGE_RXCLEAR); 00080 00081 GetCommTimeouts(prtHdl, &oto); 00082 nto.ReadIntervalTimeout = MAXDWORD; 00083 nto.ReadTotalTimeoutMultiplier = 0; 00084 nto.ReadTotalTimeoutConstant = ccd.rttc; 00085 nto.WriteTotalTimeoutMultiplier = 0; 00086 nto.WriteTotalTimeoutConstant = ccd.wttc; 00087 if (!SetCommTimeouts(prtHdl, &nto)) { 00088 CloseHandle(prtHdl); 00089 throw CannotGetSetPortAttributesException(_deviceName); 00090 } 00091 00092 // Everything done, now we can change the state 00093 _prtHdl = prtHdl; 00094 _deviceName = deviceName; 00095 _ccd = ccd; 00096 _oto = oto; 00097 } 00098 00099 CCdlCOM::~CCdlCOM() { 00100 if(_prtHdl == INVALID_HANDLE_VALUE) 00101 return; 00102 00103 FlushFileBuffers(_prtHdl); 00104 SetCommTimeouts(_prtHdl, &_oto); 00105 00106 CloseHandle(_prtHdl); 00107 00108 } 00109 00110 int CCdlCOM::send(const void* buf, int size) { 00111 00112 if (_prtHdl == INVALID_HANDLE_VALUE) { 00113 throw PortNotOpenException(_deviceName); 00114 } 00115 00116 if(PurgeComm(_prtHdl, PURGE_TXABORT | PURGE_TXCLEAR) == 0) { 00117 throw DeviceWriteException(_deviceName, "PurgeComm failed"); 00118 } 00119 00120 unsigned long readsz; 00121 if (WriteFile(_prtHdl, buf, size, &readsz, 0) == 0) { 00122 throw DeviceWriteException(_deviceName, "WriteFile failed"); 00123 } 00124 00125 if(readsz != static_cast<long>(size)) { 00126 throw WriteNotCompleteException(_deviceName); 00127 } 00128 00129 return (int)readsz; 00130 } 00131 00132 int CCdlCOM::recv(void* buf, int size) { 00133 00134 if (_prtHdl == INVALID_HANDLE_VALUE) { 00135 throw PortNotOpenException(_deviceName); 00136 } 00137 00138 unsigned char* tmp = static_cast<unsigned char*>(buf); 00139 unsigned long readsz = 0, readsz_temp = 0; 00140 KNI::Timer timeout(_ccd.rttc); 00141 timeout.Start(); 00142 while (readsz<(unsigned long)size && !timeout.Elapsed()) { 00143 if(ReadFile(_prtHdl, &tmp[readsz], size, &readsz_temp, 0) == 0) { 00144 DeviceReadException( _deviceName, "ReadFile failed" ); 00145 } else { 00146 readsz += readsz_temp; 00147 } 00148 } 00149 00150 if((unsigned)size != readsz) { 00151 throw ReadNotCompleteException(_deviceName); 00152 } 00153 00154 if(PurgeComm(_prtHdl, PURGE_RXABORT | PURGE_RXCLEAR) == 0) { 00155 throw DeviceReadException(_deviceName, "PurgeComm failed"); 00156 } 00157 return (int)readsz; 00158 } 00159 00160 00161 #else //LINUX 00162 00163 CCdlCOM::CCdlCOM(TCdlCOMDesc ccd) : _deviceName(""), _ccd(), _prtHdl(-1), _oto() { 00164 00165 int prtHdl = -1; 00166 00167 std::string deviceName; 00168 struct termios nto, oto; 00169 char name[11]; 00170 00171 errno = 0; 00172 00173 strncpy(name, "/dev/ttyS ", 11); 00174 name[9] = digit(ccd.port); 00175 prtHdl = ::open(name, O_RDWR | O_NOCTTY | O_NDELAY| O_NONBLOCK); 00176 00177 _deviceName = name; 00178 00179 if (prtHdl < 0) { 00180 throw CannotOpenPortException(_deviceName, strerror(errno)); 00181 } 00182 00183 tcgetattr(prtHdl, &oto); 00184 bzero(&nto, sizeof(nto)); 00185 nto.c_cc[VTIME] = 0; 00186 nto.c_cc[VMIN] = 0; 00187 nto.c_oflag = 0; 00188 nto.c_lflag = 0; 00189 nto.c_cflag = CLOCAL | CREAD; 00190 nto.c_iflag = 0; 00191 00192 switch (ccd.baud) { 00193 case 50: 00194 nto.c_cflag |= B50; 00195 break; 00196 case 75: 00197 nto.c_cflag |= B75; 00198 break; 00199 case 110: 00200 nto.c_cflag |= B110; 00201 break; 00202 case 134: 00203 nto.c_cflag |= B134; 00204 break; 00205 case 150: 00206 nto.c_cflag |= B150; 00207 break; 00208 case 200: 00209 nto.c_cflag |= B200; 00210 break; 00211 case 300: 00212 nto.c_cflag |= B300; 00213 break; 00214 case 600: 00215 nto.c_cflag |= B600; 00216 break; 00217 case 1200: 00218 nto.c_cflag |= B1200; 00219 break; 00220 case 1800: 00221 nto.c_cflag |= B1800; 00222 break; 00223 case 2400: 00224 nto.c_cflag |= B2400; 00225 break; 00226 case 4800: 00227 nto.c_cflag |= B4800; 00228 break; 00229 case 9600: 00230 nto.c_cflag |= B9600; 00231 break; 00232 case 19200: 00233 nto.c_cflag |= B19200; 00234 break; 00235 case 38400: 00236 nto.c_cflag |= B38400; 00237 break; 00238 case 57600: 00239 nto.c_cflag |= B57600; 00240 break; 00241 case 115200: 00242 nto.c_cflag |= B115200; 00243 break; 00244 case 230400: 00245 nto.c_cflag |= B230400; 00246 break; 00247 } 00248 00249 switch (ccd.data) { 00250 case 5: 00251 nto.c_cflag |= CS5; 00252 break; 00253 case 6: 00254 nto.c_cflag |= CS6; 00255 break; 00256 case 7: 00257 nto.c_cflag |= CS7; 00258 break; 00259 case 8: 00260 nto.c_cflag |= CS8; 00261 break; 00262 } 00263 00264 switch (ccd.parity) { 00265 case 'N': 00266 case 'n': 00267 break; 00268 case 'O': 00269 case 'o': 00270 nto.c_cflag |= PARENB | PARODD; 00271 break; 00272 case 'E': 00273 case 'e': 00274 nto.c_cflag |= PARENB; 00275 break; 00276 } 00277 00278 switch (ccd.stop) { 00279 case 1: 00280 break; 00281 case 2: 00282 nto.c_cflag |= CSTOPB; 00283 break; 00284 } 00285 00286 tcflush(prtHdl,TCIFLUSH); 00287 if (tcsetattr(prtHdl, TCSANOW, &nto) != 0) { 00288 ::close(prtHdl); 00289 throw CannotGetSetPortAttributesException(_deviceName); 00290 } 00291 00292 _prtHdl = prtHdl; 00293 _deviceName = deviceName; 00294 _ccd = ccd; 00295 _oto = oto; 00296 } 00297 00298 CCdlCOM::~CCdlCOM() { 00299 00300 if (_prtHdl < 0) { 00301 return; 00302 } 00303 00304 tcflush(_prtHdl, TCIFLUSH); 00305 tcsetattr(_prtHdl, TCSANOW, &_oto); 00306 00307 ::close(_prtHdl); // there's nothing we can do about failing 00308 00309 } 00310 00311 int CCdlCOM::send(const void* buf, int size) { 00312 00313 if (_prtHdl < 0) 00314 throw PortNotOpenException(_deviceName); 00315 00316 errno = 0; 00317 00318 int tcflush_return = tcflush(_prtHdl,TCIFLUSH); 00319 if(tcflush_return < 0) 00320 throw DeviceWriteException( _deviceName, strerror(errno) ); 00321 00322 int writesz = write(_prtHdl, buf, size); 00323 00324 if(writesz < 0) 00325 throw DeviceWriteException( _deviceName, strerror(errno) ); 00326 00327 if(writesz != size) 00328 throw WriteNotCompleteException(_deviceName); 00329 00330 return writesz; 00331 } 00332 00333 int CCdlCOM::recv(void* buf, int size) { 00334 unsigned char* tmp = static_cast<unsigned char*>(buf); 00335 register int readsz = 0; 00336 00337 if (_prtHdl < 0) 00338 throw PortNotOpenException(_deviceName); 00339 00340 errno = 0; 00341 00342 int read_return; 00343 KNI::Timer timeout(_ccd.rttc); 00344 timeout.Start(); 00345 while (readsz<size && !timeout.Elapsed()) { 00346 read_return = read(_prtHdl, &tmp[readsz], size-readsz); 00347 if(read_return < 0) { 00348 if(errno != EAGAIN) 00349 throw DeviceReadException( _deviceName, strerror(errno)); 00350 } else { 00351 readsz += read_return; 00352 } 00353 } 00354 00355 if (readsz != size) 00356 throw ReadNotCompleteException(_deviceName); 00357 00358 int tcflush_return = tcflush(_prtHdl,TCIFLUSH); 00359 if(tcflush_return < 0) 00360 throw DeviceReadException( _deviceName, strerror(errno)); 00361 00362 return readsz; 00363 00364 } 00365 00366 00367 00368 #endif //WIN32 else LINUX 00369