SerRelayBoard.cpp
Go to the documentation of this file.
1 /*
2  * Copyright 2017 Fraunhofer Institute for Manufacturing Engineering and Automation (IPA)
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9 
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 
18 #include <math.h>
20 #include <iostream>
21 
22 //-----------------------------------------------
23 
24 
25 #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
26 
27 #define RS422_BAUDRATE 420000
28 #define RS422_RX_BUFFERSIZE 1024
29 #define RS422_TX_BUFFERSIZE 1024
30 
31 #define RS422_TIMEOUT 0.025
32 
33 #define NUM_BYTE_REC_MAX 120
34 #define NUM_BYTE_REC_HEADER 4 //Header bytes, which are used to identify the beginning of a new received message {0x02, 0x80, 0xD6, 0x02}
35 #define NUM_BYTE_REC_CHECKSUM 2 //checksum for message, that is built as the sum of all data bytes contained in the message
36 #define NUM_BYTE_REC 104 //Total amount of data bytes in a received message (from the relayboard)
37 
38 #define NUM_BYTE_SEND_RELAYBOARD_14 88
39 #define NUM_BYTE_REC_RELAYBOARD_14 124
40 
41 
42 //-----------------------------------------------
43 SerRelayBoard::SerRelayBoard(std::string ComPort, int ProtocolVersion)
44 {
45  m_iProtocolVersion = ProtocolVersion;
46  if(m_iProtocolVersion == 1)
47  m_NUM_BYTE_SEND = 50;
48  else if(m_iProtocolVersion == 2)
49  { m_NUM_BYTE_SEND = 79;
51  }
52  else if(m_iProtocolVersion == 3)
53  {
56  }
57  m_bComInit = false;
58  m_sNumComPort = ComPort;
59 
62  m_iRelBoardKeyPad = 0xFFFF;
63  m_iCmdRelayBoard = 0;
64  m_iDigIn = 0;
65  m_cSoftEMStop = 0;
66 
67 }
68 
69 //-----------------------------------------------
71 {
72  m_SerIO.closeIO();
73 }
74 
75 //-----------------------------------------------
77 {
78  static int siNoMsgCnt = 0;
79 
80  int iNumByteRec = NUM_BYTE_REC;
82  {
83  iNumByteRec = NUM_BYTE_REC_RELAYBOARD_14;
84  }
85 
86  const int c_iNrBytesMin = NUM_BYTE_REC_HEADER + iNumByteRec + NUM_BYTE_REC_CHECKSUM;
87  const int c_iSizeBuffer = 4096;
88 
89  int i;
90  int errorFlag = NO_ERROR;
91  int iNrBytesInQueue, iNrBytesRead, iDataStart;
92  unsigned char cDat[c_iSizeBuffer];
93  unsigned char cTest[4] = {0x02, 0x80, 0xD6, 0x02};
94 
95  if( !m_bComInit ) return NOT_INITIALIZED;
96 
97  //enough data in queue?
98  iNrBytesInQueue = m_SerIO.getSizeRXQueue();
99  if(iNrBytesInQueue < c_iNrBytesMin)
100  {
101  //there are too less bytes in queue
102  siNoMsgCnt++;
103  if(siNoMsgCnt > 29)
104  {
105  //std::cerr << "Relayboard: " << siNoMsgCnt << " cycles no msg received";
106  siNoMsgCnt = 0;
107  errorFlag = NO_MESSAGES;
108  } else errorFlag = TOO_LESS_BYTES_IN_QUEUE;
109 
110  return errorFlag;
111  }
112  else
113  {
114  siNoMsgCnt = 0;
115  }
116 
117  // search most recent data from back of queue
118  iNrBytesRead = m_SerIO.readBlocking((char*)&cDat[0], iNrBytesInQueue);
119  for(i = (iNrBytesRead - c_iNrBytesMin); i >= 0 ; i--)
120  {
121  //try to find start bytes
122  if((cDat[i] == cTest[0]) && (cDat[i+1] == cTest[1]) && (cDat[i+2] == cTest[2]) && (cDat[i+3] == cTest[3]))
123  {
124  iDataStart = i + 4;
125 
126  // checksum ok?
127  if( convRecMsgToData(&cDat[iDataStart]) )
128  {
129  return errorFlag;
130  }
131  else
132  {
133  //std::cerr << "Relayboard: checksum error";
134  errorFlag = CHECKSUM_ERROR;
135  return errorFlag;
136  }
137  }
138  }
139 
140  return errorFlag;
141 }
142 
143 //-----------------------------------------------
145 {
150 
151  m_SerIO.openIO();
152 
153  m_bComInit = true;
154 
155  return true;
156 }
157 
158 //-----------------------------------------------
160 {
161  m_SerIO.closeIO();
162  m_bComInit = false;
163 
164  init();
165 
166  return true;
167 }
168 
169 //-----------------------------------------------
171 {
172  m_SerIO.closeIO();
173 
174  m_bComInit = false;
175 
176  return true;
177 }
178 
179 
180 //-----------------------------------------------
182 {
183  if( (m_iRelBoardStatus & 0x0001) != 0)
184  {
185  return true;
186  }
187  else
188  {
189  return false;
190  }
191 }
192 
193 //-----------------------------------------------
195 {
196  if( (m_iRelBoardStatus & 0x0002) != 0)
197  {
198  return true;
199  }
200  else
201  {
202  return false;
203  }
204 }
205 
206 //-----------------------------------------------
208  int errorFlag = NO_ERROR;
209  int iNrBytesWritten;
210 
211  unsigned char cMsg[m_NUM_BYTE_SEND];
212 
213  m_Mutex.lock();
214 
215  convDataToSendMsg(cMsg);
216 
217  m_SerIO.purgeTx();
218 
219  iNrBytesWritten = m_SerIO.writeIO((char*)cMsg, m_NUM_BYTE_SEND);
220 
221  if(iNrBytesWritten < m_NUM_BYTE_SEND) {
222  //std::cerr << "Error in sending message to Relayboard over SerialIO, lost bytes during writing" << std::endl;
223  errorFlag = GENERAL_SENDING_ERROR;
224  }
225 
226  m_Mutex.unlock();
227 
228  return errorFlag;
229 }
230 
231 int SerRelayBoard::setDigOut(int iChannel, bool bOn)
232 {
233  switch( iChannel)
234  {
235  case 0:
236 
237  if(bOn) { m_iCmdRelayBoard |= CMD_SET_CHARGE_RELAY; }
239 
240  break;
241 
242  case 1:
243 
244  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY1; }
245  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY1; }
246 
247  break;
248 
249  case 2:
250 
251  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY2; }
252  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY2; }
253 
254  break;
255 
256  case 3:
257 
258  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY3; }
259  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY3; }
260 
261  break;
262 
263  case 4:
264 
265  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY4; }
266  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY4; }
267 
268  break;
269 
270  case 5:
271 
272  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY5; }
273  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY5; }
274 
275  break;
276 
277  case 6:
278 
279  if(bOn) { m_iCmdRelayBoard |= CMD_SET_RELAY6; }
280  else { m_iCmdRelayBoard &= ~CMD_SET_RELAY6; }
281 
282  break;
283 
284  default:
285 
286  return -1;
287  }
288 
289  return 0;
290 }
291 //-----------------------------------------------
292 int SerRelayBoard::getAnalogIn(int* piAnalogIn)
293 {
294  piAnalogIn[0] = m_iChargeCurrent;
295  piAnalogIn[1] = m_iRelBoardBattVoltage;
296  piAnalogIn[2] = m_iRelBoardTempSensor;
297  piAnalogIn[3] = m_iRelBoardKeyPad;
298  piAnalogIn[4] = m_iRelBoardAnalogIn[0];
299  piAnalogIn[5] = m_iRelBoardAnalogIn[1];
300  piAnalogIn[6] = m_iRelBoardAnalogIn[2];
301  piAnalogIn[7] = m_iRelBoardAnalogIn[3];
302 
303  return 0;
304 }
305 
306 //-----------------------------------------------
308 {
309  return m_iDigIn;
310 }
311 
312 void SerRelayBoard::convDataToSendMsg(unsigned char cMsg[])
313 {
314  int i;
315  static int j = 0;
316  int iCnt = 0;
317  int iChkSum = 0;
318 
319  if (m_cSoftEMStop & 0x02)
320  {
321  if (j == 1)
322  {
323  m_cSoftEMStop &= 0xFD;
324  j = 0;
325  }
326  else if (j == 0)
327  {
328  j = 1;
329  }
330  }
331 
332  cMsg[iCnt++] = CMD_RELAISBOARD_GET_DATA;
333 
334  cMsg[iCnt++] = m_iConfigRelayBoard >> 8;
335  cMsg[iCnt++] = m_iConfigRelayBoard;
336 
337  cMsg[iCnt++] = m_iCmdRelayBoard >> 8;
338  cMsg[iCnt++] = m_iCmdRelayBoard;
339 
340  cMsg[iCnt++] = m_iIOBoardDigOut >> 8;
341  cMsg[iCnt++] = m_iIOBoardDigOut;
342 
343  cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 24;
344  cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 16;
345  cMsg[iCnt++] = m_iVelCmdMotRightEncS >> 8;
346  cMsg[iCnt++] = m_iVelCmdMotRightEncS;
347 
348  cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 24;
349  cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 16;
350  cMsg[iCnt++] = m_iVelCmdMotLeftEncS >> 8;
351  cMsg[iCnt++] = m_iVelCmdMotLeftEncS;
352 
354  {
355  cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 24;
356  cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 16;
357  cMsg[iCnt++] = m_iVelCmdMotRearRightEncS >> 8;
358  cMsg[iCnt++] = m_iVelCmdMotRearRightEncS;
359 
360  cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 24;
361  cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 16;
362  cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS >> 8;
363  cMsg[iCnt++] = m_iVelCmdMotRearLeftEncS;
364  }
365 
366  cMsg[iCnt++] = m_iUSBoardSensorActive >> 8;
367  cMsg[iCnt++] = m_iUSBoardSensorActive;
368 
370  {
371  for(i = 0; i < 20; i++)
372  {
373  cMsg[iCnt++] = m_cTextDisplay[i];
374  }
375 
376  // fill remaining msg with 0's
377  do
378  {
379  cMsg[iCnt++] = 0;
380  }
381  while(iCnt < (m_NUM_BYTE_SEND - 2));
382  }
383  else
384  {
385  for(i = 0; i < 60; i++)
386  {
387  cMsg[iCnt++] = m_cTextDisplay[i];
388  }
389  }
390 
392  {
393  cMsg[iCnt++] = m_cSoftEMStop;
394  }
395  // calc checksum
396  for(i = 0; i < (m_NUM_BYTE_SEND - 2); i++)
397  {
398  iChkSum %= 0xFF00;
399  iChkSum += cMsg[i];
400  }
401 
402  cMsg[m_NUM_BYTE_SEND - 2] = iChkSum >> 8;
403  cMsg[m_NUM_BYTE_SEND - 1] = iChkSum;
404 
405  // reset flags
407 
408 }
409 
410 
411 //-----------------------------------------------
412 /*void SerRelayBoard::convDataToSendMsg(unsigned char cMsg[])
413 {
414  int i;
415  int iCnt = 0;
416  int iChkSum = 0;
417 
418  cMsg[iCnt++] = 1;//CMD_RELAISBOARD_GET_DATA;
419 
420  cMsg[iCnt++] = m_iConfigRelayBoard >> 8;
421  cMsg[iCnt++] = m_iConfigRelayBoard;
422 
423  cMsg[iCnt++] = m_iCmdRelayBoard >> 8;
424  cMsg[iCnt++] = m_iCmdRelayBoard;
425 
426  // fill remaining msg with 0's
427  do
428  {
429  cMsg[iCnt++] = 0;
430  }
431  while(iCnt < (m_NUM_BYTE_SEND - 2));
432 
433  // calc checksum: summation of all bytes in the message
434  for(i = 0; i < (m_NUM_BYTE_SEND - 2); i++)
435  {
436  iChkSum += cMsg[i];
437  }
438 
439  cMsg[m_NUM_BYTE_SEND - 2] = iChkSum >> 8;
440  cMsg[m_NUM_BYTE_SEND - 1] = iChkSum;
441 
442  // reset flags
443  m_iCmdRelayBoard &= ~CMD_RESET_POS_CNT;
444 }
445 */
446 //-----------------------------------------------
447 bool SerRelayBoard::convRecMsgToData(unsigned char cMsg[])
448 {
449 
450  int iNumByteRec = NUM_BYTE_REC;
452  {
453  iNumByteRec = NUM_BYTE_REC;
454  }
456  {
457  iNumByteRec = NUM_BYTE_REC;
458  }
460  {
461  iNumByteRec = NUM_BYTE_REC_RELAYBOARD_14;
462  }
463 
464  const int c_iStartCheckSum = iNumByteRec;
465 
466  int i;
467  unsigned int iTxCheckSum;
468  unsigned int iCheckSum;
469 
470  m_Mutex.lock();
471 
472  // test checksum: checksum should be sum of all bytes
473  iTxCheckSum = (cMsg[c_iStartCheckSum + 1] << 8) | cMsg[c_iStartCheckSum];
474 
475  iCheckSum = 0;
476  for(i = 0; i < c_iStartCheckSum; i++)
477  {
478  iCheckSum %= 0xFF00;
479  iCheckSum += cMsg[i];
480  }
481 
482  if(iCheckSum != iTxCheckSum)
483  {
484  return false;
485  }
486 
487  // convert data
488  int iCnt = 0;
489 
490  //RelayboardStatus bytes contain EM-Stop and Scanner-Stop bits
491  m_iRelBoardStatus = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
492  iCnt += 2;
493 
494  //unused at the moment
495  m_iChargeCurrent = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
496  iCnt += 2;
497 
498  //unused at the moment
499  m_iRelBoardBattVoltage = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
500  iCnt += 2;
501 
502  //unused at the moment
503  m_iRelBoardKeyPad = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
504  iCnt += 2;
505 
506  //unused at the moment
507  for(i = 0; i < 4; i++)
508  {
509  m_iRelBoardAnalogIn[i] = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
510  iCnt += 2;
511  }
512 
513  //unused at the moment
514  m_iRelBoardTempSensor = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
515  iCnt += 2;
516 
517  //Digital Inputs
518  //unused at the moment
519  m_iDigIn = (cMsg[iCnt + 1] << 8) | cMsg[iCnt];
520  iCnt += 2;
521 
522  //Throw away rest of the message, it was used for earlier purposes
523 
524  m_Mutex.unlock();
525  return true;
526 }
int getSizeRXQueue()
Definition: SerialIO.cpp:407
#define NUM_BYTE_REC_RELAYBOARD_14
unsigned char m_cTextDisplay[60]
int m_iVelCmdMotLeftEncS
void closeIO()
Definition: SerialIO.cpp:292
SerialIO m_SerIO
int m_iVelCmdMotRightEncS
void setBufferSize(int ReadBufSize, int WriteBufSize)
Definition: SerialIO.h:108
int m_iRelBoardAnalogIn[4]
#define NUM_BYTE_REC
int m_iUSBoardSensorActive
int m_iVelCmdMotRearLeftEncS
void convDataToSendMsg(unsigned char cMsg[])
void setTimeout(double Timeout)
Definition: SerialIO.cpp:301
int m_iVelCmdMotRearRightEncS
#define RS422_TX_BUFFERSIZE
bool lock(unsigned int uiTimeOut=INFINITE)
Definition: Mutex.h:50
void setDeviceName(const char *Name)
Definition: SerialIO.h:70
#define NUM_BYTE_REC_HEADER
int writeIO(const char *Buffer, int Length)
Definition: SerialIO.cpp:379
int setDigOut(int iChannel, bool bOn)
#define RS422_RX_BUFFERSIZE
int readBlocking(char *Buffer, int Length)
Definition: SerialIO.cpp:343
int m_iRelBoardBattVoltage
#define NUM_BYTE_SEND_RELAYBOARD_14
bool convRecMsgToData(unsigned char cMsg[])
void setBaudRate(int BaudRate)
Definition: SerialIO.h:76
void purgeTx()
Definition: SerialIO.h:184
#define RS422_TIMEOUT
int openIO()
Definition: SerialIO.cpp:128
int m_iRelBoardTempSensor
#define RS422_BAUDRATE
std::string m_sNumComPort
int getAnalogIn(int *piAnalogIn)
void unlock()
Definition: Mutex.h:67
SerRelayBoard(std::string ComPort, int ProtocolVersion=1)
#define NUM_BYTE_REC_CHECKSUM


cob_relayboard
Author(s): Christian Connette
autogenerated on Wed Apr 7 2021 02:11:46