SerRelayBoard.cpp
Go to the documentation of this file.
00001 /*
00002  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *   http://www.apache.org/licenses/LICENSE-2.0
00009 
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 
00018 #include <math.h>
00019 #include <cob_relayboard/SerRelayBoard.h>
00020 #include <iostream>
00021 
00022 //-----------------------------------------------
00023 
00024 
00025 #define NUM_BYTE_SEND 79 //Total amount of data sent to relayboard in one message, is now passed and set as protocol-version argument in constructor
00026 
00027 #define RS422_BAUDRATE 420000
00028 #define RS422_RX_BUFFERSIZE 1024
00029 #define RS422_TX_BUFFERSIZE 1024
00030 
00031 #define RS422_TIMEOUT 0.025
00032 
00033 #define NUM_BYTE_REC_MAX 120
00034 #define NUM_BYTE_REC_HEADER 4 //Header bytes, which are used to identify the beginning of a new received message {0x02, 0x80, 0xD6, 0x02}
00035 #define NUM_BYTE_REC_CHECKSUM 2 //checksum for message, that is built as the sum of all data bytes contained in the message
00036 #define NUM_BYTE_REC 104 //Total amount of data bytes in a received message (from the relayboard)
00037 
00038 #define NUM_BYTE_SEND_RELAYBOARD_14 88
00039 #define NUM_BYTE_REC_RELAYBOARD_14 124
00040 
00041 
00042 //-----------------------------------------------
00043 SerRelayBoard::SerRelayBoard(std::string ComPort, int ProtocolVersion)
00044 {
00045         m_iProtocolVersion = ProtocolVersion;
00046         if(m_iProtocolVersion == 1)
00047                 m_NUM_BYTE_SEND = 50;
00048         else if(m_iProtocolVersion == 2)
00049         {       m_NUM_BYTE_SEND = 79;
00050                 m_iTypeLCD = LCD_60CHAR_TEXT;
00051         }
00052         else if(m_iProtocolVersion == 3)
00053         {
00054                 m_NUM_BYTE_SEND = NUM_BYTE_SEND_RELAYBOARD_14;
00055                 m_iTypeLCD = RELAY_BOARD_1_4;
00056         }
00057         m_bComInit = false;
00058         m_sNumComPort = ComPort;
00059 
00060         m_iRelBoardBattVoltage = 0;
00061         m_iConfigRelayBoard = 0;
00062         m_iRelBoardKeyPad = 0xFFFF;
00063         m_iCmdRelayBoard = 0;
00064         m_iDigIn = 0;
00065         m_cSoftEMStop = 0;
00066 
00067 }
00068 
00069 //-----------------------------------------------
00070 SerRelayBoard::~SerRelayBoard()
00071 {
00072         m_SerIO.closeIO();
00073 }
00074 
00075 //-----------------------------------------------
00076 int SerRelayBoard::evalRxBuffer()
00077 {
00078         static int siNoMsgCnt = 0;
00079 
00080         int iNumByteRec = NUM_BYTE_REC;
00081         if(m_iTypeLCD == RELAY_BOARD_1_4)
00082         {
00083                 iNumByteRec = NUM_BYTE_REC_RELAYBOARD_14;
00084         }
00085 
00086         const int c_iNrBytesMin = NUM_BYTE_REC_HEADER + iNumByteRec + NUM_BYTE_REC_CHECKSUM;
00087         const int c_iSizeBuffer = 4096;
00088 
00089         int i;
00090         int errorFlag = NO_ERROR;
00091         int iNrBytesInQueue, iNrBytesRead, iDataStart;
00092         unsigned char cDat[c_iSizeBuffer];
00093         unsigned char cTest[4] = {0x02, 0x80, 0xD6, 0x02};
00094 
00095         if( !m_bComInit ) return NOT_INITIALIZED;
00096 
00097         //enough data in queue?
00098         iNrBytesInQueue = m_SerIO.getSizeRXQueue();
00099         if(iNrBytesInQueue < c_iNrBytesMin)
00100         {
00101                 //there are too less bytes in queue
00102                 siNoMsgCnt++;
00103                 if(siNoMsgCnt > 29)
00104                 {
00105                         //std::cerr << "Relayboard: " << siNoMsgCnt << " cycles no msg received";
00106                         siNoMsgCnt = 0;
00107                         errorFlag = NO_MESSAGES;
00108                 } else errorFlag = TOO_LESS_BYTES_IN_QUEUE;
00109 
00110                 return errorFlag;
00111         }
00112         else
00113         {
00114                 siNoMsgCnt = 0;
00115         }
00116 
00117         // search most recent data from back of queue
00118         iNrBytesRead = m_SerIO.readBlocking((char*)&cDat[0], iNrBytesInQueue);
00119         for(i = (iNrBytesRead - c_iNrBytesMin); i >= 0 ; i--)
00120         {
00121                 //try to find start bytes
00122                 if((cDat[i] == cTest[0]) && (cDat[i+1] == cTest[1]) && (cDat[i+2] == cTest[2]) && (cDat[i+3] == cTest[3]))
00123                 {
00124                         iDataStart = i + 4;
00125 
00126                         // checksum ok?
00127                         if( convRecMsgToData(&cDat[iDataStart]) )
00128                         {
00129                                 return errorFlag;
00130                         }
00131                         else
00132                         {
00133                                 //std::cerr << "Relayboard: checksum error";
00134                                 errorFlag = CHECKSUM_ERROR;
00135                                 return errorFlag;
00136                         }
00137                 }
00138         }
00139 
00140         return errorFlag;
00141 }
00142 
00143 //-----------------------------------------------
00144 bool SerRelayBoard::init()
00145 {
00146         m_SerIO.setBaudRate(RS422_BAUDRATE);
00147         m_SerIO.setDeviceName( m_sNumComPort.c_str() );
00148         m_SerIO.setBufferSize(RS422_RX_BUFFERSIZE, RS422_TX_BUFFERSIZE);
00149         m_SerIO.setTimeout(RS422_TIMEOUT);
00150 
00151         m_SerIO.openIO();
00152 
00153         m_bComInit = true;
00154 
00155         return true;
00156 }
00157 
00158 //-----------------------------------------------
00159 bool SerRelayBoard::reset()
00160 {
00161         m_SerIO.closeIO();
00162         m_bComInit = false;
00163 
00164         init();
00165 
00166         return true;
00167 }
00168 
00169 //-----------------------------------------------
00170 bool SerRelayBoard::shutdown()
00171 {
00172         m_SerIO.closeIO();
00173 
00174         m_bComInit = false;
00175 
00176         return true;
00177 }
00178 
00179 
00180 //-----------------------------------------------
00181 bool SerRelayBoard::isEMStop()
00182 {
00183         if( (m_iRelBoardStatus & 0x0001) != 0)
00184         {
00185                 return true;
00186         }
00187         else
00188         {
00189                 return false;
00190         }
00191 }
00192 
00193 //-----------------------------------------------
00194 bool SerRelayBoard::isScannerStop()
00195 {
00196         if( (m_iRelBoardStatus & 0x0002) != 0)
00197         {
00198                 return true;
00199         }
00200         else
00201         {
00202                 return false;
00203         }
00204 }
00205 
00206 //-----------------------------------------------
00207 int SerRelayBoard::sendRequest() {
00208         int errorFlag = NO_ERROR;
00209         int iNrBytesWritten;
00210 
00211         unsigned char cMsg[m_NUM_BYTE_SEND];
00212 
00213         m_Mutex.lock();
00214 
00215                 convDataToSendMsg(cMsg);
00216 
00217                 m_SerIO.purgeTx();
00218 
00219                 iNrBytesWritten = m_SerIO.writeIO((char*)cMsg, m_NUM_BYTE_SEND);
00220 
00221                 if(iNrBytesWritten < m_NUM_BYTE_SEND) {
00222                         //std::cerr << "Error in sending message to Relayboard over SerialIO, lost bytes during writing" << std::endl;
00223                         errorFlag = GENERAL_SENDING_ERROR;
00224                 }
00225 
00226         m_Mutex.unlock();
00227 
00228         return errorFlag;
00229 }
00230 
00231 int SerRelayBoard::setDigOut(int iChannel, bool bOn)
00232 {
00233         switch( iChannel)
00234         {
00235         case 0:
00236 
00237                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_CHARGE_RELAY; }
00238                 else { m_iCmdRelayBoard &= ~CMD_SET_CHARGE_RELAY; }
00239 
00240                 break;
00241 
00242         case 1:
00243 
00244                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY1; }
00245                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY1; }
00246 
00247                 break;
00248 
00249         case 2:
00250 
00251                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY2; }
00252                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY2; }
00253 
00254                 break;
00255 
00256         case 3:
00257 
00258                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY3; }
00259                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY3; }
00260 
00261                 break;
00262 
00263         case 4:
00264 
00265                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY4; }
00266                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY4; }
00267 
00268                 break;
00269 
00270         case 5:
00271 
00272                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY5; }
00273                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY5; }
00274 
00275                 break;
00276 
00277         case 6:
00278 
00279                 if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY6; }
00280                 else { m_iCmdRelayBoard &= ~CMD_SET_RELAY6; }
00281 
00282                 break;
00283 
00284         default:
00285 
00286                 return -1;
00287         }
00288 
00289         return 0;
00290 }
00291 //-----------------------------------------------
00292 int SerRelayBoard::getAnalogIn(int* piAnalogIn)
00293 {
00294         piAnalogIn[0] = m_iChargeCurrent;
00295         piAnalogIn[1] = m_iRelBoardBattVoltage;
00296         piAnalogIn[2] = m_iRelBoardTempSensor;
00297         piAnalogIn[3] = m_iRelBoardKeyPad;
00298         piAnalogIn[4] = m_iRelBoardAnalogIn[0];
00299         piAnalogIn[5] = m_iRelBoardAnalogIn[1];
00300         piAnalogIn[6] = m_iRelBoardAnalogIn[2];
00301         piAnalogIn[7] = m_iRelBoardAnalogIn[3];
00302 
00303         return 0;
00304 }
00305 
00306 //-----------------------------------------------
00307 int SerRelayBoard::getDigIn()
00308 {
00309         return m_iDigIn;
00310 }
00311 
00312 void SerRelayBoard::convDataToSendMsg(unsigned char cMsg[])
00313 {
00314         int i;
00315         static int j = 0;
00316         int iCnt = 0;
00317         int iChkSum = 0;
00318 
00319         if (m_cSoftEMStop & 0x02)
00320         {
00321                 if (j == 1)
00322                 {
00323                         m_cSoftEMStop &= 0xFD;
00324                         j = 0;
00325                 }
00326                 else if (j == 0)
00327                 {
00328                         j = 1;
00329                 }
00330         }
00331 
00332         cMsg[iCnt++] = CMD_RELAISBOARD_GET_DATA;
00333 
00334         cMsg[iCnt++] = m_iConfigRelayBoard >> 8;
00335         cMsg[iCnt++] = m_iConfigRelayBoard;
00336 
00337         cMsg[iCnt++] = m_iCmdRelayBoard >> 8;
00338         cMsg[iCnt++] = m_iCmdRelayBoard;
00339 
00340         cMsg[iCnt++] = m_iIOBoardDigOut >> 8;
00341         cMsg[iCnt++] = m_iIOBoardDigOut;
00342 
00343         cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 24;
00344         cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 16;
00345         cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 8;
00346         cMsg[iCnt++] = m_iVelCmdMotRightEncS;
00347 
00348         cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 24;
00349         cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 16;
00350         cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 8;
00351         cMsg[iCnt++] = m_iVelCmdMotLeftEncS;
00352 
00353         if(m_iTypeLCD == RELAY_BOARD_1_4)
00354         {
00355                 cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 24;
00356                 cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 16;
00357                 cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 8;
00358                 cMsg[iCnt++] = m_iVelCmdMotRearRightEncS;
00359 
00360                 cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 24;
00361                 cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 16;
00362                 cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 8;
00363                 cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS;
00364         }
00365 
00366         cMsg[iCnt++] = m_iUSBoardSensorActive >> 8;
00367         cMsg[iCnt++] = m_iUSBoardSensorActive;
00368 
00369         if(m_iTypeLCD == LCD_20CHAR_TEXT)
00370         {
00371                 for(i = 0; i < 20; i++)
00372                 {
00373                         cMsg[iCnt++] = m_cTextDisplay[i];
00374                 }
00375 
00376                 // fill remaining msg with 0's
00377                 do
00378                 {
00379                         cMsg[iCnt++] = 0;
00380                 }
00381                 while(iCnt < (m_NUM_BYTE_SEND - 2));
00382         }
00383         else
00384         {
00385                 for(i = 0; i < 60; i++)
00386                 {
00387                         cMsg[iCnt++] = m_cTextDisplay[i];
00388                 }
00389         }
00390 
00391         if(m_iTypeLCD == RELAY_BOARD_1_4)
00392         {
00393                 cMsg[iCnt++] = m_cSoftEMStop;
00394         }
00395         // calc checksum
00396         for(i = 0; i < (m_NUM_BYTE_SEND - 2); i++)
00397         {
00398                 iChkSum %= 0xFF00;
00399                 iChkSum += cMsg[i];
00400         }
00401 
00402         cMsg[m_NUM_BYTE_SEND - 2] = iChkSum >> 8;
00403         cMsg[m_NUM_BYTE_SEND - 1] = iChkSum;
00404 
00405         // reset flags
00406         m_iCmdRelayBoard &= ~CMD_RESET_POS_CNT;
00407 
00408 }
00409 
00410 
00411 //-----------------------------------------------
00412 /*void SerRelayBoard::convDataToSendMsg(unsigned char cMsg[])
00413 {
00414         int i;
00415         int iCnt = 0;
00416         int iChkSum = 0;
00417 
00418         cMsg[iCnt++] = 1;//CMD_RELAISBOARD_GET_DATA;
00419 
00420         cMsg[iCnt++] = m_iConfigRelayBoard >> 8;
00421         cMsg[iCnt++] = m_iConfigRelayBoard;
00422 
00423         cMsg[iCnt++] = m_iCmdRelayBoard >> 8;
00424         cMsg[iCnt++] = m_iCmdRelayBoard;
00425 
00426         // fill remaining msg with 0's
00427         do
00428         {
00429                 cMsg[iCnt++] = 0;
00430         }
00431         while(iCnt < (m_NUM_BYTE_SEND - 2));
00432 
00433         // calc checksum: summation of all bytes in the message
00434         for(i = 0; i < (m_NUM_BYTE_SEND - 2); i++)
00435         {
00436                 iChkSum += cMsg[i];
00437         }
00438 
00439         cMsg[m_NUM_BYTE_SEND - 2] = iChkSum >> 8;
00440         cMsg[m_NUM_BYTE_SEND - 1] = iChkSum;
00441 
00442         // reset flags
00443         m_iCmdRelayBoard &= ~CMD_RESET_POS_CNT;
00444 }
00445 */
00446 //-----------------------------------------------
00447 bool SerRelayBoard::convRecMsgToData(unsigned char cMsg[])
00448 {
00449 
00450         int iNumByteRec = NUM_BYTE_REC;
00451         if(m_iTypeLCD == LCD_20CHAR_TEXT)
00452         {
00453                 iNumByteRec = NUM_BYTE_REC;
00454         }
00455         if(m_iTypeLCD == LCD_60CHAR_TEXT)
00456         {
00457                 iNumByteRec = NUM_BYTE_REC;
00458         }
00459         if(m_iTypeLCD == RELAY_BOARD_1_4)
00460         {
00461                 iNumByteRec = NUM_BYTE_REC_RELAYBOARD_14;
00462         }
00463 
00464         const int c_iStartCheckSum = iNumByteRec;
00465 
00466         int i;
00467         unsigned int iTxCheckSum;
00468         unsigned int iCheckSum;
00469 
00470         m_Mutex.lock();
00471 
00472         // test checksum: checksum should be sum of all bytes
00473         iTxCheckSum = (cMsg[c_iStartCheckSum + 1] << 8) | cMsg[c_iStartCheckSum];
00474 
00475         iCheckSum = 0;
00476         for(i = 0; i < c_iStartCheckSum; i++)
00477         {
00478                 iCheckSum %= 0xFF00;
00479                 iCheckSum += cMsg[i];
00480         }
00481 
00482         if(iCheckSum != iTxCheckSum)
00483         {
00484                 return false;
00485         }
00486 
00487         // convert data
00488         int iCnt = 0;
00489 
00490         //RelayboardStatus bytes contain EM-Stop and Scanner-Stop bits
00491         m_iRelBoardStatus = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00492         iCnt += 2;
00493 
00494         //unused at the moment
00495         m_iChargeCurrent = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00496         iCnt += 2;
00497 
00498         //unused at the moment
00499         m_iRelBoardBattVoltage = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00500         iCnt += 2;
00501 
00502         //unused at the moment
00503         m_iRelBoardKeyPad = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00504         iCnt += 2;
00505 
00506         //unused at the moment
00507         for(i = 0; i < 4; i++)
00508         {
00509                 m_iRelBoardAnalogIn[i] = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00510                 iCnt += 2;
00511         }
00512 
00513         //unused at the moment
00514         m_iRelBoardTempSensor = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00515         iCnt += 2;
00516 
00517         //Digital Inputs
00518         //unused at the moment
00519         m_iDigIn = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
00520         iCnt += 2;
00521 
00522         //Throw away rest of the message, it was used for earlier purposes
00523 
00524         m_Mutex.unlock();
00525         return true;
00526 }


cob_relayboard
Author(s): Christian Connette
autogenerated on Sat Jun 8 2019 21:02:18