sick_scan_common_nw.cpp
Go to the documentation of this file.
1 
23 #include "sick_scan/tcp/colaa.hpp"
24 #include "sick_scan/tcp/colab.hpp"
26 #include "sick_scan/tcp/tcp.hpp"
27 #include <map> // for std::map
28 
29 #include "sick_scan/tcp/tcp.hpp"
32 #include "sick_scan/tcp/Mutex.hpp"
33 #include <assert.h>
34 
36 {
38  m_beVerbose = false;
39 
40 }
41 
43 {
44  // Disconnect and shut down receive thread.
45  if (isConnected() == true)
46  {
47  // Change from CONNECTED to CONSTRUCTED
48  disconnect();
49  }
50 }
51 
52 
53 //
54 // Disconnect from the scanner, and close the interface.
55 //
57 {
59 
60  // Change back to CONSTRUCTED
62  return true;
63 }
64 
65 
66 //
67 // Initialisation from Scanner class:
68 // Parameter setup only. Afterwards, call connect() to connect to the scanner.
69 //
70 bool SickScanCommonNw::init(std::string ipAddress,
71  unsigned short portNumber,
72  Tcp::DisconnectFunction disconnectFunction,
73  void *obj)
74 {
75  m_ipAddress = ipAddress;
76  m_portNumber = portNumber;
77  m_tcp.setDisconnectCallbackFunction(disconnectFunction, obj);
78  return true;
79 }
80 
81 
83  void *obj)
84 {
85  m_tcp.setReadCallbackFunction(readFunction, obj);
86  return (true);
87 }
88 //
89 // Verbinde mit dem unter init() eingestellten Geraet, und pruefe die Verbindung
90 // durch einen DeviceIdent-Aufruf.
91 //
92 // true = Erfolgreich.
93 //
94 
95 
97 {
98 
99  assert (m_state == CONSTRUCTED); // must not be opened or running already
100 
101  // Initialise buffer variables
102  m_numberOfBytesInReceiveBuffer = 0; // Buffer is empty
103  m_numberOfBytesInResponseBuffer = 0; // Buffer is empty
104 
105  // Establish connection here
106  // Set the data input callback for our TCP connection
107  // m_tcp.setReadCallbackFunction(&SickScanCommonNw::readCallbackFunctionS, this); // , this, _1, _2));
108 
109  bool success = openTcpConnection();
110  if (success == true)
111  {
112  // Check if scanner type matches
113  m_state = CONNECTED;
114 
115  }
116  return success;
117 }
118 
119 
120 //
121 // True, if state is CONNECTED, that is:
122 // - A TCP-connection exists
123 // - Read thread is running
124 //
126 {
127  return (m_state == CONNECTED);
128 }
129 
130 
137 {
138  // printInfoMessage("SickScanCommonNw::openTcpConnection: Connecting TCP/IP connection to " + m_ipAddress + ":" + toString(m_portNumber) + " ...", m_beVerbose);
139 
140  bool success = m_tcp.open(m_ipAddress, m_portNumber, m_beVerbose);
141  if (success == false)
142  {
143  // printError("SickScanCommonNw::openTcpConnection: ERROR: Failed to establish TCP connection, aborting!");
144  return false;
145  }
146 
147  return true;
148 }
149 
150 
151 //
152 // Close TCP-connection and shut down read thread
153 //
155 {
156  if (m_tcp.isOpen())
157  {
158  m_tcp.close();
159  }
160 }
161 
162 //
163 // Static entry point.
164 //
165 void SickScanCommonNw::readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes)
166 {
167  ((SickScanCommonNw *) obj)->readCallbackFunction(buffer, numOfBytes);
168 }
169 
170 
176 {
177  bool beVerboseHere = false;
179  "SickScanCommonNw::readCallbackFunction(): Called with " + toString(numOfBytes) + " available bytes.",
180  beVerboseHere);
181 
182  ScopedLock lock(&m_receiveDataMutex); // Mutex for access to the input buffer
183  UINT32 remainingSpace = sizeof(m_receiveBuffer) - m_numberOfBytesInReceiveBuffer;
184  UINT32 bytesToBeTransferred = numOfBytes;
185  if (remainingSpace < numOfBytes)
186  {
187  bytesToBeTransferred = remainingSpace;
188  // printWarning("SickScanCommonNw::readCallbackFunction(): Input buffer space is to small, transferring only " +
189  // ::toString(bytesToBeTransferred) + " of " + ::toString(numOfBytes) + " bytes.");
190  }
191  else
192  {
193  // printInfoMessage("SickScanCommonNw::readCallbackFunction(): Transferring " + ::toString(bytesToBeTransferred) +
194  // " bytes from TCP to input buffer.", beVerboseHere);
195  }
196 
197  if (bytesToBeTransferred > 0)
198  {
199  // Data can be transferred into our input buffer
200  memcpy(&(m_receiveBuffer[m_numberOfBytesInReceiveBuffer]), buffer, bytesToBeTransferred);
201  m_numberOfBytesInReceiveBuffer += bytesToBeTransferred;
202 
203  UINT32 size = 0;
204 
205  while (1)
206  {
207  // Now work on the input buffer until all received datasets are processed
209 
210  size = frame.size();
211  if (size == 0)
212  {
213  // Framesize = 0: There is no valid frame in the buffer. The buffer is either empty or the frame
214  // is incomplete, so leave the loop
215  printInfoMessage("SickScanCommonNw::readCallbackFunction(): No complete frame in input buffer, we are done.",
216  beVerboseHere);
217 
218  // Leave the loop
219  break;
220  }
221  else
222  {
223  // A frame was found in the buffer, so process it now.
225  "SickScanCommonNw::readCallbackFunction(): Processing a frame of length " + ::toString(frame.size()) +
226  " bytes.", beVerboseHere);
227  processFrame(frame);
228  }
229  }
230  }
231  else
232  {
233  // There was input data from the TCP interface, but our input buffer was unable to hold a single byte.
234  // Either we have not read data from our buffer for a long time, or something has gone wrong. To re-sync,
235  // we clear the input buffer here.
237  }
238 
239 }
240 
241 
242 //
243 // Look for 23-frame (STX/ETX) in receive buffer.
244 // Move frame to start of buffer
245 //
246 // Return: 0 : No (complete) frame found
247 // >0 : Frame length
248 //
250 {
251  UINT32 frameLen = 0;
252  UINT32 i;
253 
254  // Depends on protocol...
255  if (m_protocol == CoLa_A)
256  {
257  //
258  // COLA-A
259  //
260  // Must start with STX (0x02)
261  if (m_receiveBuffer[0] != 0x02)
262  {
263  // Look for starting STX (0x02)
264  for (i = 1; i < m_numberOfBytesInReceiveBuffer; i++)
265  {
266  if (m_receiveBuffer[i] == 0x02)
267  {
268  break;
269  }
270  }
271 
272  // Found beginning of frame?
273  if (i >= m_numberOfBytesInReceiveBuffer)
274  {
275  // No start found, everything can be discarded
276  m_numberOfBytesInReceiveBuffer = 0; // Invalidate buffer
277  return SopasEventMessage(); // No frame found
278  }
279 
280  // Move frame start to index 0
281  UINT32 newLen = m_numberOfBytesInReceiveBuffer - i;
282  memmove(&(m_receiveBuffer[0]), &(m_receiveBuffer[i]), newLen);
283  m_numberOfBytesInReceiveBuffer = newLen;
284  }
285 
286  // Look for ending ETX (0x03)
287  for (i = 1; i < m_numberOfBytesInReceiveBuffer; i++)
288  {
289  if (m_receiveBuffer[i] == 0x03)
290  {
291  break;
292  }
293  }
294 
295  // Found end?
296  if (i >= m_numberOfBytesInReceiveBuffer)
297  {
298  // No end marker found, so it's not a complete frame (yet)
299  return SopasEventMessage(); // No frame found
300  }
301 
302  // Calculate frame length in byte
303  frameLen = i + 1;
304 
305  return SopasEventMessage(m_receiveBuffer, CoLa_A, frameLen);
306  }
307  else if (m_protocol == CoLa_B)
308  {
309  UINT32 magicWord;
310  UINT32 payloadlength;
311 
313  {
314  return SopasEventMessage();
315  }
316  UINT16 pos = 0;
317  magicWord = colab::getIntegerFromBuffer<UINT32>(m_receiveBuffer, pos);
318  if (magicWord != 0x02020202)
319  {
320  // Look for starting STX (0x02020202)
321  for (i = 1; i <= m_numberOfBytesInReceiveBuffer - 4; i++)
322  {
323  pos = i; // this is needed, as the position value is updated by getIntegerFromBuffer
324  magicWord = colab::getIntegerFromBuffer<UINT32>(m_receiveBuffer, pos);
325  if (magicWord == 0x02020202)
326  {
327  // found magic word
328  break;
329  }
330  }
331 
332  // Found beginning of frame?
333  if (i > m_numberOfBytesInReceiveBuffer - 4)
334  {
335  // No start found, everything can be discarded
336  m_numberOfBytesInReceiveBuffer = 0; // Invalidate buffer
337  return SopasEventMessage(); // No frame found
338  }
339  else
340  {
341  // Move frame start to index
342  UINT32 bytesToMove = m_numberOfBytesInReceiveBuffer - i;
343  memmove(&(m_receiveBuffer[0]), &(m_receiveBuffer[i]), bytesToMove); // payload+magic+length+s+checksum
344  m_numberOfBytesInReceiveBuffer = bytesToMove;
345  }
346  }
347 
348  // Pruefe Laenge des Pufferinhalts
350  {
351  // Es sind nicht genug Daten fuer einen Frame
352  printInfoMessage("SickScanCommonNw::findFrameInReceiveBuffer: Frame cannot be decoded yet, only " +
353  ::toString(m_numberOfBytesInReceiveBuffer) + " bytes in the buffer.", m_beVerbose);
354  return SopasEventMessage();
355  }
356 
357  // Read length of payload
358  pos = 4;
359  payloadlength = colab::getIntegerFromBuffer<UINT32>(m_receiveBuffer, pos);
361  "SickScanCommonNw::findFrameInReceiveBuffer: Decoded payload length is " + ::toString(payloadlength) +
362  " bytes.", m_beVerbose);
363 
364  // Ist die Datenlaenge plausibel und wuede in den Puffer passen?
365  if (payloadlength > (sizeof(m_receiveBuffer) - 9))
366  {
367  // magic word + length + checksum = 9
368  printWarning(
369  "SickScanCommonNw::findFrameInReceiveBuffer: Frame too big for receive buffer. Frame discarded with length:"
370  + ::toString(payloadlength) + ".");
372  return SopasEventMessage();
373  }
374  if ((payloadlength + 9) > m_numberOfBytesInReceiveBuffer)
375  {
376  // magic word + length + s + checksum = 10
378  "SickScanCommonNw::findFrameInReceiveBuffer: Frame not complete yet. Waiting for the rest of it (" +
379  ::toString(payloadlength + 9 - m_numberOfBytesInReceiveBuffer) + " bytes missing).", m_beVerbose);
380  return SopasEventMessage(); // frame not complete
381  }
382 
383  // Calculate the total frame length in bytes: Len = Frame (9 bytes) + Payload
384  frameLen = payloadlength + 9;
385 
386  //
387  // test checksum of payload
388  //
389  UINT8 temp = 0;
390  UINT8 temp_xor = 0;
391  UINT8 checkSum;
392 
393  // Read original checksum
394  pos = frameLen - 1;
395  checkSum = colab::getIntegerFromBuffer<UINT8>(m_receiveBuffer, pos);
396 
397  // Erzeuge die Pruefsumme zum Vergleich
398  for (UINT16 i = 8; i < (frameLen - 1); i++)
399  {
400  pos = i;
401  temp = colab::getIntegerFromBuffer<UINT8>(m_receiveBuffer, pos);
402  temp_xor = temp_xor ^ temp;
403  }
404 
405  // Vergleiche die Pruefsummen
406  if (temp_xor != checkSum)
407  {
408  printWarning("SickScanCommonNw::findFrameInReceiveBuffer: Wrong checksum, Frame discarded.");
410  return SopasEventMessage();
411  }
412 
413  return SopasEventMessage(m_receiveBuffer, CoLa_B, frameLen);
414  }
415 
416  // Return empty frame
417  return SopasEventMessage();
418 }
419 
420 
427 {
428  m_tcp.write(buffer, len);
429 }
430 
431 
438 {
439 
440  if (m_protocol == CoLa_A)
441  {
443  "SickScanCommonNw::processFrame: Calling processFrame_CoLa_A() with " + ::toString(frame.size()) + " bytes.",
444  m_beVerbose);
445  // processFrame_CoLa_A(frame);
446  }
447  else if (m_protocol == CoLa_B)
448  {
450  "SickScanCommonNw::processFrame: Calling processFrame_CoLa_B() with " + ::toString(frame.size()) + " bytes.",
451  m_beVerbose);
452  // processFrame_CoLa_B(frame);
453  }
454 }
455 
456 
457 //
458 // Copies a complete frame - in any protocol - from the main input buffer to
459 // the response buffer.
460 // The frame is *not* removed from the main input buffer.
461 //
463 {
464  printInfoMessage("SickScanCommonNw::copyFrameToResposeBuffer: Copying a frame of " + ::toString(frameLength) +
465  " bytes to response buffer.", m_beVerbose);
466 
467  if (frameLength <= sizeof(m_responseBuffer))
468  {
469  // Wir duerfen kopieren
470  memcpy(m_responseBuffer, m_receiveBuffer, frameLength);
471  m_numberOfBytesInResponseBuffer = frameLength;
472  }
473  else
474  {
475  // Der respose-Buffer ist zu klein
476  printError("SickScanCommonNw::copyFrameToResposeBuffer: Failed to copy frame (Length=" + ::toString(frameLength) +
477  " bytes) to response buffer because the response buffer is too small (buffer size=" +
478  ::toString(sizeof(m_responseBuffer)) + " bytes).");
480  }
481 }
482 
483 
484 //
485 // Removes a complete frame - in any protocol - from the main input buffer.
486 //
488 {
489  // Remove frame from receive buffer
490  if (frameLength < m_numberOfBytesInReceiveBuffer)
491  {
492  // More data in buffer, move them to the buffer start
493  UINT32 newLen = m_numberOfBytesInReceiveBuffer - frameLength;
494  printInfoMessage("SickScanCommonNw::removeFrameFromReceiveBuffer: Removing " + ::toString(frameLength) +
495  " bytes from the input buffer. New length is " + ::toString(newLen) + " bytes.", m_beVerbose);
496  memmove(m_receiveBuffer, &(m_receiveBuffer[frameLength]), newLen);
498  }
499  else
500  {
501  // No other data in buffer, just mark as empty
502  printInfoMessage("SickScanCommonNw::removeFrameFromReceiveBuffer: Done, no more data in input buffer.",
503  m_beVerbose);
505  }
506 }
507 
508 
509 //
510 // ************************* SOPAS FRAME ************************************************** //
511 //
513  m_buffer(NULL), m_protocol(CoLa_A), m_frameLength(0)
514 {
515 }
516 
517 
519  m_buffer(buffer), m_protocol(protocol), m_frameLength(frameLength)
520 {
521 // Constructor
522 }
523 
524 
526 {
527  UINT32 payLoadLength = 0;
528 
529  switch (m_protocol)
530  {
531  case CoLa_A:
532  payLoadLength = m_frameLength - 2; // everything except the 0x02 0x03 frame
533  break;
534  case CoLa_B:
535  payLoadLength =
536  m_frameLength - 9; // everything except start 0x02020202(4byte), payloadLength(4byte) and checksum(1 byte)
537  }
538 
539  return payLoadLength;
540 }
541 
542 
550 {
551  std::string commandString;
552 
553  switch (m_protocol)
554  {
555  case CoLa_A:
556  commandString = std::string((char *) &m_buffer[2], 2);
557  break;
558  case CoLa_B:
559  commandString = std::string((char *) &m_buffer[9], 2);
560  }
561 
562  return commandString;
563 }
564 
565 
574 {
575  BYTE *bufferPos = NULL;
576 
577  switch (m_protocol)
578  {
579  case CoLa_A:
580  bufferPos = &m_buffer[1];
581  break;
582  case CoLa_B:
583  bufferPos = &m_buffer[8];
584  break;
585  }
586 
587  return bufferPos;
588 }
589 
590 
598 {
599  BYTE *bufferPos = NULL;
600  bufferPos = &m_buffer[0];
601  return bufferPos;
602 }
603 
604 
606 {
607  INT32 index = -1;
608 
609 
610  BYTE *bufferPos = &getPayLoad()[3];
611  switch (m_protocol)
612  {
613  case CoLa_A:
614  index = (INT32) (colaa::decodeUINT16(bufferPos));
615  break;
616  case CoLa_B:
617  index = (INT32) (colab::decodeUINT16(bufferPos));
618  break;
619  default:
620  printError("SopasEventMessage::getVariableIndex: Unknown protocol!");
621  }
622 
623  return index;
624 }
void printError(std::string message)
std::string getCommandString() const
Returns two character long command.
BYTE * getPayLoad()
contains &#39;s&#39; + command string(2 byte) + content(payload length - 3)
unsigned char BYTE
SopasEventMessage findFrameInReceiveBuffer()
uint16_t UINT16
bool init(std::string ipAddress, unsigned short portNumber, Tcp::DisconnectFunction disconnectFunction, void *obj)
void processFrame(SopasEventMessage &frame)
UINT8 m_responseBuffer[1024]
Receive buffer for everything except scan data and eval case data.
void sendCommandBuffer(UINT8 *buffer, UINT16 len)
UINT8 m_receiveBuffer[25000]
Low-Level receive buffer for all data (25000 should be enough for NAV300 Events)
UINT16 decodeUINT16(BYTE *buffer)
Definition: colab.cpp:142
UINT32 getPayLoadLength() const
contains &#39;s&#39; + command string(2 byte) + content(payload length - 3)
void(* DisconnectFunction)(void *obj)
Definition: tcp.hpp:53
#define printInfoMessage(a, b)
uint32_t UINT32
SopasProtocol m_protocol
bool setReadCallbackFunction(Tcp::ReadFunction readFunction, void *obj)
bool write(UINT8 *buffer, UINT32 numberOfBytes)
Definition: tcp.cpp:51
Interface for TCP/IP.
void copyFrameToResposeBuffer(UINT32 frameLength)
Command Language ASCI.
bool open(std::string ipAddress, UINT16 port, bool enableVerboseDebugOutput=false)
Definition: tcp.cpp:136
UINT32 size() const
BYTE * getRawData()
get SOPAS raw data include header and CRC
SopasProtocol m_protocol
bool isConnected()
Returns true if the tcp connection is established.
void(* ReadFunction)(void *obj, UINT8 *inputBuffer, UINT32 &numBytes)
Definition: tcp.hpp:49
UINT32 m_numberOfBytesInResponseBuffer
Number of bytes in buffer.
Command Language binary.
Object has been constructed. Use init() to go into CONNECTED state.
int32_t INT32
SopasEventMessage()
Default constructor.
Mutex m_receiveDataMutex
Access mutex for buffer.
Class that represents a message that was sent by a sensor. (Event message)
std::string toString(INT32 value)
Definition: toolbox.cpp:279
UINT32 m_numberOfBytesInReceiveBuffer
Number of bytes in buffer.
void removeFrameFromReceiveBuffer(UINT32 frameLength)
void readCallbackFunction(UINT8 *buffer, UINT32 &numOfBytes)
bool connect()
Connects to a sensor via tcp and reads the device name.
bool disconnect()
Closes the connection to the LMS. This is the opposite of init().
bool isOpen()
Definition: tcp.cpp:95
void setReadCallbackFunction(ReadFunction readFunction, void *obj)
Definition: tcp.cpp:110
void setDisconnectCallbackFunction(DisconnectFunction discFunction, void *obj)
Definition: tcp.cpp:82
void close()
Definition: tcp.cpp:326
SopasProtocol
static void readCallbackFunctionS(void *obj, UINT8 *buffer, UINT32 &numOfBytes)
Function that will be called on incomming data via tcp.
void printWarning(std::string message)
UINT16 decodeUINT16(BYTE *buffer)
Definition: colaa.cpp:627
uint8_t UINT8
INT32 getVariableIndex()
Returns the index of a variable (answer to read variable by index). In case of error a negative value...


sick_scan
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Wed May 5 2021 03:05:48