00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018 #include "RS232Device.h"
00019 #if defined (_WIN32)
00020 #endif
00021 #if defined(__LINUX__)
00022 #include <fcntl.h>
00023 #include <termios.h>
00024 #include <unistd.h>
00025 #endif
00026 #if defined (__QNX__)
00027 #include <fcntl.h>
00028 #include <termios.h>
00029 #endif
00030
00031 #define RSID_SENDDAT 0x04
00032 #define RSID_RECVDAT 0x08
00033 #define STX 0x02
00034 #define ETX 0x03
00035 #define DLE 0x10
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049 int CRS232Device::getDeviceError(int iErrorState)
00050 {
00051 m_iErrorState = 0;
00052 return iErrorState;
00053 }
00054
00055 int CRS232Device::setBaudRate()
00056 {
00057 m_iErrorState = 0;
00058 return m_iErrorState;
00059 }
00060
00061 int CRS232Device::setMessageId(unsigned long uiMessageId)
00062 {
00063 m_iErrorState = 0;
00064 return m_iErrorState;
00065 }
00066
00067 int CRS232Device::clearReadQueue()
00068 {
00069 m_iErrorState = 0;
00070 return m_iErrorState;
00071 }
00072
00073 int CRS232Device::reinit(unsigned char ucBaudRateId)
00074 {
00075 m_iErrorState = 0;
00076 return m_iErrorState;
00077 }
00078
00079 int CRS232Device::readDevice(CProtocolMessage& rclProtocolMessage)
00080 {
00081 unsigned char aucMessageBuffer[22] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
00082 unsigned char aucReadBuffer[22] = {0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0,0};
00083 unsigned char ucChar;
00084 unsigned char aucDecodeBuffer[11] = {0,0,0,0,0,0,0,0,0,0,0};
00085 unsigned char ucMessageLength = 0;
00086 unsigned int i = 0;
00087 unsigned int k = 0;
00088 unsigned int uiMessageBufferIndex = 0;
00089 unsigned int uiReadBufferIndex = 0;
00090 double fTime = 0;
00091 bool bExit = false;
00092 bool bMessageComplete = false;
00093 bool bDecodeError = false;
00094 int iRetVal;
00095 m_iErrorState = 0;
00096 #if defined(_WIN32)
00097 DWORD iErrorCode = 0;
00098 DWORD iReadLength = 0;
00099 m_clTimer.start();
00100
00101 do
00102 {
00103 iRetVal = ReadFile( m_hDevice, &ucChar, 1, &iReadLength, NULL );
00104 if (iRetVal == 0)
00105 {
00106 void* lpMsgBuf;
00107 FormatMessage(
00108 FORMAT_MESSAGE_ALLOCATE_BUFFER |
00109 FORMAT_MESSAGE_FROM_SYSTEM |
00110 FORMAT_MESSAGE_IGNORE_INSERTS,
00111 NULL,
00112 GetLastError(),
00113 MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
00114 (LPTSTR) &lpMsgBuf,
00115 0,
00116 NULL
00117 );
00118 debug(1,"COMERROR:%s\n",lpMsgBuf);
00119 warning( "Receive Error. ReadFile failed.\n" );
00120 ClearCommError( m_hDevice, &iErrorCode, NULL );
00121 m_iErrorState = ERRID_DEV_READERROR;
00122 return m_iErrorState;
00123 }
00124 if( iReadLength == 1 )
00125 {
00126 aucReadBuffer[uiReadBufferIndex++] = ucChar;
00127 if( ucChar == ETX )
00128 bExit = true;
00129 }
00130 m_clTimer.stop();
00131 fTime = m_clTimer.executionTime() * 1000;
00132 if( fTime > m_uiTimeOut + 10 * m_iModuleCount)
00133 {
00134 bExit = true;
00135 warning( "Receive Error. Timeout %f. %d bytes received.\n", fTime, uiReadBufferIndex);
00136 m_iErrorState = ERRID_DEV_READTIMEOUT;
00137 return m_iErrorState;
00138 }
00139 } while( !bExit );
00140
00141 #endif
00142
00143 #if defined(__QNX__)
00144 struct timeval clTimeout;
00145 fd_set fdReadSet;
00146 clTimeout.tv_sec=0;
00147 clTimeout.tv_usec=m_uiTimeOut * 1000;
00148 m_clTimer.start();
00149 ssize_t bytesRead = 0;
00150 do
00151 {
00152 FD_ZERO( &fdReadSet );
00153 FD_SET( m_hDevice, &fdReadSet );
00154
00155 iRetVal=select( FD_SETSIZE, &fdReadSet, NULL, NULL, &clTimeout );
00156 if(iRetVal < 0)
00157 {
00158 warning("Receive Error in select");
00159 return ERRID_IO_READERROR;
00160 }
00161 else if (iRetVal>0 && FD_ISSET(m_hDevice,&fdReadSet))
00162 {
00163 bytesRead = read( m_hDevice, &ucChar, 1 );
00164 if( bytesRead < 0 )
00165 { warning( "Receive Error. Read error.\n" );
00166 m_iErrorState = ERRID_DEV_READERROR;
00167 return m_iErrorState;
00168 }
00169 else if( bytesRead == 1 )
00170 {
00171 aucReadBuffer[uiReadBufferIndex++] = ucChar;
00172 if( ucChar == ETX )
00173 bExit = true;
00174 }
00175 else if( bytesRead == 0 )
00176 {
00177 warning( "Receive Error. Timeout\n");
00178 m_iErrorState = ERRID_DEV_READTIMEOUT;
00179 return m_iErrorState;
00180 }
00181 }
00182 m_clTimer.stop();
00183 fTime = m_clTimer.executionTime() * 1000;
00184 if( fTime > m_uiTimeOut * m_iModuleCount)
00185 { bExit = true;
00186 warning( "Receive Error. Timeout. %d bytes received.\n", uiReadBufferIndex );
00187 m_iErrorState = ERRID_DEV_READTIMEOUT;
00188 return m_iErrorState;
00189 }
00190 } while( !bExit );
00191
00192 #endif
00193
00194 #if defined(__LINUX__)
00195 ssize_t bytesRead = 0;
00196 struct timeval clTimeout;
00197 fd_set fdReadSet;
00198 clTimeout.tv_sec=0;
00199 clTimeout.tv_usec=m_uiTimeOut * 1000;
00200 m_clTimer.start();
00201
00202 do
00203 {
00204 FD_ZERO( &fdReadSet );
00205 FD_SET( m_hDevice, &fdReadSet );
00206
00207 iRetVal=select( FD_SETSIZE, &fdReadSet, NULL, NULL, &clTimeout );
00208 if(iRetVal < 0)
00209 {
00210 warning("Receive Error in select");
00211 return ERRID_IO_READERROR;
00212 }
00213 else if (iRetVal>0 && FD_ISSET(m_hDevice,&fdReadSet))
00214 {
00215 bytesRead = read( m_hDevice, &ucChar, 1 );
00216 if( bytesRead < 0 )
00217 { warning( "Receive Error. Read error.\n" );
00218 m_iErrorState = ERRID_DEV_READERROR;
00219 return m_iErrorState;
00220 }
00221 else if( bytesRead == 1 )
00222 {
00223 aucReadBuffer[uiReadBufferIndex++] = ucChar;
00224 if( ucChar == ETX )
00225 bExit = true;
00226 }
00227 else if( bytesRead == 0 )
00228 {
00229 warning( "Receive Error. Timeout\n");
00230 m_iErrorState = ERRID_DEV_READTIMEOUT;
00231 return m_iErrorState;
00232 }
00233 }
00234 m_clTimer.stop();
00235 fTime = m_clTimer.executionTime() * 1000;
00236 if( fTime > m_uiTimeOut * m_iModuleCount)
00237 { bExit = true;
00238 warning( "Receive Error. Timeout. %d bytes received.\n", uiReadBufferIndex );
00239 m_iErrorState = ERRID_DEV_READTIMEOUT;
00240 return m_iErrorState;
00241 }
00242 } while( !bExit );
00243
00244 #endif
00245
00246 for( i = 0; i < uiReadBufferIndex; i++ )
00247 {
00248 if( aucReadBuffer[i] == STX )
00249 {
00250 uiMessageBufferIndex = 0;
00251 bMessageComplete = false;
00252 }
00253 if( aucReadBuffer[i] == ETX )
00254 bMessageComplete = true;
00255 if( uiMessageBufferIndex > 22 )
00256 {
00257 uiMessageBufferIndex = 0;
00258 bMessageComplete = false;
00259 warning( "More than 22 bytes!" );
00260 }
00261 aucMessageBuffer[uiMessageBufferIndex] = aucReadBuffer[i];
00262 uiMessageBufferIndex++;
00263 }
00264
00265 if( bMessageComplete )
00266 {
00267 if( (aucMessageBuffer[0] == STX) && (aucMessageBuffer[uiMessageBufferIndex-1] == ETX) )
00268 {
00269 for( i = 1; i < uiMessageBufferIndex-1; i++ )
00270 {
00271 if( aucMessageBuffer[i] == DLE )
00272 {
00273 i++;
00274 aucDecodeBuffer[k] = aucMessageBuffer[i] - 0x80;
00275 }
00276 else if( aucMessageBuffer[i] == ETX || aucMessageBuffer[i] == STX )
00277 {
00278 bDecodeError = true;
00279 break;
00280 }
00281 else
00282 aucDecodeBuffer[k] = aucMessageBuffer[i];
00283 k++;
00284 }
00285 }
00286 else
00287 {
00288 warning( "Receive Error: STX/ETX framing incorrect.\n" );
00289 m_iErrorState = ERRID_DEV_READERROR;
00290 return m_iErrorState;
00291 }
00292
00293
00294 ucMessageLength = aucDecodeBuffer[1] & 0x0F;
00295 if( aucDecodeBuffer[0] & RSID_RECVDAT )
00296 {
00297 if( !bDecodeError )
00298 {
00299 if( ucMessageLength == k-3 )
00300 {
00301 rclProtocolMessage.m_ucMessageLength = ucMessageLength;
00302 rclProtocolMessage.m_iModuleId = (((aucDecodeBuffer[0]&0x03)<<3)+((aucDecodeBuffer[1]&0xE0)>>5));
00303 for( i = 0; i < ucMessageLength; i++ )
00304 rclProtocolMessage.m_aucMessageData[i] = aucDecodeBuffer[i+2];
00305 rclProtocolMessage.m_uiMessageId = MSGID_ACK + rclProtocolMessage.m_iModuleId;
00306 m_iErrorState = 0;
00307 return m_iErrorState;
00308 }
00309 warning( "Receive Error: Length incorrect received %d instead of %d\n", k-3, ucMessageLength );
00310 m_iErrorState = ERRID_DEV_READERROR;
00311 return m_iErrorState;
00312 }
00313
00314 warning( "Receive Error: STX/ETX inside message.\n" );
00315 m_iErrorState = ERRID_DEV_READERROR;
00316 return m_iErrorState;
00317 }
00318
00319 warning( "Receive Error: MessageId incorrect.\n" );
00320 m_iErrorState = ERRID_DEV_READERROR;
00321 return m_iErrorState;
00322 }
00323
00324 warning( "Receive Error: ETX not received.\n" );
00325 m_iErrorState = ERRID_DEV_READERROR;
00326 return m_iErrorState;
00327 }
00328
00329 int CRS232Device::writeDevice(CProtocolMessage& rclProtocolMessage)
00330 {
00331 int i = 0;
00332 unsigned int uiWriteBufferIndex = 0;
00333 unsigned long uiWriteLength = 0;
00334 unsigned char aucWriteBuffer[24];
00335 unsigned short uiSum = 0;
00336 unsigned char aucEncodeBuffer[11] = {0,0,0,0,0,0,0,0,0,0,0};
00337 int iRetVal;
00338 CRS232Message clRS232Message;
00339
00340 m_iErrorState = 0;
00341
00342 clRS232Message.m_aucMessageId[0] = (unsigned char)rclProtocolMessage.m_iModuleId >> 3;
00343 clRS232Message.m_aucMessageId[0] |= RSID_SENDDAT;
00344 clRS232Message.m_aucMessageId[1] = (unsigned char)rclProtocolMessage.m_iModuleId << 5;
00345 clRS232Message.m_aucMessageId[1] |= (unsigned char)rclProtocolMessage.m_ucMessageLength;
00346 clRS232Message.m_ucMessageLength = (unsigned char)rclProtocolMessage.m_ucMessageLength;
00347 memcpy(clRS232Message.m_aucMessageData, rclProtocolMessage.m_aucMessageData, rclProtocolMessage.m_ucMessageLength);
00348
00349 aucEncodeBuffer[0] = clRS232Message.m_aucMessageId[0];
00350 aucEncodeBuffer[1] = clRS232Message.m_aucMessageId[1];
00351 for( i = 0; i < clRS232Message.m_ucMessageLength; i++ )
00352 aucEncodeBuffer[i+2] = clRS232Message.m_aucMessageData[i];
00353 for( i = 0; i < clRS232Message.m_ucMessageLength+2; i++ )
00354 uiSum += aucEncodeBuffer[i];
00355 aucEncodeBuffer[clRS232Message.m_ucMessageLength+2] = uiSum + (uiSum>>8);
00356
00357 aucWriteBuffer[0] = STX;
00358 uiWriteBufferIndex = 1;
00359
00360 for( i = 0; i < clRS232Message.m_ucMessageLength+3; i++ )
00361 {
00362 if( aucEncodeBuffer[i] == DLE || aucEncodeBuffer[i] == STX || aucEncodeBuffer[i] == ETX )
00363 {
00364 aucWriteBuffer[uiWriteBufferIndex] = DLE;
00365 uiWriteBufferIndex++;
00366 aucWriteBuffer[uiWriteBufferIndex] = aucEncodeBuffer[i] + 0x80;
00367 }
00368 else
00369 aucWriteBuffer[uiWriteBufferIndex] = aucEncodeBuffer[i];
00370 uiWriteBufferIndex++;
00371 }
00372
00373 aucWriteBuffer[uiWriteBufferIndex] = ETX;
00374
00375 #if defined(_WIN32)
00376 DWORD iErrorCode;
00377
00378 PurgeComm( m_hDevice, PURGE_TXABORT );
00379 PurgeComm( m_hDevice, PURGE_RXABORT );
00380 PurgeComm( m_hDevice, PURGE_TXCLEAR );
00381 PurgeComm( m_hDevice, PURGE_RXCLEAR );
00382
00383 iRetVal = WriteFile( m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1, &uiWriteLength, NULL );
00384 if (iRetVal == 0)
00385 {
00386
00387 void* lpMsgBuf;
00388 FormatMessage(
00389 FORMAT_MESSAGE_ALLOCATE_BUFFER |
00390 FORMAT_MESSAGE_FROM_SYSTEM |
00391 FORMAT_MESSAGE_IGNORE_INSERTS,
00392 NULL,
00393 GetLastError(),
00394 MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
00395 (LPTSTR) &lpMsgBuf,
00396 0,
00397 NULL
00398 );
00399 debug(1,"COMERROR:%s\n",lpMsgBuf);
00400 warning( "Transmission Error. Sent %ld bytes instead of &ld: \n", uiWriteLength, uiWriteBufferIndex+1 );
00401 ClearCommError( m_hDevice, &iErrorCode, NULL );
00402 m_iErrorState = ERRID_DEV_WRITEERROR;
00403 return m_iErrorState;
00404 }
00405
00406 if( uiWriteLength != uiWriteBufferIndex+1 )
00407 { warning( "Transmission Error. Sent %ld bytes instead of &ld: \n", uiWriteLength, uiWriteBufferIndex+1 );
00408 m_iErrorState = ERRID_DEV_WRITEERROR;
00409 return m_iErrorState;
00410 }
00411 #endif
00412
00413 #if defined(__QNX__)
00414 tcflush( m_hDevice, TCIOFLUSH );
00415
00416 uiWriteLength = write(m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1);
00417 if( uiWriteLength != uiWriteBufferIndex+1 )
00418 { warning( "Transmission Error %d. Sent %ld bytes instead of %ld.\n", errno, uiWriteLength, uiWriteBufferIndex+1 );
00419 m_iErrorState = ERRID_DEV_WRITEERROR;
00420 return m_iErrorState;
00421 }
00422 tcdrain( m_hDevice );
00423 #endif
00424
00425 #if defined(__LINUX__)
00426 tcflush( m_hDevice, TCIOFLUSH );
00427
00428 uiWriteLength = write(m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1);
00429 if( uiWriteLength != uiWriteBufferIndex+1 )
00430 { warning( "Transmission Error. Sent %ld bytes instead of %ld.\n", uiWriteLength, uiWriteBufferIndex+1 );
00431 m_iErrorState = ERRID_DEV_WRITEERROR;
00432 return m_iErrorState;
00433 }
00434 tcdrain( m_hDevice );
00435 #endif
00436
00437 return m_iErrorState;
00438 }
00439
00440
00441
00442
00443
00444
00445
00446 CRS232Device::CRS232Device() : m_hDevice(0), m_iDeviceId(-1), m_uiBaudRate(0), m_uiTimeOut(30), m_clTimer(util_REAL_TIME)
00447 {
00448 initMessage("CRS232Device", g_iDebugLevel, g_bDebug, g_bDebugFile);
00449 }
00450
00451 CRS232Device::CRS232Device(const CRS232Device& rclRS232Device)
00452 {
00453 error(-1, "Sorry constructor is not implemented");
00454 }
00455
00456 CRS232Device::~CRS232Device()
00457 {
00458 exit();
00459 }
00460
00461
00462
00463
00464
00465
00466
00467 CRS232Device& CRS232Device::operator=(const CRS232Device& rclRS232Device)
00468 {
00469 error(-1, "Sorry operator= is not implemented");
00470 return *this;
00471 }
00472
00473
00474
00475
00476
00477
00478
00479
00480
00481
00482
00483
00484
00485 void CRS232Device::setTimeOut(unsigned long uiTimeOut)
00486 {
00487 m_uiTimeOut= uiTimeOut;
00488 }
00489
00490
00491
00492
00493
00494
00495
00496
00497
00498
00499
00500
00501
00502 int CRS232Device::init()
00503 {
00504 return init(m_acInitString);
00505 }
00506
00507 int CRS232Device::init(const char* acInitString)
00508 {
00509 InitializeCriticalSection(&m_csDevice);
00510 char* pcToken;
00511 char acString[128];
00512 char acDevice[128];
00513 if(m_bInitFlag)
00514 {
00515 warning("device already initialized");
00516 m_iErrorState = ERRID_DEV_ISINITIALIZED;
00517 return m_iErrorState;
00518 }
00519 m_iDeviceId = -1;
00520 m_iErrorState = 0;
00521 strncpy(m_acInitString,acInitString,128);
00522 strncpy(acString,acInitString,128);
00523
00524 pcToken = strtok( acString, ":" );
00525 if( !pcToken )
00526 { m_iErrorState = ERRID_DEV_BADINITSTRING;
00527 return m_iErrorState;
00528 }
00529 if( strcmp( pcToken, "RS232" ) != 0 )
00530 { m_iErrorState = ERRID_DEV_BADINITSTRING;
00531 return m_iErrorState;
00532 }
00533
00534 pcToken = strtok( NULL, "," );
00535 if( !pcToken )
00536 { m_iErrorState = ERRID_DEV_BADINITSTRING;
00537 return m_iErrorState;
00538 }
00539 m_iDeviceId = atoi(pcToken);
00540
00541 pcToken = strtok( NULL, "," );
00542 if( !pcToken )
00543 { m_iErrorState = ERRID_DEV_BADINITSTRING;
00544 return m_iErrorState;
00545 }
00546 m_iBaudRate = atoi(pcToken);
00547
00548 #if defined(_WIN32)
00549 COMMTIMEOUTS commtimeouts;
00550 DCB dcb;
00551 sprintf( acDevice, "COM%d", m_iDeviceId );
00552 m_hDevice = CreateFile( acDevice, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL );
00553 if( m_hDevice == INVALID_HANDLE_VALUE )
00554 { warning( "Could not initialize %s\n", acDevice );
00555 m_iErrorState = ERRID_DEV_INITERROR;
00556 return m_iErrorState;
00557 }
00558
00559 if( !GetCommState( m_hDevice, &dcb ) )
00560 { warning( "GetCommState-Error %d\n", GetLastError() );
00561 m_iErrorState = ERRID_DEV_INITERROR;
00562 return m_iErrorState;
00563 }
00564
00565 switch( m_iBaudRate )
00566 {
00567 case 1200:
00568 dcb.BaudRate = CBR_1200;
00569 break;
00570 case 2400:
00571 dcb.BaudRate = CBR_2400;
00572 break;
00573 case 4800:
00574 dcb.BaudRate = CBR_4800;
00575 break;
00576 case 9600:
00577 dcb.BaudRate = CBR_9600;
00578 break;
00579 case 19200:
00580 dcb.BaudRate = CBR_19200;
00581 break;
00582 case 38400:
00583 dcb.BaudRate = CBR_38400;
00584 break;
00585 case 57600:
00586 dcb.BaudRate = CBR_57600;
00587 break;
00588 case 115200:
00589 dcb.BaudRate = CBR_115200;
00590 break;
00591 default:
00592 dcb.BaudRate = CBR_9600;
00593 break;
00594 }
00595
00596 dcb.ByteSize = 8;
00597 dcb.StopBits = ONESTOPBIT;
00598 dcb.Parity = NOPARITY;
00599 dcb.fRtsControl = RTS_CONTROL_DISABLE;
00600 dcb.fDtrControl = DTR_CONTROL_HANDSHAKE;
00601
00602 if( !SetCommState( m_hDevice, &dcb) )
00603 { warning( "SetCommState-Error %d\n", GetLastError() );
00604 m_iErrorState = ERRID_DEV_INITERROR;
00605 return m_iErrorState;
00606 }
00607 commtimeouts.ReadIntervalTimeout = 0;
00608 commtimeouts.ReadTotalTimeoutMultiplier = 0;
00609 commtimeouts.ReadTotalTimeoutConstant = m_uiTimeOut;
00610 commtimeouts.WriteTotalTimeoutMultiplier = 0;
00611 commtimeouts.WriteTotalTimeoutConstant = m_uiTimeOut;
00612 SetCommTimeouts(m_hDevice,&commtimeouts);
00613
00614 #endif
00615
00616 #if defined(__QNX__)
00617 sprintf(acDevice,"/dev/ser%d",m_iDeviceId);
00618 m_hDevice = open(acDevice, O_RDWR|O_NONBLOCK );
00619 if( m_hDevice <=0 )
00620 { warning( "Could not initialize %s\n", acDevice );
00621 m_iErrorState = ERRID_DEV_INITERROR;
00622 return m_iErrorState;
00623 }
00624
00625 struct termios clPortOptions;
00626 tcgetattr(m_hDevice, &clPortOptions);
00627
00628 switch( m_iBaudRate )
00629 {
00630 case 1200:
00631 cfsetispeed(&clPortOptions, B1200);
00632 cfsetospeed(&clPortOptions, B1200);
00633 break;
00634 case 2400:
00635 cfsetispeed(&clPortOptions, B2400);
00636 cfsetospeed(&clPortOptions, B2400);
00637 break;
00638 case 4800:
00639 cfsetispeed(&clPortOptions, B4800);
00640 cfsetospeed(&clPortOptions, B4800);
00641 break;
00642 case 9600:
00643 cfsetispeed(&clPortOptions, B9600);
00644 cfsetospeed(&clPortOptions, B9600);
00645 break;
00646 case 19200:
00647 cfsetispeed(&clPortOptions, B19200);
00648 cfsetospeed(&clPortOptions, B19200);
00649 break;
00650 case 38400:
00651 cfsetispeed(&clPortOptions, B38400);
00652 cfsetospeed(&clPortOptions, B38400);
00653 break;
00654 case 57600:
00655 cfsetispeed(&clPortOptions, B57600);
00656 cfsetospeed(&clPortOptions, B57600);
00657 break;
00658 case 115200:
00659 cfsetispeed(&clPortOptions, B115200);
00660 cfsetospeed(&clPortOptions, B115200);
00661 break;
00662 default:
00663 cfsetispeed(&clPortOptions, B9600);
00664 cfsetospeed(&clPortOptions, B9600);
00665 break;
00666 }
00667
00668 clPortOptions.c_cflag |= CREAD|CS8;
00669 clPortOptions.c_lflag = 0;
00670 if( tcsetattr(m_hDevice, TCSANOW, &clPortOptions) != 0 )
00671 { warning( "open: Could not set attributes\n" );
00672 m_iErrorState = ERRID_DEV_INITERROR;
00673 return m_iErrorState;
00674 }
00675
00676 #endif
00677
00678 #if defined(__LINUX__)
00679 sprintf(acDevice,"/dev/ttyS%d",m_iDeviceId-1);
00680 m_hDevice = open( acDevice, O_RDWR );
00681 if( m_hDevice == -1 )
00682 { warning( "open: Could not initialize %s\n", acDevice );
00683 m_iErrorState = ERRID_DEV_INITERROR;
00684 return m_iErrorState;
00685 }
00686
00687 struct termios clPortOptions;
00688 tcgetattr(m_hDevice, &clPortOptions);
00689
00690 switch( m_iBaudRate )
00691 {
00692 case 1200:
00693 cfsetispeed(&clPortOptions, B1200);
00694 cfsetospeed(&clPortOptions, B1200);
00695 break;
00696 case 2400:
00697 cfsetispeed(&clPortOptions, B2400);
00698 cfsetospeed(&clPortOptions, B2400);
00699 break;
00700 case 4800:
00701 cfsetispeed(&clPortOptions, B4800);
00702 cfsetospeed(&clPortOptions, B4800);
00703 break;
00704 case 9600:
00705 cfsetispeed(&clPortOptions, B9600);
00706 cfsetospeed(&clPortOptions, B9600);
00707 break;
00708 case 19200:
00709 cfsetispeed(&clPortOptions, B19200);
00710 cfsetospeed(&clPortOptions, B19200);
00711 break;
00712 case 38400:
00713 cfsetispeed(&clPortOptions, B38400);
00714 cfsetospeed(&clPortOptions, B38400);
00715 break;
00716 case 57600:
00717 cfsetispeed(&clPortOptions, B57600);
00718 cfsetospeed(&clPortOptions, B57600);
00719 break;
00720 case 115200:
00721 cfsetispeed(&clPortOptions, B115200);
00722 cfsetospeed(&clPortOptions, B115200);
00723 break;
00724 default:
00725 cfsetispeed(&clPortOptions, B9600);
00726 cfsetospeed(&clPortOptions, B9600);
00727 break;
00728 }
00729
00730 clPortOptions.c_iflag = 0;
00731 clPortOptions.c_oflag = 0;
00732 clPortOptions.c_cflag |= CLOCAL|CREAD|CS8|CSIZE;
00733 clPortOptions.c_lflag = 0;
00734 if( tcsetattr(m_hDevice, TCSANOW, &clPortOptions) != 0 )
00735 { warning( "open: Could not set attributes\n" );
00736 m_iErrorState = ERRID_DEV_INITERROR;
00737 return m_iErrorState;
00738 }
00739 #endif
00740
00741 m_iErrorState = clearReadQueue();
00742 if(m_iErrorState != 0)
00743 return m_iErrorState;
00744
00745 if(m_iErrorState == 0)
00746 m_bInitFlag = true;
00747 updateModuleIdMap();
00748 return m_iErrorState;
00749 }
00750
00751 int CRS232Device::exit()
00752 {
00753 m_iErrorState = 0;
00754 if(!m_bInitFlag)
00755 {
00756 warning("device not initialized");
00757 m_iErrorState = ERRID_DEV_NOTINITIALIZED;
00758 return m_iErrorState;
00759 }
00760 EnterCriticalSection(&m_csDevice);
00761 #if defined(_WIN32)
00762 if( !CloseHandle( m_hDevice ) )
00763 {
00764 warning( "Error closing Device.\n" );
00765 m_iErrorState = ERRID_DEV_EXITERROR;
00766 return m_iErrorState;
00767 }
00768 #endif
00769
00770 #if defined(__QNX__)
00771 if( close(m_hDevice) < 0 )
00772 { warning( "Error closing Device.\n" );
00773 m_iErrorState = ERRID_DEV_EXITERROR;
00774 return m_iErrorState;
00775 }
00776 #endif
00777
00778 #if defined(__LINUX__)
00779 if( close(m_hDevice) < 0 )
00780 { warning( "Error closing Device.\n" );
00781 m_iErrorState = ERRID_DEV_EXITERROR;
00782 return m_iErrorState;
00783 }
00784 #endif
00785
00786 m_bInitFlag = false;
00787 LeaveCriticalSection(&m_csDevice);
00788 DeleteCriticalSection(&m_csDevice);
00789 return m_iErrorState;
00790 }