21 #if defined(__LINUX__) 31 #define RSID_SENDDAT 0x04 32 #define RSID_RECVDAT 0x08 81 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};
82 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};
84 unsigned char aucDecodeBuffer[11] = {0,0,0,0,0,0,0,0,0,0,0};
85 unsigned char ucMessageLength = 0;
88 unsigned int uiMessageBufferIndex = 0;
89 unsigned int uiReadBufferIndex = 0;
92 bool bMessageComplete =
false;
93 bool bDecodeError =
false;
98 DWORD iReadLength = 0;
103 iRetVal = ReadFile( m_hDevice, &ucChar, 1, &iReadLength, NULL );
108 FORMAT_MESSAGE_ALLOCATE_BUFFER |
109 FORMAT_MESSAGE_FROM_SYSTEM |
110 FORMAT_MESSAGE_IGNORE_INSERTS,
113 MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
118 debug(1,
"COMERROR:%s\n",lpMsgBuf);
119 warning(
"Receive Error. ReadFile failed.\n" );
120 ClearCommError( m_hDevice, &iErrorCode, NULL );
124 if( iReadLength == 1 )
126 aucReadBuffer[uiReadBufferIndex++] = ucChar;
135 warning(
"Receive Error. Timeout %f. %d bytes received.\n", fTime, uiReadBufferIndex);
144 struct timeval clTimeout;
149 ssize_t bytesRead = 0;
152 FD_ZERO( &fdReadSet );
153 FD_SET( m_hDevice, &fdReadSet );
155 iRetVal=select( FD_SETSIZE, &fdReadSet, NULL, NULL, &clTimeout );
158 warning(
"Receive Error in select");
161 else if (iRetVal>0 && FD_ISSET(m_hDevice,&fdReadSet))
163 bytesRead = read( m_hDevice, &ucChar, 1 );
165 {
warning(
"Receive Error. Read error.\n" );
169 else if( bytesRead == 1 )
171 aucReadBuffer[uiReadBufferIndex++] = ucChar;
175 else if( bytesRead == 0 )
177 warning(
"Receive Error. Timeout\n");
186 warning(
"Receive Error. Timeout. %d bytes received.\n", uiReadBufferIndex );
194 #if defined(__LINUX__) 195 ssize_t bytesRead = 0;
196 struct timeval clTimeout;
204 FD_ZERO( &fdReadSet );
205 FD_SET( m_hDevice, &fdReadSet );
207 iRetVal=select( FD_SETSIZE, &fdReadSet, NULL, NULL, &clTimeout );
210 warning(
"Receive Error in select");
213 else if (iRetVal>0 && FD_ISSET(m_hDevice,&fdReadSet))
215 bytesRead = read( m_hDevice, &ucChar, 1 );
217 {
warning(
"Receive Error. Read error.\n" );
221 else if( bytesRead == 1 )
223 aucReadBuffer[uiReadBufferIndex++] = ucChar;
227 else if( bytesRead == 0 )
229 warning(
"Receive Error. Timeout\n");
238 warning(
"Receive Error. Timeout. %d bytes received.\n", uiReadBufferIndex );
246 for( i = 0; i < uiReadBufferIndex; i++ )
248 if( aucReadBuffer[i] ==
STX )
250 uiMessageBufferIndex = 0;
251 bMessageComplete =
false;
253 if( aucReadBuffer[i] ==
ETX )
254 bMessageComplete =
true;
255 if( uiMessageBufferIndex > 22 )
257 uiMessageBufferIndex = 0;
258 bMessageComplete =
false;
259 warning(
"More than 22 bytes!" );
261 aucMessageBuffer[uiMessageBufferIndex] = aucReadBuffer[i];
262 uiMessageBufferIndex++;
265 if( bMessageComplete )
267 if( (aucMessageBuffer[0] ==
STX) && (aucMessageBuffer[uiMessageBufferIndex-1] ==
ETX) )
269 for( i = 1; i < uiMessageBufferIndex-1; i++ )
271 if( aucMessageBuffer[i] ==
DLE )
274 aucDecodeBuffer[k] = aucMessageBuffer[i] - 0x80;
276 else if( aucMessageBuffer[i] ==
ETX || aucMessageBuffer[i] ==
STX )
282 aucDecodeBuffer[k] = aucMessageBuffer[i];
288 warning(
"Receive Error: STX/ETX framing incorrect.\n" );
294 ucMessageLength = aucDecodeBuffer[1] & 0x0F;
299 if( ucMessageLength == k-3 )
302 rclProtocolMessage.
m_iModuleId = (((aucDecodeBuffer[0]&0x03)<<3)+((aucDecodeBuffer[1]&0xE0)>>5));
303 for( i = 0; i < ucMessageLength; i++ )
309 warning(
"Receive Error: Length incorrect received %d instead of %d\n", k-3, ucMessageLength );
314 warning(
"Receive Error: STX/ETX inside message.\n" );
319 warning(
"Receive Error: MessageId incorrect.\n" );
324 warning(
"Receive Error: ETX not received.\n" );
332 unsigned int uiWriteBufferIndex = 0;
333 unsigned long uiWriteLength = 0;
334 unsigned char aucWriteBuffer[24];
335 unsigned short uiSum = 0;
336 unsigned char aucEncodeBuffer[11] = {0,0,0,0,0,0,0,0,0,0,0};
354 uiSum += aucEncodeBuffer[i];
357 aucWriteBuffer[0] =
STX;
358 uiWriteBufferIndex = 1;
362 if( aucEncodeBuffer[i] ==
DLE || aucEncodeBuffer[i] ==
STX || aucEncodeBuffer[i] ==
ETX )
364 aucWriteBuffer[uiWriteBufferIndex] =
DLE;
365 uiWriteBufferIndex++;
366 aucWriteBuffer[uiWriteBufferIndex] = aucEncodeBuffer[i] + 0x80;
369 aucWriteBuffer[uiWriteBufferIndex] = aucEncodeBuffer[i];
370 uiWriteBufferIndex++;
373 aucWriteBuffer[uiWriteBufferIndex] =
ETX;
378 PurgeComm( m_hDevice, PURGE_TXABORT );
379 PurgeComm( m_hDevice, PURGE_RXABORT );
380 PurgeComm( m_hDevice, PURGE_TXCLEAR );
381 PurgeComm( m_hDevice, PURGE_RXCLEAR );
383 iRetVal = WriteFile( m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1, &uiWriteLength, NULL );
389 FORMAT_MESSAGE_ALLOCATE_BUFFER |
390 FORMAT_MESSAGE_FROM_SYSTEM |
391 FORMAT_MESSAGE_IGNORE_INSERTS,
394 MAKELANGID(LANG_NEUTRAL, SUBLANG_DEFAULT),
399 debug(1,
"COMERROR:%s\n",lpMsgBuf);
400 warning(
"Transmission Error. Sent %ld bytes instead of &ld: \n", uiWriteLength, uiWriteBufferIndex+1 );
401 ClearCommError( m_hDevice, &iErrorCode, NULL );
406 if( uiWriteLength != uiWriteBufferIndex+1 )
407 {
warning(
"Transmission Error. Sent %ld bytes instead of &ld: \n", uiWriteLength, uiWriteBufferIndex+1 );
414 tcflush( m_hDevice, TCIOFLUSH );
416 uiWriteLength = write(m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1);
417 if( uiWriteLength != uiWriteBufferIndex+1 )
418 {
warning(
"Transmission Error %d. Sent %ld bytes instead of %ld.\n", errno, uiWriteLength, uiWriteBufferIndex+1 );
422 tcdrain( m_hDevice );
425 #if defined(__LINUX__) 426 tcflush( m_hDevice, TCIOFLUSH );
428 uiWriteLength = write(m_hDevice, aucWriteBuffer, uiWriteBufferIndex+1);
429 if( uiWriteLength != uiWriteBufferIndex+1 )
430 {
warning(
"Transmission Error. Sent %ld bytes instead of %ld.\n", uiWriteLength, uiWriteBufferIndex+1 );
434 tcdrain( m_hDevice );
453 error(-1,
"Sorry constructor is not implemented");
469 error(-1,
"Sorry operator= is not implemented");
515 warning(
"device already initialized");
522 strncpy(acString,acInitString,128);
524 pcToken = strtok( acString,
":" );
529 if( strcmp( pcToken,
"RS232" ) != 0 )
534 pcToken = strtok( NULL,
"," );
541 pcToken = strtok( NULL,
"," );
549 COMMTIMEOUTS commtimeouts;
552 m_hDevice = CreateFile( acDevice, GENERIC_READ | GENERIC_WRITE, 0, NULL, OPEN_EXISTING, 0, NULL );
553 if( m_hDevice == INVALID_HANDLE_VALUE )
554 {
warning(
"Could not initialize %s\n", acDevice );
559 if( !GetCommState( m_hDevice, &dcb ) )
560 {
warning(
"GetCommState-Error %d\n", GetLastError() );
568 dcb.BaudRate = CBR_1200;
571 dcb.BaudRate = CBR_2400;
574 dcb.BaudRate = CBR_4800;
577 dcb.BaudRate = CBR_9600;
580 dcb.BaudRate = CBR_19200;
583 dcb.BaudRate = CBR_38400;
586 dcb.BaudRate = CBR_57600;
589 dcb.BaudRate = CBR_115200;
592 dcb.BaudRate = CBR_9600;
597 dcb.StopBits = ONESTOPBIT;
598 dcb.Parity = NOPARITY;
599 dcb.fRtsControl = RTS_CONTROL_DISABLE;
600 dcb.fDtrControl = DTR_CONTROL_HANDSHAKE;
602 if( !SetCommState( m_hDevice, &dcb) )
603 {
warning(
"SetCommState-Error %d\n", GetLastError() );
607 commtimeouts.ReadIntervalTimeout = 0;
608 commtimeouts.ReadTotalTimeoutMultiplier = 0;
609 commtimeouts.ReadTotalTimeoutConstant =
m_uiTimeOut;
610 commtimeouts.WriteTotalTimeoutMultiplier = 0;
611 commtimeouts.WriteTotalTimeoutConstant =
m_uiTimeOut;
612 SetCommTimeouts(m_hDevice,&commtimeouts);
618 m_hDevice = open(acDevice, O_RDWR|O_NONBLOCK );
620 {
warning(
"Could not initialize %s\n", acDevice );
625 struct termios clPortOptions;
626 tcgetattr(m_hDevice, &clPortOptions);
631 cfsetispeed(&clPortOptions, B1200);
632 cfsetospeed(&clPortOptions, B1200);
635 cfsetispeed(&clPortOptions, B2400);
636 cfsetospeed(&clPortOptions, B2400);
639 cfsetispeed(&clPortOptions, B4800);
640 cfsetospeed(&clPortOptions, B4800);
643 cfsetispeed(&clPortOptions, B9600);
644 cfsetospeed(&clPortOptions, B9600);
647 cfsetispeed(&clPortOptions, B19200);
648 cfsetospeed(&clPortOptions, B19200);
651 cfsetispeed(&clPortOptions, B38400);
652 cfsetospeed(&clPortOptions, B38400);
655 cfsetispeed(&clPortOptions, B57600);
656 cfsetospeed(&clPortOptions, B57600);
659 cfsetispeed(&clPortOptions, B115200);
660 cfsetospeed(&clPortOptions, B115200);
663 cfsetispeed(&clPortOptions, B9600);
664 cfsetospeed(&clPortOptions, B9600);
668 clPortOptions.c_cflag |= CREAD|CS8;
669 clPortOptions.c_lflag = 0;
670 if( tcsetattr(m_hDevice, TCSANOW, &clPortOptions) != 0 )
671 {
warning(
"open: Could not set attributes\n" );
678 #if defined(__LINUX__) 680 m_hDevice = open( acDevice, O_RDWR );
681 if( m_hDevice == -1 )
682 {
warning(
"open: Could not initialize %s\n", acDevice );
687 struct termios clPortOptions;
688 tcgetattr(m_hDevice, &clPortOptions);
693 cfsetispeed(&clPortOptions, B1200);
694 cfsetospeed(&clPortOptions, B1200);
697 cfsetispeed(&clPortOptions, B2400);
698 cfsetospeed(&clPortOptions, B2400);
701 cfsetispeed(&clPortOptions, B4800);
702 cfsetospeed(&clPortOptions, B4800);
705 cfsetispeed(&clPortOptions, B9600);
706 cfsetospeed(&clPortOptions, B9600);
709 cfsetispeed(&clPortOptions, B19200);
710 cfsetospeed(&clPortOptions, B19200);
713 cfsetispeed(&clPortOptions, B38400);
714 cfsetospeed(&clPortOptions, B38400);
717 cfsetispeed(&clPortOptions, B57600);
718 cfsetospeed(&clPortOptions, B57600);
721 cfsetispeed(&clPortOptions, B115200);
722 cfsetospeed(&clPortOptions, B115200);
725 cfsetispeed(&clPortOptions, B9600);
726 cfsetospeed(&clPortOptions, B9600);
730 clPortOptions.c_iflag = 0;
731 clPortOptions.c_oflag = 0;
732 clPortOptions.c_cflag |= CLOCAL|CREAD|CS8|CSIZE;
733 clPortOptions.c_lflag = 0;
734 if( tcsetattr(m_hDevice, TCSANOW, &clPortOptions) != 0 )
735 {
warning(
"open: Could not set attributes\n" );
756 warning(
"device not initialized");
762 if( !CloseHandle( m_hDevice ) )
764 warning(
"Error closing Device.\n" );
771 if( close(m_hDevice) < 0 )
772 {
warning(
"Error closing Device.\n" );
778 #if defined(__LINUX__) 779 if( close(m_hDevice) < 0 )
780 {
warning(
"Error closing Device.\n" );
#define ERRID_DEV_BADINITSTRING
int writeDevice(CProtocolMessage &rclProtocolMessage)
unsigned long m_uiTimeOut
#define ERRID_IO_READERROR
unsigned char m_aucMessageData[8]
int initMessage(const char *pcClassName, int iDebuglevel=0, bool bDebug=true, bool bDebugFile=false)
unsigned char m_aucMessageId[2]
CRITICAL_SECTION m_csDevice
int readDevice(CProtocolMessage &rclProtocolMessage)
#define ERRID_DEV_ISINITIALIZED
void error(const int iErrorCode, const char *pcErrorMessage,...) const
#define ERRID_DEV_WRITEERROR
int reinit(unsigned char ucBaudRateId)
CRS232Device()
default constructor
#define ERRID_DEV_NOTINITIALIZED
#define ERRID_DEV_READTIMEOUT
unsigned char m_ucMessageLength
int getDeviceError(int iErrorState)
unsigned long m_uiMessageId
int setMessageId(unsigned long uiMessageId)
void setTimeOut(unsigned long uiTimeOut)
void warning(const char *pcWarningMessage,...) const
#define ERRID_DEV_INITERROR
virtual ~CRS232Device()
destructor
#define ERRID_DEV_EXITERROR
void debug(const int iDebugLevel, const char *pcDebugMessage,...) const
unsigned char m_ucMessageLength
CRS232Device & operator=(const CRS232Device &rclRS232Device)
unsigned long m_uiBaudRate
#define ERRID_DEV_READERROR
unsigned char m_aucMessageData[8]