00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043
00044
00045
00046
00047
00048
00049
00050
00051
00052
00053
00054
00055 #include <math.h>
00056 #include <cob_relayboard/SerRelayBoard.h>
00057
00058
00059
00060
00061
00062
00063 #define RS422_BAUDRATE 420000
00064 #define RS422_RX_BUFFERSIZE 1024
00065 #define RS422_TX_BUFFERSIZE 1024
00066
00067 #define RS422_TIMEOUT 0.025
00068
00069 #define NUM_BYTE_REC_MAX 120
00070 #define NUM_BYTE_REC_HEADER 4 //Header bytes, which are used to identify the beginning of a new received message {0x02, 0x80, 0xD6, 0x02}
00071 #define NUM_BYTE_REC_CHECKSUM 2 //checksum for message, that is built as the sum of all data bytes contained in the message
00072 #define NUM_BYTE_REC 104 //Total amount of data bytes in a received message (from the relayboard)
00073
00074
00075
00076 SerRelayBoard::SerRelayBoard(std::string ComPort, int ProtocolVersion)
00077 {
00078 m_iProtocolVersion = ProtocolVersion;
00079 if(m_iProtocolVersion == 1)
00080 m_NUM_BYTE_SEND = 50;
00081 else if(m_iProtocolVersion == 2)
00082 m_NUM_BYTE_SEND = 79;
00083 else
00084 m_NUM_BYTE_SEND = 50;
00085
00086 m_bComInit = false;
00087 m_sNumComPort = ComPort;
00088
00089 m_iRelBoardBattVoltage = 0;
00090 m_iConfigRelayBoard = 0;
00091 m_iRelBoardKeyPad = 0xFFFF;
00092 m_iCmdRelayBoard = 0;
00093 m_iDigIn = 0;
00094 }
00095
00096
00097 SerRelayBoard::~SerRelayBoard()
00098 {
00099 m_SerIO.close();
00100 }
00101
00102
00103 int SerRelayBoard::evalRxBuffer()
00104 {
00105 static int siNoMsgCnt = 0;
00106
00107 const int c_iNrBytesMin = NUM_BYTE_REC_HEADER + NUM_BYTE_REC + NUM_BYTE_REC_CHECKSUM;
00108 const int c_iSizeBuffer = 4096;
00109
00110 int i;
00111 int errorFlag = NO_ERROR;
00112 int iNrBytesInQueue, iNrBytesRead, iDataStart;
00113 unsigned char cDat[c_iSizeBuffer];
00114 unsigned char cTest[4] = {0x02, 0x80, 0xD6, 0x02};
00115
00116 if( !m_bComInit ) return NOT_INITIALIZED;
00117
00118
00119 iNrBytesInQueue = m_SerIO.getSizeRXQueue();
00120 if(iNrBytesInQueue < c_iNrBytesMin)
00121 {
00122
00123 siNoMsgCnt++;
00124 if(siNoMsgCnt > 29)
00125 {
00126
00127 siNoMsgCnt = 0;
00128 errorFlag = NO_MESSAGES;
00129 } else errorFlag = TOO_LESS_BYTES_IN_QUEUE;
00130
00131 return errorFlag;
00132 }
00133 else
00134 {
00135 siNoMsgCnt = 0;
00136 }
00137
00138
00139 iNrBytesRead = m_SerIO.readBlocking((char*)&cDat[0], iNrBytesInQueue);
00140 for(i = (iNrBytesRead - c_iNrBytesMin); i >= 0 ; i--)
00141 {
00142
00143 if((cDat[i] == cTest[0]) && (cDat[i+1] == cTest[1]) && (cDat[i+2] == cTest[2]) && (cDat[i+3] == cTest[3]))
00144 {
00145 iDataStart = i + 4;
00146
00147
00148 if( convRecMsgToData(&cDat[iDataStart]) )
00149 {
00150 return errorFlag;
00151 }
00152 else
00153 {
00154
00155 errorFlag = CHECKSUM_ERROR;
00156 return errorFlag;
00157 }
00158 }
00159 }
00160
00161 return errorFlag;
00162 }
00163
00164
00165 bool SerRelayBoard::init()
00166 {
00167 int iRet;
00168
00169 m_SerIO.setBaudRate(RS422_BAUDRATE);
00170 m_SerIO.setDeviceName( m_sNumComPort.c_str() );
00171 m_SerIO.setBufferSize(RS422_RX_BUFFERSIZE, RS422_TX_BUFFERSIZE);
00172 m_SerIO.setTimeout(RS422_TIMEOUT);
00173
00174 iRet = m_SerIO.open();
00175
00176 m_bComInit = true;
00177
00178 return true;
00179 }
00180
00181
00182 bool SerRelayBoard::reset()
00183 {
00184 m_SerIO.close();
00185 m_bComInit = false;
00186
00187 init();
00188
00189 return true;
00190 }
00191
00192
00193 bool SerRelayBoard::shutdown()
00194 {
00195 m_SerIO.close();
00196
00197 m_bComInit = false;
00198
00199 return true;
00200 }
00201
00202
00203
00204 bool SerRelayBoard::isEMStop()
00205 {
00206 if( (m_iRelBoardStatus & 0x0001) != 0)
00207 {
00208 return true;
00209 }
00210 else
00211 {
00212 return false;
00213 }
00214 }
00215
00216
00217 bool SerRelayBoard::isScannerStop()
00218 {
00219 if( (m_iRelBoardStatus & 0x0002) != 0)
00220 {
00221 return true;
00222 }
00223 else
00224 {
00225 return false;
00226 }
00227 }
00228
00229
00230 int SerRelayBoard::sendRequest() {
00231 int errorFlag = NO_ERROR;
00232 int iNrBytesWritten;
00233
00234 unsigned char cMsg[m_NUM_BYTE_SEND];
00235
00236 m_Mutex.lock();
00237
00238 convDataToSendMsg(cMsg);
00239
00240 m_SerIO.purgeTx();
00241
00242 iNrBytesWritten = m_SerIO.write((char*)cMsg, m_NUM_BYTE_SEND);
00243
00244 if(iNrBytesWritten < m_NUM_BYTE_SEND) {
00245
00246 errorFlag = GENERAL_SENDING_ERROR;
00247 }
00248
00249 m_Mutex.unlock();
00250
00251 return errorFlag;
00252 }
00253
00254 int SerRelayBoard::setDigOut(int iChannel, bool bOn)
00255 {
00256 switch( iChannel)
00257 {
00258 case 0:
00259
00260 if(bOn) { m_iCmdRelayBoard |= CMD_SET_CHARGE_RELAY; }
00261 else { m_iCmdRelayBoard &= ~CMD_SET_CHARGE_RELAY; }
00262
00263 break;
00264
00265 case 1:
00266
00267 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY1; }
00268 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY1; }
00269
00270 break;
00271
00272 case 2:
00273
00274 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY2; }
00275 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY2; }
00276
00277 break;
00278
00279 case 3:
00280
00281 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY3; }
00282 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY3; }
00283
00284 break;
00285
00286 case 4:
00287
00288 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY4; }
00289 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY4; }
00290
00291 break;
00292
00293 case 5:
00294
00295 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY5; }
00296 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY5; }
00297
00298 break;
00299
00300 case 6:
00301
00302 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY6; }
00303 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY6; }
00304
00305 break;
00306
00307 default:
00308
00309 return -1;
00310 }
00311
00312 return 0;
00313 }
00314
00315 int SerRelayBoard::getAnalogIn(int* piAnalogIn)
00316 {
00317 piAnalogIn[0] = m_iChargeCurrent;
00318 piAnalogIn[1] = m_iRelBoardBattVoltage;
00319 piAnalogIn[2] = m_iRelBoardTempSensor;
00320 piAnalogIn[3] = m_iRelBoardKeyPad;
00321 piAnalogIn[4] = m_iRelBoardAnalogIn[0];
00322 piAnalogIn[5] = m_iRelBoardAnalogIn[1];
00323 piAnalogIn[6] = m_iRelBoardAnalogIn[2];
00324 piAnalogIn[7] = m_iRelBoardAnalogIn[3];
00325
00326 return 0;
00327 }
00328
00329
00330 int SerRelayBoard::getDigIn()
00331 {
00332 return m_iDigIn;
00333 }
00334
00335
00336 void SerRelayBoard::convDataToSendMsg(unsigned char cMsg[])
00337 {
00338 int i;
00339 int iCnt = 0;
00340 int iChkSum = 0;
00341
00342 cMsg[iCnt++] = 1;
00343
00344 cMsg[iCnt++] = m_iConfigRelayBoard >> 8;
00345 cMsg[iCnt++] = m_iConfigRelayBoard;
00346
00347 cMsg[iCnt++] = m_iCmdRelayBoard >> 8;
00348 cMsg[iCnt++] = m_iCmdRelayBoard;
00349
00350
00351 do
00352 {
00353 cMsg[iCnt++] = 0;
00354 }
00355 while(iCnt < (m_NUM_BYTE_SEND - 2));
00356
00357
00358 for(i = 0; i < (m_NUM_BYTE_SEND - 2); i++)
00359 {
00360 iChkSum += cMsg[i];
00361 }
00362
00363 cMsg[m_NUM_BYTE_SEND - 2] = iChkSum >> 8;
00364 cMsg[m_NUM_BYTE_SEND - 1] = iChkSum;
00365
00366
00367 m_iCmdRelayBoard &= ~CMD_RESET_POS_CNT;
00368 }
00369
00370
00371 bool SerRelayBoard::convRecMsgToData(unsigned char cMsg[])
00372 {
00373 const int c_iStartCheckSum = NUM_BYTE_REC;
00374
00375 int i;
00376 unsigned int iTxCheckSum;
00377 unsigned int iCheckSum;
00378
00379 m_Mutex.lock();
00380
00381
00382 iTxCheckSum = (cMsg[c_iStartCheckSum + 1] << 8) | cMsg[c_iStartCheckSum];
00383
00384 iCheckSum = 0;
00385 for(i = 0; i < c_iStartCheckSum; i++)
00386 {
00387 iCheckSum += cMsg[i];
00388 }
00389
00390 if(iCheckSum != iTxCheckSum)
00391 {
00392 return false;
00393 }
00394
00395
00396 int iCnt = 0;
00397
00398
00399 m_iRelBoardStatus = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00400 iCnt += 2;
00401
00402
00403 m_iChargeCurrent = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00404 iCnt += 2;
00405
00406
00407 m_iRelBoardBattVoltage = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00408 iCnt += 2;
00409
00410
00411 m_iRelBoardKeyPad = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00412 iCnt += 2;
00413
00414
00415 for(i = 0; i < 4; i++)
00416 {
00417 m_iRelBoardAnalogIn[i] = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00418 iCnt += 2;
00419 }
00420
00421
00422 m_iRelBoardTempSensor = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00423 iCnt += 2;
00424
00425
00426
00427 m_iDigIn = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00428 iCnt += 2;
00429
00430
00431
00432 m_Mutex.unlock();
00433 return true;
00434 }