sick_scan_common.cpp
Go to the documentation of this file.
1 
52 #ifdef _MSC_VER // compiling simulation for MS-Visual C++ - not defined for linux system
53 #pragma warning(disable: 4996)
54 #pragma warning(disable: 4267) // due to conversion warning size_t in the ros header file
55 #define _WIN32_WINNT 0x0501
56 
57 #endif
58 
65 
66 #ifdef _MSC_VER
67 #include "sick_scan/rosconsole_simu.hpp"
68 #endif
69 
70 #include "sick_scan/binScanf.hpp"
71 // if there is a missing RadarScan.h, try to run catkin_make in der workspace-root
72 #include <sick_scan/RadarScan.h>
73 
74 #include "sick_scan/Encoder.h"
75 
76 #include <cstdio>
77 #include <cstring>
78 
79 #define _USE_MATH_DEFINES
80 
81 #include <math.h>
82 
83 #ifndef rad2deg
84 #define rad2deg(x) ((x) / M_PI * 180.0)
85 #endif
86 
87 #define deg2rad_const (0.017453292519943295769236907684886f)
88 
89 #include "sick_scan/tcp/colaa.hpp"
90 #include "sick_scan/tcp/colab.hpp"
91 
92 #include <map>
93 #include <climits>
96 
102 void swap_endian(unsigned char *ptr, int numBytes)
103 {
104  unsigned char *buf = (ptr);
105  unsigned char tmpChar;
106  for (int i = 0; i < numBytes / 2; i++)
107  {
108  tmpChar = buf[numBytes - 1 - i];
109  buf[numBytes - 1 - i] = buf[i];
110  buf[i] = tmpChar;
111  }
112 }
113 
114 
122 std::vector<unsigned char> stringToVector(std::string s)
123 {
124  std::vector<unsigned char> result;
125  for (size_t j = 0; j < s.length(); j++)
126  {
127  result.push_back(s[j]);
128  }
129  return result;
130 
131 }
132 
133 
139 static int getDiagnosticErrorCode() // workaround due to compiling error under Visual C++
140 {
141 #ifdef _MSC_VER
142 #undef ERROR
143  return(2);
144 #else
145  return (diagnostic_msgs::DiagnosticStatus::ERROR);
146 #endif
147 }
148 
156 const std::string binScanfGetStringFromVec(std::vector<unsigned char> *replyDummy, int off, long len)
157 {
158  std::string s;
159  s = "";
160  for (int i = 0; i < len; i++)
161  {
162  char ch = (char) ((*replyDummy)[i + off]);
163  s += ch;
164  }
165  return (s);
166 }
167 
168 namespace sick_scan
169 {
177  unsigned char sick_crc8(unsigned char *msgBlock, int len)
178  {
179  unsigned char xorVal = 0x00;
180  int off = 0;
181  for (int i = off; i < len; i++)
182  {
183 
184  unsigned char val = msgBlock[i];
185  xorVal ^= val;
186  }
187  return (xorVal);
188  }
189 
195  std::string stripControl(std::vector<unsigned char> s)
196  {
197  bool isParamBinary = false;
198  int spaceCnt = 0x00;
199  int cnt0x02 = 0;
200 
201  for (size_t i = 0; i < s.size(); i++)
202  {
203  if (s[i] != 0x02)
204  {
205  isParamBinary = false;
206 
207  }
208  else
209  {
210  cnt0x02++;
211  }
212  if (i > 4)
213  {
214  break;
215  }
216  }
217  if (4 == cnt0x02)
218  {
219  isParamBinary = true;
220  }
221  std::string dest;
222  if (isParamBinary == true)
223  {
224  int parseState = 0;
225 
226  unsigned long lenId = 0x00;
227  char szDummy[255] = {0};
228  for (size_t i = 0; i < s.size(); i++)
229  {
230  switch (parseState)
231  {
232  case 0:
233  if (s[i] == 0x02)
234  {
235  dest += "<STX>";
236  }
237  else
238  {
239  dest += "?????";
240  }
241  if (i == 3)
242  {
243  parseState = 1;
244  }
245  break;
246  case 1:
247  lenId |= s[i] << (8 * (7 - i));
248  if (i == 7)
249  {
250  sprintf(szDummy, "<Len=%04lu>", lenId);
251  dest += szDummy;
252  parseState = 2;
253  }
254  break;
255  case 2:
256  {
257  unsigned long dataProcessed = i - 8;
258  if (s[i] == ' ')
259  {
260  spaceCnt++;
261  }
262  if (spaceCnt == 2)
263  {
264  parseState = 3;
265  }
266  dest += s[i];
267  if (dataProcessed >= (lenId - 1))
268  {
269  parseState = 4;
270  }
271 
272  break;
273  }
274 
275  case 3:
276  {
277  char ch = dest[dest.length() - 1];
278  if (ch != ' ')
279  {
280  dest += ' ';
281  }
282  sprintf(szDummy, "0x%02x", s[i]);
283  dest += szDummy;
284 
285  unsigned long dataProcessed = i - 8;
286  if (dataProcessed >= (lenId - 1))
287  {
288  parseState = 4;
289  }
290  break;
291  }
292  case 4:
293  {
294  sprintf(szDummy, " CRC:<0x%02x>", s[i]);
295  dest += szDummy;
296  break;
297  }
298  default:
299  break;
300  }
301  }
302  }
303  else
304  {
305  for (size_t i = 0; i < s.size(); i++)
306  {
307 
308  if (s[i] >= ' ')
309  {
310  // <todo> >= 0x80
311  dest += s[i];
312  }
313  else
314  {
315  switch (s[i])
316  {
317  case 0x02:
318  dest += "<STX>";
319  break;
320  case 0x03:
321  dest += "<ETX>";
322  break;
323  }
324  }
325  }
326  }
327 
328  return (dest);
329  }
330 
336  diagnosticPub_(NULL), parser_(parser)
337  // FIXME All Tims have 15Hz
338  {
340 
341  setSensorIsRadar(false);
342  init_cmdTables();
343 #ifndef _MSC_VER
344  dynamic_reconfigure::Server<sick_scan::SickScanConfig>::CallbackType f;
345  f = boost::bind(&sick_scan::SickScanCommon::update_config, this, _1, _2);
346  dynamic_reconfigure_server_.setCallback(f);
347 #else
348  // For simulation under MS Visual c++ the update config is switched off
349  {
350  SickScanConfig cfg;
351  ros::NodeHandle tmp("~");
352  double min_angle, max_angle, res_angle;
353  tmp.getParam(PARAM_MIN_ANG, min_angle);
354  tmp.getParam(PARAM_MAX_ANG, max_angle);
355  tmp.getParam(PARAM_RES_ANG, res_angle);
356  cfg.min_ang = min_angle;
357  cfg.max_ang = max_angle;
358  cfg.skip = 0;
359  update_config(cfg);
360  }
361 #endif
362  // datagram publisher (only for debug)
363  ros::NodeHandle pn("~");
364  pn.param<bool>("publish_datagram", publish_datagram_, false);
365  if (publish_datagram_)
366  {
367  datagram_pub_ = nh_.advertise<std_msgs::String>("datagram", 1000);
368  }
369  std::string cloud_topic_val = "cloud";
370  pn.getParam("cloud_topic", cloud_topic_val);
371  std::string frame_id_val = cloud_topic_val;
372  pn.getParam("frame_id", frame_id_val);
373 
374 
375  cloud_marker_ = 0;
376  publish_lferec_ = false;
377  publish_lidoutputstate_ = false;
378  const std::string scannername = parser_->getCurrentParamPtr()->getScannerName();
380  {
381  lferec_pub_ = nh_.advertise<sick_scan::LFErecMsg>(scannername + "/lferec", 100);
382  lidoutputstate_pub_ = nh_.advertise<sick_scan::LIDoutputstateMsg>(scannername + "/lidoutputstate", 100);
383  publish_lferec_ = true;
385  cloud_marker_ = new sick_scan::SickScanMarker(&nh_, scannername + "/marker", frame_id_val); // "cloud");
386  }
387 
388  // Pointcloud2 publisher
389  //
390 
391 
392  ROS_INFO("Publishing laserscan-pointcloud2 to %s", cloud_topic_val.c_str());
393  cloud_pub_ = nh_.advertise<sensor_msgs::PointCloud2>(cloud_topic_val, 100);
394 
395  imuScan_pub_ = nh_.advertise<sensor_msgs::Imu>("imu", 100);
396 
397 
398  Encoder_pub = nh_.advertise<sick_scan::Encoder>("encoder", 100);
399  // scan publisher
400  pub_ = nh_.advertise<sensor_msgs::LaserScan>("scan", 1000);
401 
402 #ifndef _MSC_VER
403  diagnostics_.setHardwareID("none"); // set from device after connection
405  // frequency should be target +- 10%.
408  &expectedFrequency_, 0.1,
409  10),
410  // timestamp delta can be from 0.0 to 1.3x what it ideally is.
412  -1, 1.3 * 1.0 /
414  config_.time_offset));
415  ROS_ASSERT(diagnosticPub_ != NULL);
416 #endif
417  }
418 
424  {
425  /*
426  * Stop streaming measurements
427  */
428  const char requestScanData0[] = {"\x02sEN LMDscandata 0\x03\0"};
429  int result = sendSOPASCommand(requestScanData0, NULL);
430  if (result != 0)
431  {
432  // use printf because we cannot use ROS_ERROR from the destructor
433  printf("\nSOPAS - Error stopping streaming scan data!\n");
434  }
435  else
436  {
437  printf("\nSOPAS - Stopped streaming scan data.\n");
438  }
439 
441  {
442  if(sendSOPASCommand("\x02sEN LFErec 0\x03", NULL) != 0 // TiM781S: deactivate LFErec messages, send "sEN LFErec 0"
443  || sendSOPASCommand("\x02sEN LIDoutputstate 0\x03", NULL) != 0 // TiM781S: deactivate LIDoutputstate messages, send "sEN LIDoutputstate 0"
444  || sendSOPASCommand("\x02sEN LIDinputstate 0\x03", NULL) != 0) // TiM781S: deactivate LIDinputstate messages, send "sEN LIDinputstate 0"
445  {
446  // use printf because we cannot use ROS_ERROR from the destructor
447  printf("\nSOPAS - Error stopping streaming LFErec, LIDoutputstate and LIDinputstate messages!\n");
448  }
449  else
450  {
451  printf("\nSOPAS - Stopped streaming LFErec, LIDoutputstate and LIDinputstate messages\n");
452  }
453  }
454 
455  return result;
456  }
457 
463  unsigned long SickScanCommon::convertBigEndianCharArrayToUnsignedLong(const unsigned char *vecArr)
464  {
465  unsigned long val = 0;
466  for (int i = 0; i < 4; i++)
467  {
468  val = val << 8;
469  val |= vecArr[i];
470  }
471  return (val);
472  }
473 
474 
480  int sick_scan::SickScanCommon::checkForBinaryAnswer(const std::vector<unsigned char> *reply)
481  {
482  int retVal = -1;
483 
484  if (reply == NULL)
485  {
486  }
487  else
488  {
489  if (reply->size() < 8)
490  {
491  retVal = -1;
492  }
493  else
494  {
495  const unsigned char *ptr = &((*reply)[0]);
496  unsigned binId = convertBigEndianCharArrayToUnsignedLong(ptr);
497  unsigned cmdLen = convertBigEndianCharArrayToUnsignedLong(ptr + 4);
498  if (binId == 0x02020202)
499  {
500  int replyLen = reply->size();
501  if (replyLen == 8 + cmdLen + 1)
502  {
503  retVal = cmdLen;
504  }
505  }
506  }
507  }
508  return (retVal);
509 
510  }
511 
512 
518  {
519  /*
520  * Set Maintenance access mode to allow reboot to be sent
521  */
522  std::vector<unsigned char> access_reply;
523  // changed from "03" to "3"
524  int result = sendSOPASCommand("\x02sMN SetAccessMode 3 F4724744\x03\0", &access_reply);
525  if (result != 0)
526  {
527  ROS_ERROR("SOPAS - Error setting access mode");
528  diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
529  return false;
530  }
531  std::string access_reply_str = replyToString(access_reply);
532  if (access_reply_str != "sAN SetAccessMode 1")
533  {
534  ROS_ERROR_STREAM("SOPAS - Error setting access mode, unexpected response : " << access_reply_str);
535  diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
536  return false;
537  }
538 
539  /*
540  * Send reboot command
541  */
542  std::vector<unsigned char> reboot_reply;
543  result = sendSOPASCommand("\x02sMN mSCreboot\x03\0", &reboot_reply);
544  if (result != 0)
545  {
546  ROS_ERROR("SOPAS - Error rebooting scanner");
547  diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error rebooting device.");
548  return false;
549  }
550  std::string reboot_reply_str = replyToString(reboot_reply);
551  if (reboot_reply_str != "sAN mSCreboot")
552  {
553  ROS_ERROR_STREAM("SOPAS - Error rebooting scanner, unexpected response : " << reboot_reply_str);
554  diagnostics_.broadcast(getDiagnosticErrorCode(), "SOPAS - Error setting access mode.");
555  return false;
556  }
557 
558  ROS_INFO("SOPAS - Rebooted scanner");
559 
560  // Wait a few seconds after rebooting
561  ros::Duration(15.0).sleep();
562 
563  return true;
564  }
565 
570  {
571  delete cloud_marker_;
572  delete diagnosticPub_;
573 
574  printf("sick_scan driver exiting.\n");
575  }
576 
577 
583  std::string SickScanCommon::generateExpectedAnswerString(const std::vector<unsigned char> requestStr)
584  {
585  std::string expectedAnswer = "";
586  int i = 0;
587  char cntWhiteCharacter = 0;
588  int initalTokenCnt = 2; // number of initial token to identify command
589  std::map<std::string, int> specialTokenLen;
590  char firstToken[1024] = {0};
591  specialTokenLen["sRI"] = 1; // for SRi-Command only the first token identify the command
592  std::string tmpStr = "";
593  int cnt0x02 = 0;
594  bool isBinary = false;
595  for (size_t i = 0; i < 4; i++)
596  {
597  if (i < requestStr.size())
598  {
599  if (requestStr[i] == 0x02)
600  {
601  cnt0x02++;
602  }
603 
604  }
605  }
606 
607  int iStop = requestStr.size(); // copy string until end of string
608  if (cnt0x02 == 4)
609  {
610 
611  int cmdLen = 0;
612  for (int i = 0; i < 4; i++)
613  {
614  cmdLen |= cmdLen << 8;
615  cmdLen |= requestStr[i + 4];
616  }
617  iStop = cmdLen + 8;
618  isBinary = true;
619 
620  }
621  int iStart = (isBinary == true) ? 8 : 0;
622  for (int i = iStart; i < iStop; i++)
623  {
624  tmpStr += (char) requestStr[i];
625  }
626  if (isBinary)
627  {
628  tmpStr = "\x2" + tmpStr;
629  }
630  if (sscanf(tmpStr.c_str(), "\x2%s", firstToken) == 1)
631  {
632  if (specialTokenLen.find(firstToken) != specialTokenLen.end())
633  {
634  initalTokenCnt = specialTokenLen[firstToken];
635 
636  }
637  }
638 
639  for (int i = iStart; i < iStop; i++)
640  {
641  if ((requestStr[i] == ' ') || (requestStr[i] == '\x3'))
642  {
643  cntWhiteCharacter++;
644  }
645  if (cntWhiteCharacter >= initalTokenCnt)
646  {
647  break;
648  }
649  if (requestStr[i] == '\x2')
650  {
651  }
652  else
653  {
654  expectedAnswer += requestStr[i];
655  }
656  }
657 
661  std::map<std::string, std::string> keyWordMap;
662  keyWordMap["sWN"] = "sWA";
663  keyWordMap["sRN"] = "sRA";
664  keyWordMap["sRI"] = "sRA";
665  keyWordMap["sMN"] = "sAN";
666  keyWordMap["sEN"] = "sEA";
667 
668  for (std::map<std::string, std::string>::iterator it = keyWordMap.begin(); it != keyWordMap.end(); it++)
669  {
670 
671  std::string keyWord = it->first;
672  std::string newKeyWord = it->second;
673 
674  size_t pos = expectedAnswer.find(keyWord);
675  if (pos == std::string::npos)
676  {
677 
678  }
679  else
680  {
681  if (pos == 0) // must be 0, if keyword has been found
682  {
683  expectedAnswer.replace(pos, keyWord.length(), newKeyWord);
684  }
685  else
686  {
687  ROS_WARN("Unexpected position of key identifier.\n");
688  }
689  }
690 
691  }
692  return (expectedAnswer);
693 
694  }
695 
703  int SickScanCommon::sendSopasAndCheckAnswer(std::string requestStr, std::vector<unsigned char> *reply, int cmdId = -1)
704  {
705  std::vector<unsigned char> requestStringVec;
706  for (size_t i = 0; i < requestStr.length(); i++)
707  {
708  requestStringVec.push_back(requestStr[i]);
709  }
710  int retCode = sendSopasAndCheckAnswer(requestStringVec, reply, cmdId);
711  return (retCode);
712  }
713 
721  int SickScanCommon::sendSopasAndCheckAnswer(std::vector<unsigned char> requestStr, std::vector<unsigned char> *reply,
722  int cmdId = -1)
723  {
724  std::lock_guard<std::mutex> send_lock_guard(sopasSendMutex); // lock send mutex in case of asynchronous service calls
725 
726  std::string cmdStr = "";
727  int cmdLen = 0;
728  for (size_t i = 0; i < requestStr.size(); i++)
729  {
730  cmdLen++;
731  cmdStr += (char) requestStr[i];
732  }
733  int result = -1;
734 
735  std::string errString;
736  if (cmdId == -1)
737  {
738  errString = "Error unexpected Sopas Answer for request " + stripControl(requestStr);
739  }
740  else
741  {
742  errString = this->sopasCmdErrMsg[cmdId];
743  }
744 
745  std::string expectedAnswer = generateExpectedAnswerString(requestStr);
746 
747  // send sopas cmd
748 
749  std::string reqStr = replyToString(requestStr);
750  ROS_INFO("Sending : %s", stripControl(requestStr).c_str());
751  result = sendSOPASCommand(cmdStr.c_str(), reply, cmdLen);
752  std::string replyStr = replyToString(*reply);
753  std::vector<unsigned char> replyVec;
754  replyStr = "<STX>" + replyStr + "<ETX>";
755  replyVec = stringToVector(replyStr);
756  ROS_INFO("Receiving: %s", stripControl(replyVec).c_str());
757 
758  if (result != 0)
759  {
760  std::string tmpStr = "SOPAS Communication -" + errString;
761  ROS_INFO("%s\n", tmpStr.c_str());
763  }
764  else
765  {
766  std::string answerStr = replyToString(*reply);
767  std::string searchPattern = generateExpectedAnswerString(requestStr);
768 
769  if (answerStr.find(searchPattern) != std::string::npos)
770  {
771  result = 0;
772  }
773  else
774  {
775  if (cmdId == CMD_START_IMU_DATA)
776  {
777  ROS_INFO("IMU-Data transfer started. No checking of reply to avoid confusing with LMD Scandata\n");
778  result = 0;
779  }
780  else
781  {
782  std::string tmpMsg = "Error Sopas answer mismatch " + errString + "Answer= >>>" + answerStr + "<<<";
783  ROS_ERROR("%s\n", tmpMsg.c_str());
785  result = -1;
786  }
787  }
788  }
789  return result;
790 
791  }
792 
799  {
800  readTimeOutInMs = timeOutInMs;
801  }
802 
809  {
810  return (readTimeOutInMs);
811  }
812 
819  {
820  return m_protocolId;
821  }
822 
828  {
829  m_protocolId = cola_dialect_id;
830  }
831 
837  {
838  int result = init_device();
839  if (result != 0)
840  {
841  ROS_FATAL("Failed to init device: %d", result);
842  return result;
843  }
844 
845  result = init_scanner();
846  if (result != 0)
847  {
848  ROS_INFO("Failed to init scanner Error Code: %d\nWaiting for timeout...\n"
849  "If the communication mode set in the scanner memory is different from that used by the driver, the scanner's communication mode is changed.\n"
850  "This requires a restart of the TCP-IP connection, which can extend the start time by up to 30 seconds. There are two ways to prevent this:\n"
851  "1. [Recommended] Set the communication mode with the SOPAS ET software to binary and save this setting in the scanner's EEPROM.\n"
852  "2. Use the parameter \"use_binary_protocol\" to overwrite the default settings of the driver.",
853  result);
854  }
855 
856  return result;
857  }
858 
859 
865  {
867  sopasCmdMaskVec.resize(
868  SickScanCommon::CMD_END); // you for cmd with variable content. sprintf should print into corresponding sopasCmdVec
869  sopasCmdErrMsg.resize(
870  SickScanCommon::CMD_END); // you for cmd with variable content. sprintf should print into corresponding sopasCmdVec
874 
875  std::string unknownStr = "Command or Error message not defined";
876  for (int i = 0; i < SickScanCommon::CMD_END; i++)
877  {
878  sopasCmdVec[i] = unknownStr;
879  sopasCmdMaskVec[i] = unknownStr; // for cmd with variable content. sprintf should print into corresponding sopasCmdVec
880  sopasCmdErrMsg[i] = unknownStr;
881  sopasReplyVec[i] = unknownStr;
882  sopasReplyStrVec[i] = unknownStr;
883  }
884 
885  sopasCmdVec[CMD_DEVICE_IDENT_LEGACY] = "\x02sRI 0\x03\0";
886  sopasCmdVec[CMD_DEVICE_IDENT] = "\x02sRN DeviceIdent\x03\0";
887  sopasCmdVec[CMD_REBOOT] = "\x02sMN mSCreboot\x03";
888  sopasCmdVec[CMD_WRITE_EEPROM] = "\x02sMN mEEwriteall\x03";
889  sopasCmdVec[CMD_SERIAL_NUMBER] = "\x02sRN SerialNumber\x03\0";
890  sopasCmdVec[CMD_FIRMWARE_VERSION] = "\x02sRN FirmwareVersion\x03\0";
891  sopasCmdVec[CMD_DEVICE_STATE] = "\x02sRN SCdevicestate\x03\0";
892  sopasCmdVec[CMD_OPERATION_HOURS] = "\x02sRN ODoprh\x03\0";
893  sopasCmdVec[CMD_POWER_ON_COUNT] = "\x02sRN ODpwrc\x03\0";
894  sopasCmdVec[CMD_LOCATION_NAME] = "\x02sRN LocationName\x03\0";
895  sopasCmdVec[CMD_ACTIVATE_STANDBY] = "\x02sMN LMCstandby\x03";
896  sopasCmdVec[CMD_SET_ACCESS_MODE_3] = "\x02sMN SetAccessMode 3 F4724744\x03\0";
897  sopasCmdVec[CMD_SET_ACCESS_MODE_3_SAFETY_SCANNER] = "\x02sMN SetAccessMode 3 6FD62C05\x03\0";
898  sopasCmdVec[CMD_GET_OUTPUT_RANGES] = "\x02sRN LMPoutputRange\x03";
899  sopasCmdVec[CMD_RUN] = "\x02sMN Run\x03\0";
900  sopasCmdVec[CMD_STOP_SCANDATA] = "\x02sEN LMDscandata 0\x03";
901  sopasCmdVec[CMD_START_SCANDATA] = "\x02sEN LMDscandata 1\x03";
902  sopasCmdVec[CMD_START_RADARDATA] = "\x02sEN LMDradardata 1\x03";
903  sopasCmdVec[CMD_ACTIVATE_NTP_CLIENT] = "\x02sWN TSCRole 1\x03";
904  sopasCmdVec[CMD_SET_NTP_INTERFACE_ETH] = "\x02sWN TSCTCInterface 0\x03";
905 
906  /*
907  * Radar specific commands
908  */
909  sopasCmdVec[CMD_SET_TRANSMIT_RAWTARGETS_ON] = "\x02sWN TransmitTargets 1\x03"; // transmit raw target for radar
910  sopasCmdVec[CMD_SET_TRANSMIT_RAWTARGETS_OFF] = "\x02sWN TransmitTargets 0\x03"; // do not transmit raw target for radar
911  sopasCmdVec[CMD_SET_TRANSMIT_OBJECTS_ON] = "\x02sWN TransmitObjects 1\x03"; // transmit objects from radar tracking
912  sopasCmdVec[CMD_SET_TRANSMIT_OBJECTS_OFF] = "\x02sWN TransmitObjects 0\x03"; // do not transmit objects from radar tracking
913  sopasCmdVec[CMD_SET_TRACKING_MODE_0] = "\x02sWN TCTrackingMode 0\x03"; // set object tracking mode to BASIC
914  sopasCmdVec[CMD_SET_TRACKING_MODE_1] = "\x02sWN TCTrackingMode 1\x03"; // set object tracking mode to TRAFFIC
915 
916 
917  sopasCmdVec[CMD_LOAD_APPLICATION_DEFAULT] = "\x02sMN mSCloadappdef\x03"; // load application default
918  sopasCmdVec[CMD_DEVICE_TYPE] = "\x02sRN DItype\x03"; // ask for radar device type
919  sopasCmdVec[CMD_ORDER_NUMBER] = "\x02sRN OrdNum\x03"; // ask for radar order number
920 
921 
922 
923  sopasCmdVec[CMD_START_MEASUREMENT] = "\x02sMN LMCstartmeas\x03";
924  sopasCmdVec[CMD_STOP_MEASUREMENT] = "\x02sMN LMCstopmeas\x03";
925  sopasCmdVec[CMD_APPLICATION_MODE_FIELD_ON] = "\x02sWN SetActiveApplications 1 FEVL 1\x03"; // <STX>sWN{SPC}SetActiveApplications{SPC}1{SPC}FEVL{SPC}1<ETX>
926  sopasCmdVec[CMD_APPLICATION_MODE_FIELD_OFF] = "\x02sWN SetActiveApplications 1 FEVL 0\x03"; // <STX>sWN{SPC}SetActiveApplications{SPC}1{SPC}FEVL{SPC}1<ETX>
927  sopasCmdVec[CMD_APPLICATION_MODE_RANGING_ON] = "\x02sWN SetActiveApplications 1 RANG 1\x03";
928  sopasCmdVec[CMD_SET_TO_COLA_A_PROTOCOL] = "\x02sWN EIHstCola 0\x03";
929  sopasCmdVec[CMD_GET_PARTIAL_SCANDATA_CFG] = "\x02sRN LMDscandatacfg\x03";//<STX>sMN{SPC}mLMPsetscancfg{SPC } +5000{SPC}+1{SPC}+5000{SPC}-450000{SPC}+2250000<ETX>
930  sopasCmdVec[CMD_GET_PARTIAL_SCAN_CFG] = "\x02sRN LMPscancfg\x03";
931  sopasCmdVec[CMD_SET_TO_COLA_B_PROTOCOL] = "\x02sWN EIHstCola 1\x03";
932 
933  sopasCmdVec[CMD_STOP_IMU_DATA] = "\x02sEN InertialMeasurementUnit 0\x03";
934  sopasCmdVec[CMD_START_IMU_DATA] = "\x02sEN InertialMeasurementUnit 1\x03";
935  sopasCmdVec[CMD_SET_ENCODER_MODE_NO] = "\x02sWN LICencset 0\x03";
936  sopasCmdVec[CMD_SET_ENCODER_MODE_SI] = "\x02sWN LICencset 1\x03";
937  sopasCmdVec[CMD_SET_ENCODER_MODE_DP] = "\x02sWN LICencset 2\x03";
938  sopasCmdVec[CMD_SET_ENCODER_MODE_DL] = "\x02sWN LICencset 3\x03";
939  sopasCmdVec[CMD_SET_INCREMENTSOURCE_ENC] = "\x02sWN LICsrc 1\x03";
940  sopasCmdVec[CMD_SET_3_4_TO_ENCODER] = "\x02sWN DO3And4Fnc 1\x03";
941  //TODO remove this and add param
942  sopasCmdVec[CMD_SET_ENOCDER_RES_1] = "\x02sWN LICencres 1\x03";
943 
944  sopasCmdVec[CMD_SET_SCANDATACONFIGNAV] = "\x02sMN mLMPsetscancfg +2000 +1 +7500 +3600000 0 +2500 0 0 +2500 0 0 +2500 0 0\x03";
945  /*
946  * Special configuration for NAV Scanner
947  * in hex
948  * sMN mLMPsetscancfg 0320 01 09C4 0 0036EE80 09C4 0 0 09C4 0 0 09C4 0 0
949  * | | | | | | | | | | | | | |
950  * | | | | | | | | | | | | | +->
951  * | | | | | | | | | | | | +---> 0x0 --> 0 -> 0° start ang for sector 4
952  * | | | | | | | | | | | +-------> 0x09c4 --> 2500 -> 0.25° deg ang res for Sector 4
953  * | | | | | | | | | | +----------> 0x0 --> 0 -> 0° start ang for sector 4
954  * | | | | | | | | | +------------> 0x0 --> 0 -> 0° start ang for sector 3
955  * | | | | | | | | +----------------> 0x09c4 --> 2500 -> 0.25° deg ang res for Sector 3
956  * | | | | | | | +-------------------> 0x0 --> 0 -> 0° start ang for sector 2
957  * | | | | | | +---------------------> 0x0 --> 0 -> 0° start ang for sector 2
958  * | | | | | +------------------------> 0x09c4 --> 2500 -> 0.25° Deg ang res for Sector 2
959  * | | | | +-------------------------------> 0x36EE80h--> 3600000-> 360° stop ang for sector 1
960  * | | | +-------------------------------------> 0x0 --> 0 -> 0° Start ang for sector 1
961  * | | +----------------------------------------> 0x09c4 --> 2500 -> 0.25° Deg ang res for Sector 1
962  * | +---------------------------------------------> 0x01 --> 01 -> 1 Number of active sectors
963  * +------------------------------------------------> 0x0320 --> 0800 -> 8 Hz scanfreq
964  */
965  // 0320 01 09C4 0 0036EE80 09C4 0 0 09C4 0 0 09C4 0 0
966 
967  sopasCmdVec[CMD_SET_LFEREC_ACTIVE] = "\x02sEN LFErec 1\x03"; // TiM781S: activate LFErec messages, send "sEN LFErec 1"
968  sopasCmdVec[CMD_SET_LID_OUTPUTSTATE_ACTIVE] = "\x02sEN LIDoutputstate 1\x03"; // TiM781S: activate LIDoutputstate messages, send "sEN LIDoutputstate 1"
969  sopasCmdVec[CMD_SET_LID_INPUTSTATE_ACTIVE] = "\x02sEN LIDinputstate 1\x03"; // TiM781S: activate LIDinputstate messages, send "sEN LIDinputstate 1"
970 
971  /*
972  * Angle Compensation Command
973  *
974  */
975  sopasCmdVec[CMD_GET_ANGLE_COMPENSATION_PARAM] = "\x02sRN MCAngleCompSin\x03";
976  // defining cmd mask for cmds with variable input
977  sopasCmdMaskVec[CMD_SET_PARTIAL_SCAN_CFG] = "\x02sMN mLMPsetscancfg %+d 1 %+d 0 0\x03";//scanfreq [1/100 Hz],angres [1/10000°],
978  sopasCmdMaskVec[CMD_SET_PARTICLE_FILTER] = "\x02sWN LFPparticle %d %d\x03";
979  sopasCmdMaskVec[CMD_SET_MEAN_FILTER] = "\x02sWN LFPmeanfilter %d %d 0\x03";
980  sopasCmdMaskVec[CMD_ALIGNMENT_MODE] = "\x02sWN MMAlignmentMode %d\x03";
981  sopasCmdMaskVec[CMD_APPLICATION_MODE] = "\x02sWN SetActiveApplications 1 %s %d\x03";
982  sopasCmdMaskVec[CMD_SET_OUTPUT_RANGES] = "\x02sWN LMPoutputRange 1 %X %X %X\x03";
983  sopasCmdMaskVec[CMD_SET_OUTPUT_RANGES_NAV3] = "\x02sWN LMPoutputRange 1 %X %X %X %X %X %X %X %X %X %X %X %X\x03";
984  //sopasCmdMaskVec[CMD_SET_PARTIAL_SCANDATA_CFG]= "\x02sWN LMDscandatacfg %02d 00 %d 00 %d 0 %d 0 0 0 1 +1\x03"; //outputChannelFlagId,rssiFlag, rssiResolutionIs16Bit ,EncoderSetings
985  sopasCmdMaskVec[CMD_SET_PARTIAL_SCANDATA_CFG] = "\x02sWN LMDscandatacfg %02d 00 %d %d 0 0 %02d 0 0 0 1 1\x03";//outputChannelFlagId,rssiFlag, rssiResolutionIs16Bit ,EncoderSetings
986  sopasCmdMaskVec[CMD_GET_SAFTY_FIELD_CFG] = "\x02sRN field%03d\x03";
987  /*
988  configuration
989  * in ASCII
990  * sWN LMDscandatacfg %02d 00 %d %d 0 %02d 0 0 0 1 1
991  * | | | | | | | | | | +----------> Output rate -> All scans: 1--> every 1 scan
992  * | | | | | | | | +----------------> Time ->True (unused in Data Processing)
993  * | | | | | | | +-------------------> Comment ->False
994  * | | | | | | +------------------------> Device Name ->False
995  * | | | | | +---------------------------> Position ->False
996  * | | | | +----------------------------------> Encoder ->Param set by Mask
997  * | | | +----------------------------------------> Unit of Remission->Always 0
998  * | | +--------------------------------------------> RSSi Resolution ->0 8Bit 1 16 Bit
999  * | +-------------------------------------------------> Remission data ->Param set by Mask 0 False 1 True
1000  * +--------------------------------------------------------> Data channel ->Param set by Mask
1001 */
1002 
1003  sopasCmdMaskVec[CMD_SET_ECHO_FILTER] = "\x02sWN FREchoFilter %d\x03";
1004  sopasCmdMaskVec[CMD_SET_NTP_UPDATETIME] = "\x02sWN TSCTCupdatetime %d\x03";
1005  sopasCmdMaskVec[CMD_SET_NTP_TIMEZONE] = "sWN TSCTCtimezone %d";
1006  sopasCmdMaskVec[CMD_SET_IP_ADDR] = "\x02sWN EIIpAddr %02X %02X %02X %02X\x03";
1007  sopasCmdMaskVec[CMD_SET_NTP_SERVER_IP_ADDR] = "\x02sWN TSCTCSrvAddr %02X %02X %02X %02X\x03";
1008  sopasCmdMaskVec[CMD_SET_GATEWAY] = "\x02sWN EIgate %02X %02X %02X %02X\x03";
1009  sopasCmdMaskVec[CMD_SET_ENCODER_RES] = "\x02sWN LICencres %f\x03";
1010 
1011  //error Messages
1012  sopasCmdErrMsg[CMD_DEVICE_IDENT_LEGACY] = "Error reading device ident";
1013  sopasCmdErrMsg[CMD_DEVICE_IDENT] = "Error reading device ident for MRS-family";
1014  sopasCmdErrMsg[CMD_SERIAL_NUMBER] = "Error reading SerialNumber";
1015  sopasCmdErrMsg[CMD_FIRMWARE_VERSION] = "Error reading FirmwareVersion";
1016  sopasCmdErrMsg[CMD_DEVICE_STATE] = "Error reading SCdevicestate";
1017  sopasCmdErrMsg[CMD_OPERATION_HOURS] = "Error reading operation hours";
1018  sopasCmdErrMsg[CMD_POWER_ON_COUNT] = "Error reading operation power on counter";
1019  sopasCmdErrMsg[CMD_LOCATION_NAME] = "Error reading Locationname";
1020  sopasCmdErrMsg[CMD_ACTIVATE_STANDBY] = "Error acticvating Standby";
1021  sopasCmdErrMsg[CMD_SET_PARTICLE_FILTER] = "Error setting Particelefilter";
1022  sopasCmdErrMsg[CMD_SET_MEAN_FILTER] = "Error setting Meanfilter";
1023  sopasCmdErrMsg[CMD_ALIGNMENT_MODE] = "Error setting Alignmentmode";
1024  sopasCmdErrMsg[CMD_APPLICATION_MODE] = "Error setting Meanfilter";
1025  sopasCmdErrMsg[CMD_SET_ACCESS_MODE_3] = "Error Access Mode";
1027  sopasCmdErrMsg[CMD_SET_OUTPUT_RANGES] = "Error setting angular ranges";
1028  sopasCmdErrMsg[CMD_GET_OUTPUT_RANGES] = "Error reading angle range";
1029  sopasCmdErrMsg[CMD_RUN] = "FATAL ERROR unable to start RUN mode!";
1030  sopasCmdErrMsg[CMD_SET_PARTIAL_SCANDATA_CFG] = "Error setting Scandataconfig";
1031  sopasCmdErrMsg[CMD_STOP_SCANDATA] = "Error stopping scandata output";
1032  sopasCmdErrMsg[CMD_START_SCANDATA] = "Error starting Scandata output";
1033  sopasCmdErrMsg[CMD_SET_IP_ADDR] = "Error setting IP address";
1034  sopasCmdErrMsg[CMD_SET_GATEWAY] = "Error setting gateway";
1035  sopasCmdErrMsg[CMD_REBOOT] = "Error rebooting the device";
1036  sopasCmdErrMsg[CMD_WRITE_EEPROM] = "Error writing data to EEPRom";
1037  sopasCmdErrMsg[CMD_ACTIVATE_NTP_CLIENT] = "Error activating NTP client";
1038  sopasCmdErrMsg[CMD_SET_NTP_INTERFACE_ETH] = "Error setting NTP interface to ETH";
1039  sopasCmdErrMsg[CMD_SET_NTP_SERVER_IP_ADDR] = "Error setting NTP server Adress";
1040  sopasCmdErrMsg[CMD_SET_NTP_UPDATETIME] = "Error setting NTP update time";
1041  sopasCmdErrMsg[CMD_SET_NTP_TIMEZONE] = "Error setting NTP timezone";
1042  sopasCmdErrMsg[CMD_SET_ENCODER_MODE] = "Error activating encoder in single incremnt mode";
1043  sopasCmdErrMsg[CMD_SET_INCREMENTSOURCE_ENC] = "Error seting encoder increment source to Encoder";
1044  sopasCmdErrMsg[CMD_SET_SCANDATACONFIGNAV] = "Error setting scandata config";
1045  sopasCmdErrMsg[CMD_SET_LFEREC_ACTIVE] = "Error activating LFErec messages";
1046  sopasCmdErrMsg[CMD_SET_LID_OUTPUTSTATE_ACTIVE] = "Error activating LIDoutputstate messages";
1047  sopasCmdErrMsg[CMD_SET_LID_INPUTSTATE_ACTIVE] = "Error activating LIDinputstate messages";
1048  // ML: Add here more useful cmd and mask entries
1049 
1050  // After definition of command, we specify the command sequence for scanner initalisation
1051 
1052 
1053 
1054 
1055 
1057  {
1059  }
1060  else
1061  {
1063  }
1064 
1066  {
1068  }
1069  else
1070  {
1071  //for binary Mode Testing
1073  }
1074 
1075 
1077  {
1079  }
1080 
1081  /*
1082  * NAV2xx supports angle compensation
1083  */
1084  bool isNav2xxOr3xx = false;
1086  {
1087  isNav2xxOr3xx = true;
1088  }
1090  {
1091  isNav2xxOr3xx = true;
1092  }
1093  if (isNav2xxOr3xx)
1094  {
1096  }
1097 
1098 
1099  bool tryToStopMeasurement = true;
1101  {
1102  tryToStopMeasurement = false;
1103  // do not stop measurement for TiM571 otherwise the scanner would not start after start measurement
1104  // do not change the application - not supported for TiM5xx
1105  }
1106  if (parser_->getCurrentParamPtr()->getDeviceIsRadar() == true)
1107  {
1108  sopasCmdChain.push_back(CMD_LOAD_APPLICATION_DEFAULT); // load application default for radar
1109 
1110  tryToStopMeasurement = false;
1111  // do not stop measurement for RMS320 - the RMS320 does not support the stop command
1112  }
1113  if (tryToStopMeasurement)
1114  {
1116  int numberOfLayers = parser_->getCurrentParamPtr()->getNumberOfLayers();
1117 
1118  switch (numberOfLayers)
1119  {
1120  case 4:
1123  sopasCmdChain.push_back(CMD_DEVICE_IDENT);
1124  sopasCmdChain.push_back(CMD_SERIAL_NUMBER);
1125 
1126  break;
1127  case 24:
1128  // just measuring - Application setting not supported
1129  // "Old" device ident command "SRi 0" not supported
1130  sopasCmdChain.push_back(CMD_DEVICE_IDENT);
1131  break;
1132 
1133  default:
1137 
1138  sopasCmdChain.push_back(CMD_SERIAL_NUMBER);
1139  break;
1140  }
1141 
1142  }
1143  sopasCmdChain.push_back(CMD_FIRMWARE_VERSION); // read firmware
1144  sopasCmdChain.push_back(CMD_DEVICE_STATE); // read device state
1145  sopasCmdChain.push_back(CMD_OPERATION_HOURS); // read operation hours
1146  sopasCmdChain.push_back(CMD_POWER_ON_COUNT); // read power on count
1147  sopasCmdChain.push_back(CMD_LOCATION_NAME); // read location name
1149  {
1151  }
1152 
1153  return (0);
1154 
1155  }
1156 
1157 
1163  {
1164 
1165  const int MAX_STR_LEN = 1024;
1166 
1167  int maxNumberOfEchos = 1;
1168 
1169 
1170  maxNumberOfEchos = this->parser_->getCurrentParamPtr()->getNumberOfMaximumEchos(); // 1 for TIM 571, 3 for MRS1104, 5 for 6000
1171 
1172 
1173  bool rssiFlag = false;
1174  bool rssiResolutionIs16Bit = true; //True=16 bit Flase=8bit
1175  int activeEchos = 0;
1176  ros::NodeHandle pn("~");
1177 
1178  pn.getParam("intensity", rssiFlag);
1179  pn.getParam("intensity_resolution_16bit", rssiResolutionIs16Bit);
1180  //check new ip adress and add cmds to write ip to comand chain
1181  std::string sNewIPAddr = "";
1182  boost::asio::ip::address_v4 ipNewIPAddr;
1183  bool setNewIPAddr = false;
1184  setNewIPAddr = pn.getParam("new_IP_address", sNewIPAddr);
1185  if (setNewIPAddr)
1186  {
1187  boost::system::error_code ec;
1188  ipNewIPAddr = boost::asio::ip::address_v4::from_string(sNewIPAddr, ec);
1189  if (ec == boost::system::errc::success)
1190  {
1191  sopasCmdChain.clear();
1193  }
1194  else
1195  {
1196  setNewIPAddr = false;
1197  ROS_ERROR("ERROR: IP ADDRESS could not be parsed Boost Error %s:%d", ec.category().name(), ec.value());;
1198  }
1199 
1200  }
1201  std::string sNTPIpAdress = "";
1202  boost::asio::ip::address_v4 NTPIpAdress;
1203  bool setUseNTP = false;
1204  setUseNTP = pn.getParam("ntp_server_address", sNTPIpAdress);
1205  if (setUseNTP)
1206  {
1207  boost::system::error_code ec;
1208  NTPIpAdress = boost::asio::ip::address_v4::from_string(sNTPIpAdress, ec);
1209  if (ec != boost::system::errc::success)
1210  {
1211  setUseNTP = false;
1212  ROS_ERROR("ERROR: NTP Server IP ADDRESS could not be parsed Boost Error %s:%d", ec.category().name(),
1213  ec.value());;
1214  }
1215  }
1216 
1217  this->parser_->getCurrentParamPtr()->setIntensityResolutionIs16Bit(rssiResolutionIs16Bit);
1218  // parse active_echos entry and set flag array
1219  pn.getParam("active_echos", activeEchos);
1220 
1221  ROS_INFO("Parameter setting for <active_echo: %d>", activeEchos);
1222  std::vector<bool> outputChannelFlag;
1223  outputChannelFlag.resize(maxNumberOfEchos);
1224  int i;
1225  int numOfFlags = 0;
1226  for (i = 0; i < outputChannelFlag.size(); i++)
1227  {
1228  /*
1229  After consultation with the company SICK,
1230  all flags are set to true because the firmware currently does not support single selection of targets.
1231  The selection of the echoes takes place via FREchoFilter.
1232  */
1233  /* former implementation
1234  if (activeEchos & (1 << i))
1235  {
1236  outputChannelFlag[i] = true;
1237  numOfFlags++;
1238  }
1239  else
1240  {
1241  outputChannelFlag[i] = false;
1242  }
1243  */
1244  outputChannelFlag[i] = true; // always true (see comment above)
1245  numOfFlags++;
1246  }
1247 
1248  if (numOfFlags == 0) // Fallback-Solution
1249  {
1250  outputChannelFlag[0] = true;
1251  numOfFlags = 1;
1252  ROS_WARN("Activate at least one echo.");
1253  }
1254 
1255  //================== DEFINE ENCODER SETTING ==========================
1256  int EncoderSetings = -1; //Do not use encoder commands as default
1257  pn.getParam("encoder_mode", EncoderSetings);
1258  this->parser_->getCurrentParamPtr()->setEncoderMode((int8_t) EncoderSetings);
1259  if (parser_->getCurrentParamPtr()->getEncoderMode() >= 0)
1260  {
1262  {
1263  case 0:
1268  break;
1269  case 1:
1274  break;
1275  case 2:
1280  break;
1281  case 3:
1286  break;
1287  }
1288  }
1289  int result;
1290  //================== DEFINE ANGULAR SETTING ==========================
1291  int angleRes10000th = 0;
1292  int angleStart10000th = 0;
1293  int angleEnd10000th = 0;
1294 
1295 
1296  // Mainloop for initial SOPAS cmd-Handling
1297  //
1298  // To add new commands do the followings:
1299  // 1. Define new enum-entry in the enumumation "enum SOPAS_CMD" in the file sick_scan_common.h
1300  // 2. Define new command sequence in the member function init_cmdTables()
1301  // 3. Add cmd-id in the sopasCmdChain to trigger sending of command.
1302  // 4. Add handling of reply by using for the pattern "REPLY_HANDLING" in this code and adding a new case instruction.
1303  // That's all!
1304 
1305 
1306  volatile bool useBinaryCmd = false;
1307  if (this->parser_->getCurrentParamPtr()->getUseBinaryProtocol()) // hard coded for every scanner type
1308  {
1309  useBinaryCmd = true; // shall we talk ascii or binary with the scanner type??
1310  }
1311 
1312  bool useBinaryCmdNow = false;
1313  int maxCmdLoop = 2; // try binary and ascii during startup
1314 
1315  const int shortTimeOutInMs = 5000; // during startup phase to check binary or ascii
1316  const int defaultTimeOutInMs = 120000; // standard time out 120 sec.
1317 
1318  setReadTimeOutInMs(shortTimeOutInMs);
1319 
1320  bool restartDueToProcolChange = false;
1321 
1322  /* NAV310 needs special handling */
1323  /* The NAV310 does not support LMDscandatacfg and rotates clockwise. */
1324  /* The X-axis shows backwards */
1325  bool NAV3xxOutputRangeSpecialHandling=false;
1327  {
1328  NAV3xxOutputRangeSpecialHandling = true;
1329  }
1330 
1331  for (size_t i = 0; i < this->sopasCmdChain.size(); i++)
1332  {
1333  ros::Duration(0.2).sleep(); // could maybe removed
1334 
1335  int cmdId = sopasCmdChain[i]; // get next command
1336  std::string sopasCmd = sopasCmdVec[cmdId];
1337  std::vector<unsigned char> replyDummy;
1338  std::vector<unsigned char> reqBinary;
1339 
1340  std::vector<unsigned char> sopasCmdVec;
1341  for (size_t j = 0; j < sopasCmd.length(); j++)
1342  {
1343  sopasCmdVec.push_back(sopasCmd[j]);
1344  }
1345  ROS_DEBUG("Command: %s", stripControl(sopasCmdVec).c_str());
1346 
1347  // switch to either binary or ascii after switching the command mode
1348  // via ... command
1349 
1350 
1351  for (int iLoop = 0; iLoop < maxCmdLoop; iLoop++)
1352  {
1353  if (iLoop == 0)
1354  {
1355  useBinaryCmdNow = useBinaryCmd; // start with expected value
1356 
1357  }
1358  else
1359  {
1360  useBinaryCmdNow = !useBinaryCmdNow;// try the other option
1361  useBinaryCmd = useBinaryCmdNow; // and use it from now on as default
1362 
1363  }
1364 
1365  this->setProtocolType(useBinaryCmdNow ? CoLa_B : CoLa_A);
1366 
1367 
1368  if (useBinaryCmdNow)
1369  {
1370  this->convertAscii2BinaryCmd(sopasCmd.c_str(), &reqBinary);
1371  result = sendSopasAndCheckAnswer(reqBinary, &replyDummy);
1372  sopasReplyBinVec[cmdId] = replyDummy;
1373  }
1374  else
1375  {
1376  result = sendSopasAndCheckAnswer(sopasCmd.c_str(), &replyDummy);
1377  }
1378  if (result == 0) // command sent successfully
1379  {
1380  // useBinaryCmd holds information about last successful command mode
1381  break;
1382  }
1383  }
1384  if (result != 0)
1385  {
1386  ROS_ERROR("%s", sopasCmdErrMsg[cmdId].c_str());
1388  }
1389  else
1390  {
1391  sopasReplyStrVec[cmdId] = replyToString(replyDummy);
1392  }
1393 
1394  //============================================
1395  // Handle reply of specific commands here by inserting new case instruction
1396  // REPLY_HANDLING
1397  //============================================
1398  maxCmdLoop = 1;
1399 
1400 
1401  // handle special configuration commands ...
1402 
1403  switch (cmdId)
1404  {
1405 
1407  {
1408  bool protocolCheck = checkForProtocolChangeAndMaybeReconnect(useBinaryCmdNow);
1409  if (false == protocolCheck)
1410  {
1411  restartDueToProcolChange = true;
1412  }
1413  useBinaryCmd = useBinaryCmdNow;
1414  setReadTimeOutInMs(defaultTimeOutInMs);
1415  }
1416  break;
1418  {
1419  bool protocolCheck = checkForProtocolChangeAndMaybeReconnect(useBinaryCmdNow);
1420  if (false == protocolCheck)
1421  {
1422  restartDueToProcolChange = true;
1423  }
1424 
1425  useBinaryCmd = useBinaryCmdNow;
1426  setReadTimeOutInMs(defaultTimeOutInMs);
1427  }
1428  break;
1429 
1430  /*
1431  SERIAL_NUMBER: Device ident must be read before!
1432  */
1433 
1434  case CMD_DEVICE_IDENT: // FOR MRS6xxx the Device Ident holds all specific information (used instead of CMD_SERIAL_NUMBER)
1435  {
1436  std::string deviceIdent = "";
1437  int cmdLen = this->checkForBinaryAnswer(&replyDummy);
1438  if (cmdLen == -1)
1439  {
1440  int idLen = 0;
1441  int versionLen = 0;
1442  // ASCII-Return
1443  std::string deviceIdentKeyWord = "sRA DeviceIdent";
1444  char *ptr = (char *) (&(replyDummy[0]));
1445  ptr++; // skip 0x02
1446  ptr += deviceIdentKeyWord.length();
1447  ptr++; //skip blank
1448  sscanf(ptr, "%d", &idLen);
1449  char *ptr2 = strchr(ptr, ' ');
1450  if (ptr2 != NULL)
1451  {
1452  ptr2++;
1453  for (int i = 0; i < idLen; i++)
1454  {
1455  deviceIdent += *ptr2;
1456  ptr2++;
1457  }
1458 
1459  }
1460  ptr = ptr2;
1461  ptr++; //skip blank
1462  sscanf(ptr, "%d", &versionLen);
1463  ptr2 = strchr(ptr, ' ');
1464  if (ptr2 != NULL)
1465  {
1466  ptr2++;
1467  deviceIdent += " V";
1468  for (int i = 0; i < versionLen; i++)
1469  {
1470  deviceIdent += *ptr2;
1471  ptr2++;
1472  }
1473  }
1474  diagnostics_.setHardwareID(deviceIdent);
1475  if (!isCompatibleDevice(deviceIdent))
1476  {
1477  return ExitFatal;
1478  }
1479 // ROS_ERROR("BINARY REPLY REQUIRED");
1480  }
1481  else
1482  {
1483  long dummy0, dummy1, identLen, versionLen;
1484  dummy0 = 0;
1485  dummy1 = 0;
1486  identLen = 0;
1487  versionLen = 0;
1488 
1489  const char *scanMask0 = "%04y%04ysRA DeviceIdent %02y";
1490  const char *scanMask1 = "%02y";
1491  unsigned char *replyPtr = &(replyDummy[0]);
1492  int scanDataLen0 = binScanfGuessDataLenFromMask(scanMask0);
1493  int scanDataLen1 = binScanfGuessDataLenFromMask(scanMask1); // should be: 2
1494  binScanfVec(&replyDummy, scanMask0, &dummy0, &dummy1, &identLen);
1495 
1496  std::string identStr = binScanfGetStringFromVec(&replyDummy, scanDataLen0, identLen);
1497  int off = scanDataLen0 + identLen; // consuming header + fixed part + ident
1498 
1499  std::vector<unsigned char> restOfReplyDummy = std::vector<unsigned char>(replyDummy.begin() + off,
1500  replyDummy.end());
1501 
1502  versionLen = 0;
1503  binScanfVec(&restOfReplyDummy, "%02y", &versionLen);
1504  std::string versionStr = binScanfGetStringFromVec(&restOfReplyDummy, scanDataLen1, versionLen);
1505  std::string fullIdentVersionInfo = identStr + " V" + versionStr;
1506  diagnostics_.setHardwareID(fullIdentVersionInfo);
1507  if (!isCompatibleDevice(fullIdentVersionInfo))
1508  {
1509  return ExitFatal;
1510  }
1511 
1512  }
1513  break;
1514  }
1515 
1516 
1517  case CMD_SERIAL_NUMBER:
1518  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 4)
1519  {
1520  // do nothing for MRS1104 here
1521  }
1522  else
1523  {
1526 
1528  {
1529  return ExitFatal;
1530  }
1531  }
1532  break;
1533  /*
1534  DEVICE_STATE
1535  */
1536  case CMD_DEVICE_STATE:
1537  {
1538  int deviceState = -1;
1539  /*
1540  * Process device state, 0=Busy, 1=Ready, 2=Error
1541  * If configuration parameter is set, try resetting device in error state
1542  */
1543 
1544  int iRetVal = 0;
1545  if (useBinaryCmd)
1546  {
1547  long dummy0 = 0x00;
1548  long dummy1 = 0x00;
1549  deviceState = 0x00; // must be set to zero (because only one byte will be copied)
1550  iRetVal = binScanfVec(&(sopasReplyBinVec[CMD_DEVICE_STATE]), "%4y%4ysRA SCdevicestate %1y", &dummy0,
1551  &dummy1, &deviceState);
1552  }
1553  else
1554  {
1555  iRetVal = sscanf(sopasReplyStrVec[CMD_DEVICE_STATE].c_str(), "sRA SCdevicestate %d", &deviceState);
1556  }
1557  if (iRetVal > 0) // 1 or 3 (depending of ASCII or Binary)
1558  {
1559  switch (deviceState)
1560  {
1561  case 0:
1562  ROS_DEBUG("Laser is busy");
1563  break;
1564  case 1:
1565  ROS_DEBUG("Laser is ready");
1566  break;
1567  case 2:
1568  ROS_ERROR_STREAM("Laser reports error state : " << sopasReplyStrVec[CMD_DEVICE_STATE]);
1569  if (config_.auto_reboot)
1570  {
1571  rebootScanner();
1572  };
1573  break;
1574  default:
1575  ROS_WARN_STREAM("Laser reports unknown devicestate : " << sopasReplyStrVec[CMD_DEVICE_STATE]);
1576  break;
1577  }
1578  }
1579  }
1580  break;
1581 
1582  case CMD_OPERATION_HOURS:
1583  {
1584  int operationHours = -1;
1585  int iRetVal = 0;
1586  /*
1587  * Process device state, 0=Busy, 1=Ready, 2=Error
1588  * If configuration parameter is set, try resetting device in error state
1589  */
1590  if (useBinaryCmd)
1591  {
1592  long dummy0, dummy1;
1593  dummy0 = 0;
1594  dummy1 = 0;
1595  operationHours = 0;
1596  iRetVal = binScanfVec(&(sopasReplyBinVec[CMD_OPERATION_HOURS]), "%4y%4ysRA ODoprh %4y", &dummy0, &dummy1,
1597  &operationHours);
1598  }
1599  else
1600  {
1601  operationHours = 0;
1602  iRetVal = sscanf(sopasReplyStrVec[CMD_OPERATION_HOURS].c_str(), "sRA ODoprh %x", &operationHours);
1603  }
1604  if (iRetVal > 0)
1605  {
1606  double hours = 0.1 * operationHours;
1607  pn.setParam("operationHours", hours);
1608  }
1609  }
1610  break;
1611 
1612  case CMD_POWER_ON_COUNT:
1613  {
1614  int powerOnCount = -1;
1615  int iRetVal = -1;
1616  if (useBinaryCmd)
1617  {
1618  long dummy0, dummy1;
1619  powerOnCount = 0;
1620  iRetVal = binScanfVec(&(sopasReplyBinVec[CMD_POWER_ON_COUNT]), "%4y%4ysRA ODpwrc %4y", &dummy0, &dummy1,
1621  &powerOnCount);
1622  }
1623  else
1624  {
1625  iRetVal = sscanf(sopasReplyStrVec[CMD_POWER_ON_COUNT].c_str(), "sRA ODpwrc %x", &powerOnCount);
1626  }
1627  if (iRetVal > 0)
1628  {
1629  pn.setParam("powerOnCount", powerOnCount);
1630  }
1631 
1632  }
1633  break;
1634 
1635  case CMD_LOCATION_NAME:
1636  {
1637  char szLocationName[MAX_STR_LEN] = {0};
1638  const char *strPtr = sopasReplyStrVec[CMD_LOCATION_NAME].c_str();
1639  const char *searchPattern = "sRA LocationName "; // Bug fix (leading space) Jan 2018
1640  strcpy(szLocationName, "unknown location");
1641  if (useBinaryCmd)
1642  {
1643  int iRetVal = 0;
1644  long dummy0, dummy1, locationNameLen;
1645  const char *binLocationNameMask = "%4y%4ysRA LocationName %2y";
1646  int prefixLen = binScanfGuessDataLenFromMask(binLocationNameMask);
1647  dummy0 = 0;
1648  dummy1 = 0;
1649  locationNameLen = 0;
1650 
1651  iRetVal = binScanfVec(&(sopasReplyBinVec[CMD_LOCATION_NAME]), binLocationNameMask, &dummy0, &dummy1,
1652  &locationNameLen);
1653  if (iRetVal > 0)
1654  {
1655  std::string s;
1656  std::string locationNameStr = binScanfGetStringFromVec(&(sopasReplyBinVec[CMD_LOCATION_NAME]), prefixLen,
1657  locationNameLen);
1658  strcpy(szLocationName, locationNameStr.c_str());
1659  }
1660  }
1661  else
1662  {
1663  if (strstr(strPtr, searchPattern) == strPtr)
1664  {
1665  const char *ptr = strPtr + strlen(searchPattern);
1666  strcpy(szLocationName, ptr);
1667  }
1668  else
1669  {
1670  ROS_WARN("Location command not supported.\n");
1671  }
1672  }
1673  pn.setParam("locationName", std::string(szLocationName));
1674  }
1675  break;
1676 
1677 
1679  {
1680 
1681  const char *strPtr = sopasReplyStrVec[CMD_GET_PARTIAL_SCANDATA_CFG].c_str();
1682  ROS_INFO("Config: %s\n", strPtr);
1683  }
1684  break;
1685 
1687  {
1688  bool useNegSign = false;
1689  if (NAV3xxOutputRangeSpecialHandling == 0)
1690  {
1691  useNegSign = true; // use negative phase compensation for NAV3xx
1692  }
1693 
1694  this->angleCompensator = new AngleCompensator(useNegSign);
1696  std::vector<unsigned char> tmpVec;
1697 
1698  if (useBinaryCmd == false)
1699  {
1700  for (int i = 0; i < s.length(); i++)
1701  {
1702  tmpVec.push_back((unsigned char)s[i]);
1703  }
1704  }
1705  else
1706  {
1708  }
1709  angleCompensator->parseReply(useBinaryCmd, tmpVec);
1710 
1711  ROS_INFO("Angle Comp. Formula used: %s\n", angleCompensator->getHumanReadableFormula().c_str());
1712  }
1713  break;
1714  // if (parser_->getCurrentParamPtr()->getScannerName().compare(SICK_SCANNER_NAV_2XX_NAME) == 0)
1715 
1716  // ML: add here reply handling
1717  }
1718 
1719 
1720  if (restartDueToProcolChange)
1721  {
1722  return ExitError;
1723 
1724  }
1725 
1726  }
1727 
1728  if (setNewIPAddr)
1729  {
1730 
1731  setNewIpAddress(ipNewIPAddr, useBinaryCmd);
1732  ROS_INFO("IP address changed. Node restart required");
1733  ROS_INFO("Exiting node NOW.");
1734  exit(0);//stopping node hard to avoide further IP-Communication
1735  }
1736 
1737 
1738 
1739 
1740 
1741 
1742  if (setUseNTP)
1743  {
1744 
1745  setNTPServerAndStart(NTPIpAdress, useBinaryCmd);
1746  }
1747 
1748  /*
1749  * The NAV310 and of course the radar does not support angular resolution handling
1750  */
1751  if (this->parser_->getCurrentParamPtr()->getDeviceIsRadar() )
1752  {
1753  //=====================================================
1754  // Radar specific commands
1755  //=====================================================
1756  }
1757  else
1758  {
1759  //-----------------------------------------------------------------
1760  //
1761  // This is recommended to decide between TiM551 and TiM561/TiM571 capabilities
1762  // The TiM551 has an angular resolution of 1.000 [deg]
1763  // The TiM561 and TiM571 have an angular resolution of 0.333 [deg]
1764  //-----------------------------------------------------------------
1765 
1766  angleRes10000th = (int) (boost::math::round(
1767  10000.0 * this->parser_->getCurrentParamPtr()->getAngularDegreeResolution()));
1768  std::vector<unsigned char> askOutputAngularRangeReply;
1769 
1770  // LMDscandatacfg corresponds to CMD_GET_OUTPUT_RANGES
1771  // LMDscandatacfg is not supported by NAV310
1772 
1773  if (NAV3xxOutputRangeSpecialHandling)
1774  {
1775 
1776  }
1777  else // CMD_GET_OUTPUT_RANGE (i.e. handling of LMDscandatacfg
1778  {
1779  if (useBinaryCmd)
1780  {
1781  std::vector<unsigned char> reqBinary;
1782  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_GET_OUTPUT_RANGES].c_str(), &reqBinary);
1784  }
1785  else
1786  {
1787  result = sendSopasAndCheckAnswer(sopasCmdVec[CMD_GET_OUTPUT_RANGES].c_str(), &askOutputAngularRangeReply);
1788  }
1789 
1790 
1791  if (0 == result)
1792  {
1793  int askTmpAngleRes10000th = 0;
1794  int askTmpAngleStart10000th = 0;
1795  int askTmpAngleEnd10000th = 0;
1796  char dummy0[MAX_STR_LEN] = {0};
1797  char dummy1[MAX_STR_LEN] = {0};
1798  int dummyInt = 0;
1799 
1800  int iDummy0, iDummy1;
1801  std::string askOutputAngularRangeStr = replyToString(askOutputAngularRangeReply);
1802  // Binary-Reply Tab. 63
1803  // 0x20 Space
1804  // 0x00 0x01 -
1805  // 0x00 0x00 0x05 0x14 // Resolution in 1/10000th degree --> 0.13°
1806  // 0x00 0x04 0x93 0xE0 // Start Angle 300000 -> 30°
1807  // 0x00 0x16 0xE3 0x60 // End Angle 1.500.000 -> 150° // in ROS +/-60°
1808  // 0x83 // Checksum
1809 
1810  int numArgs;
1811 
1812  if (useBinaryCmd)
1813  {
1814  iDummy0 = 0;
1815  iDummy1 = 0;
1816  dummyInt = 0;
1817  askTmpAngleRes10000th = 0;
1818  askTmpAngleStart10000th = 0;
1819  askTmpAngleEnd10000th = 0;
1820 
1821  const char *askOutputAngularRangeBinMask = "%4y%4ysRA LMPoutputRange %2y%4y%4y%4y";
1822  numArgs = binScanfVec(&sopasReplyBinVec[CMD_GET_OUTPUT_RANGES], askOutputAngularRangeBinMask, &iDummy0,
1823  &iDummy1,
1824  &dummyInt,
1825  &askTmpAngleRes10000th,
1826  &askTmpAngleStart10000th,
1827  &askTmpAngleEnd10000th);
1828  //
1829  }
1830  else
1831  {
1832  numArgs = sscanf(askOutputAngularRangeStr.c_str(), "%s %s %d %X %X %X", dummy0, dummy1,
1833  &dummyInt,
1834  &askTmpAngleRes10000th,
1835  &askTmpAngleStart10000th,
1836  &askTmpAngleEnd10000th);
1837  }
1838  if (numArgs >= 6)
1839  {
1840  double askTmpAngleRes = askTmpAngleRes10000th / 10000.0;
1841  double askTmpAngleStart = askTmpAngleStart10000th / 10000.0;
1842  double askTmpAngleEnd = askTmpAngleEnd10000th / 10000.0;
1843 
1844  angleRes10000th = askTmpAngleRes10000th;
1845  ROS_INFO("Angle resolution of scanner is %0.5lf [deg] (in 1/10000th deg: 0x%X)", askTmpAngleRes,
1846  askTmpAngleRes10000th);
1847  ROS_INFO("[From:To] %0.5lf [deg] to %0.5lf [deg] (in 1/10000th deg: from 0x%X to 0x%X)",
1848  askTmpAngleStart, askTmpAngleEnd, askTmpAngleStart10000th, askTmpAngleEnd10000th);
1849  }
1850  }
1851  }
1852  //-----------------------------------------------------------------
1853  //
1854  // Set Min- und Max scanning angle given by config
1855  //
1856  //-----------------------------------------------------------------
1857 
1858  ROS_INFO("MIN_ANG: %8.3f [rad] %8.3f [deg]", config_.min_ang, rad2deg(this->config_.min_ang));
1859  ROS_INFO("MAX_ANG: %8.3f [rad] %8.3f [deg]", config_.max_ang, rad2deg(this->config_.max_ang));
1860 
1861  // convert to 10000th degree
1862  double minAngSopas = rad2deg(this->config_.min_ang);
1863  double maxAngSopas = rad2deg(this->config_.max_ang);
1864 
1866  {
1867  // the TiM240 operates directly in the ros coordinate system
1868  }
1869  else
1870  {
1871  minAngSopas += 90.0;
1872  maxAngSopas += 90.0;
1873  }
1874 
1875  angleStart10000th = (int) (boost::math::round(10000.0 * minAngSopas));
1876  angleEnd10000th = (int) (boost::math::round(10000.0 * maxAngSopas));
1877 
1878  char requestOutputAngularRange[MAX_STR_LEN];
1879 
1880  std::vector<unsigned char> outputAngularRangeReply;
1881 
1882 
1883  if (NAV3xxOutputRangeSpecialHandling == 0)
1884  {
1885  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_OUTPUT_RANGES_NAV3].c_str();
1886  sprintf(requestOutputAngularRange, pcCmdMask,
1887  angleRes10000th, angleStart10000th, angleEnd10000th,
1888  angleRes10000th, angleStart10000th, angleEnd10000th,
1889  angleRes10000th, angleStart10000th, angleEnd10000th,
1890  angleRes10000th, angleStart10000th, angleEnd10000th);
1891  }
1892  else
1893  {
1894  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_OUTPUT_RANGES].c_str();
1895  sprintf(requestOutputAngularRange, pcCmdMask, angleRes10000th, angleStart10000th, angleEnd10000th);
1896  }
1897  if (useBinaryCmd)
1898  {
1899  unsigned char tmpBuffer[255] = {0};
1900  unsigned char sendBuffer[255] = {0};
1901  UINT16 sendLen;
1902  std::vector<unsigned char> reqBinary;
1903  int iStatus = 1;
1904  // const char *askOutputAngularRangeBinMask = "%4y%4ysWN LMPoutputRange %2y%4y%4y%4y";
1905  // int askOutputAngularRangeBinLen = binScanfGuessDataLenFromMask(askOutputAngularRangeBinMask);
1906  // askOutputAngularRangeBinLen -= 8; // due to header and length identifier
1907 
1908  strcpy((char *) tmpBuffer, "WN LMPoutputRange ");
1909  unsigned short orgLen = strlen((char *) tmpBuffer);
1910  if (NAV3xxOutputRangeSpecialHandling){
1911  colab::addIntegerToBuffer<UINT16>(tmpBuffer, orgLen, iStatus);
1912  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleRes10000th);
1913  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleStart10000th);
1914  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleEnd10000th);
1915  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleRes10000th);
1916  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleStart10000th);
1917  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleEnd10000th);
1918  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleRes10000th);
1919  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleStart10000th);
1920  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleEnd10000th);
1921  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleRes10000th);
1922  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleStart10000th);
1923  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleEnd10000th);
1924  }
1925  else
1926  {
1927  colab::addIntegerToBuffer<UINT16>(tmpBuffer, orgLen, iStatus);
1928  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleRes10000th);
1929  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleStart10000th);
1930  colab::addIntegerToBuffer<UINT32>(tmpBuffer, orgLen, angleEnd10000th);
1931  }
1932  sendLen = orgLen;
1933  colab::addFrameToBuffer(sendBuffer, tmpBuffer, &sendLen);
1934 
1935  // binSprintfVec(&reqBinary, askOutputAngularRangeBinMask, 0x02020202, askOutputAngularRangeBinLen, iStatus, angleRes10000th, angleStart10000th, angleEnd10000th);
1936 
1937  // unsigned char sickCrc = sick_crc8((unsigned char *)(&(reqBinary)[8]), reqBinary.size() - 8);
1938  // reqBinary.push_back(sickCrc);
1939  reqBinary = std::vector<unsigned char>(sendBuffer, sendBuffer + sendLen);
1940  // Here we must build a more complex binaryRequest
1941 
1942  // this->convertAscii2BinaryCmd(requestOutputAngularRange, &reqBinary);
1943  result = sendSopasAndCheckAnswer(reqBinary, &outputAngularRangeReply);
1944  }
1945  else
1946  {
1947  result = sendSopasAndCheckAnswer(requestOutputAngularRange, &outputAngularRangeReply);
1948  }
1949 
1950  //-----------------------------------------------------------------
1951  //
1952  // Get Min- und Max scanning angle from the scanner to verify angle setting and correct the config, if something went wrong.
1953  //
1954  // IMPORTANT:
1955  // Axis Orientation in ROS differs from SICK AXIS ORIENTATION!!!
1956  // In relation to a body the standard is:
1957  // x forward
1958  // y left
1959  // z up
1960  // see http://www.ros.org/reps/rep-0103.html#coordinate-frame-conventions for more details
1961  //-----------------------------------------------------------------
1962 
1963  askOutputAngularRangeReply.clear();
1964 
1965  if (useBinaryCmd)
1966  {
1967  std::vector<unsigned char> reqBinary;
1968  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_GET_OUTPUT_RANGES].c_str(), &reqBinary);
1970  }
1971  else
1972  {
1973  result = sendSopasAndCheckAnswer(sopasCmdVec[CMD_GET_OUTPUT_RANGES].c_str(), &askOutputAngularRangeReply);
1974  }
1975 
1976  if (result == 0)
1977  {
1978  char dummy0[MAX_STR_LEN] = {0};
1979  char dummy1[MAX_STR_LEN] = {0};
1980  int dummyInt = 0;
1981  int askAngleRes10000th = 0;
1982  int askAngleStart10000th = 0;
1983  int askAngleEnd10000th = 0;
1984  int iDummy0, iDummy1;
1985  iDummy0 = 0;
1986  iDummy1 = 0;
1987  std::string askOutputAngularRangeStr = replyToString(askOutputAngularRangeReply);
1988  // Binary-Reply Tab. 63
1989  // 0x20 Space
1990  // 0x00 0x01 -
1991  // 0x00 0x00 0x05 0x14 // Resolution in 1/10000th degree --> 0.13°
1992  // 0x00 0x04 0x93 0xE0 // Start Angle 300000 -> 30°
1993  // 0x00 0x16 0xE3 0x60 // End Angle 1.500.000 -> 150° // in ROS +/-60°
1994  // 0x83 // Checksum
1995 
1996  int numArgs;
1997 
1998  /*
1999  *
2000  * Initialize variables
2001  */
2002 
2003  iDummy0 = 0;
2004  iDummy1 = 0;
2005  dummyInt = 0;
2006  askAngleRes10000th = 0;
2007  askAngleStart10000th = 0;
2008  askAngleEnd10000th = 0;
2009 
2010  /*
2011  * scan values
2012  *
2013  */
2014 
2015  if (useBinaryCmd)
2016  {
2017  const char *askOutputAngularRangeBinMask = "%4y%4ysRA LMPoutputRange %2y%4y%4y%4y";
2018  numArgs = binScanfVec(&sopasReplyBinVec[CMD_GET_OUTPUT_RANGES], askOutputAngularRangeBinMask, &iDummy0,
2019  &iDummy1,
2020  &dummyInt,
2021  &askAngleRes10000th,
2022  &askAngleStart10000th,
2023  &askAngleEnd10000th);
2024  //
2025  }
2026  else
2027  {
2028  numArgs = sscanf(askOutputAngularRangeStr.c_str(), "%s %s %d %X %X %X", dummy0, dummy1,
2029  &dummyInt,
2030  &askAngleRes10000th,
2031  &askAngleStart10000th,
2032  &askAngleEnd10000th);
2033  }
2034  if (numArgs >= 6)
2035  {
2036  double askTmpAngleRes = askAngleRes10000th / 10000.0;
2037  double askTmpAngleStart = askAngleStart10000th / 10000.0;
2038  double askTmpAngleEnd = askAngleEnd10000th / 10000.0;
2039 
2040  angleRes10000th = askAngleRes10000th;
2041  ROS_INFO("Angle resolution of scanner is %0.5lf [deg] (in 1/10000th deg: 0x%X)", askTmpAngleRes,
2042  askAngleRes10000th);
2043 
2044  }
2045  double askAngleRes = askAngleRes10000th / 10000.0;
2046  double askAngleStart = askAngleStart10000th / 10000.0;
2047  double askAngleEnd = askAngleEnd10000th / 10000.0;
2048 
2050  {
2051  // the TiM240 operates directly in the ros coordinate system
2052  }
2053  else
2054  {
2055  askAngleStart -= 90; // angle in ROS relative to y-axis
2056  askAngleEnd -= 90; // angle in ROS relative to y-axis
2057  }
2058  this->config_.min_ang = askAngleStart / 180.0 * M_PI;
2059  this->config_.max_ang = askAngleEnd / 180.0 * M_PI;
2060  ros::NodeHandle nhPriv("~");
2061  nhPriv.setParam("min_ang",
2062  this->config_.min_ang); // update parameter setting with "true" values read from scanner
2063  nhPriv.setParam("max_ang",
2064  this->config_.max_ang); // update parameter setting with "true" values read from scanner
2065  ROS_INFO("MIN_ANG (after command verification): %8.3f [rad] %8.3f [deg]", config_.min_ang,
2066  rad2deg(this->config_.min_ang));
2067  ROS_INFO("MAX_ANG (after command verification): %8.3f [rad] %8.3f [deg]", config_.max_ang,
2068  rad2deg(this->config_.max_ang));
2069  }
2070  //-----------------------------------------------------------------
2071  //
2072  // Configure the data content of scan messing regarding to config.
2073  //
2074  //-----------------------------------------------------------------
2075  /*
2076  see 4.3.1 Configure the data content for the scan in the
2077  */
2078  // 1 2 3
2079  // Prepare flag array for echos
2080  // Except for the LMS5xx scanner here the mask is hard 00 see SICK Telegram listing "Telegram structure: sWN LMDscandatacfg" for details
2081 
2082  outputChannelFlagId = 0x00;
2083  for (size_t i = 0; i < outputChannelFlag.size(); i++)
2084  {
2085  outputChannelFlagId |= ((outputChannelFlag[i] == true) << i);
2086  }
2087  if (outputChannelFlagId < 1)
2088  {
2089  outputChannelFlagId = 1; // at least one channel must be set
2090  }
2092  {
2093  outputChannelFlagId = 1;
2094  ROS_INFO("LMS 5xx detected overwriting output channel flag ID");
2095 
2096  ROS_INFO("LMS 5xx detected overwriting resolution flag (only 8 bit supported)");
2098  rssiResolutionIs16Bit = this->parser_->getCurrentParamPtr()->getIntensityResolutionIs16Bit();
2099  }
2101  {
2102  ROS_INFO("MRS 1xxx detected overwriting resolution flag (only 8 bit supported)");
2104  rssiResolutionIs16Bit = this->parser_->getCurrentParamPtr()->getIntensityResolutionIs16Bit();
2105 
2106  }
2107  //SAFTY FIELD PARSING
2109  {
2110  ROS_INFO("Reading safety fields");
2112  int maxFieldnum = this->parser_->getCurrentParamPtr()->getMaxEvalFields();
2113  for(int fieldnum=0;fieldnum<maxFieldnum;fieldnum++)
2114  {
2115  char requestFieldcfg[MAX_STR_LEN];
2116  const char *pcCmdMask = sopasCmdMaskVec[CMD_GET_SAFTY_FIELD_CFG].c_str();
2117  sprintf(requestFieldcfg, pcCmdMask, fieldnum);
2118  if (useBinaryCmd) {
2119  std::vector<unsigned char> reqBinary;
2120  std::vector<unsigned char> fieldcfgReply;
2121  this->convertAscii2BinaryCmd(requestFieldcfg, &reqBinary);
2122  result = sendSopasAndCheckAnswer(reqBinary, &fieldcfgReply);
2123  fieldMon->parseBinaryDatagram(fieldcfgReply);
2124  } else {
2125  std::vector<unsigned char> fieldcfgReply;
2126  result = sendSopasAndCheckAnswer(requestFieldcfg, &fieldcfgReply);
2127  fieldMon->parseAsciiDatagram(fieldcfgReply);
2128  }
2129  }
2130  if(cloud_marker_)
2131  {
2132  int fieldset = 0;
2133  // pn.getParam("fieldset", fieldset);
2134  std::string LIDinputstateRequest = "\x02sRN LIDinputstate\x03";
2135  std::vector<unsigned char> LIDinputstateResponse;
2136  if (useBinaryCmd)
2137  {
2138  std::vector<unsigned char> reqBinary;
2139  this->convertAscii2BinaryCmd(LIDinputstateRequest.c_str(), &reqBinary);
2140  result = sendSopasAndCheckAnswer(reqBinary, &LIDinputstateResponse);
2141  if(result == 0)
2142  {
2143  //fieldset = (LIDinputstateResponse[32] & 0xFF);
2144  //fieldMon->setActiveFieldset(fieldset);
2145  fieldMon->parseBinaryLIDinputstateMsg(LIDinputstateResponse.data(), LIDinputstateResponse.size());
2146  ROS_INFO_STREAM("Safety fieldset response to \"sRN LIDinputstate\": " << DataDumper::binDataToAsciiString(LIDinputstateResponse.data(), LIDinputstateResponse.size())
2147  << ", active fieldset = " << fieldMon->getActiveFieldset());
2148  }
2149  }
2150  else
2151  {
2152  result = sendSopasAndCheckAnswer(LIDinputstateRequest.c_str(), &LIDinputstateResponse);
2153  }
2154 
2155  std::string scanner_name = parser_->getCurrentParamPtr()->getScannerName();
2156  EVAL_FIELD_SUPPORT eval_field_logic = this->parser_->getCurrentParamPtr()->getUseEvalFields();
2157  cloud_marker_->updateMarker(fieldMon->getMonFields(), fieldset, eval_field_logic);
2158  std::stringstream field_info;
2159  field_info << "Safety fieldset " << fieldset << ", pointcounter = [ ";
2160  for(int n = 0; n < fieldMon->getMonFields().size(); n++)
2161  field_info << (n > 0 ? ", " : " ") << fieldMon->getMonFields()[n].getPointCount();
2162  field_info << " ]";
2163  ROS_INFO_STREAM(field_info.str());
2164  for(int n = 0; n < fieldMon->getMonFields().size(); n++)
2165  {
2166  if(fieldMon->getMonFields()[n].getPointCount() > 0)
2167  {
2168  std::stringstream field_info2;
2169  field_info2 << "Safety field " << n << ", type " << (int)(fieldMon->getMonFields()[n].fieldType()) << " : ";
2170  for(int m = 0; m < fieldMon->getMonFields()[n].getPointCount(); m++)
2171  {
2172  if(m > 0)
2173  field_info2 << ", ";
2174  field_info2 << "(" << fieldMon->getMonFields()[n].getFieldPointsX()[m] << "," << fieldMon->getMonFields()[n].getFieldPointsY()[m] << ")";
2175  }
2176  ROS_INFO_STREAM(field_info2.str());
2177  }
2178  }
2179  }
2180  }
2181 
2182  // set scanning angle for tim5xx and for mrs1104
2183  if ((this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 1)
2184  || (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 4)
2185  || (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 24)
2186  )
2187  {
2188  char requestLMDscandatacfg[MAX_STR_LEN];
2189  // Uses sprintf-Mask to set bitencoded echos and rssi enable flag
2190  // sopasCmdMaskVec[CMD_SET_PARTIAL_SCANDATA_CFG] = "\x02sWN LMDscandatacfg %02d 00 %d %d 00 %d 00 0 0 0 1 1\x03";
2191  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_PARTIAL_SCANDATA_CFG].c_str();
2192  sprintf(requestLMDscandatacfg, pcCmdMask, outputChannelFlagId, rssiFlag ? 1 : 0, rssiResolutionIs16Bit ? 1 : 0,
2193  EncoderSetings != -1 ? EncoderSetings : 0);
2194  if (useBinaryCmd)
2195  {
2196  std::vector<unsigned char> reqBinary;
2197  this->convertAscii2BinaryCmd(requestLMDscandatacfg, &reqBinary);
2198  // FOR MRS6124 this should be
2199  // like this:
2200  // 0000 02 02 02 02 00 00 00 20 73 57 4e 20 4c 4d 44 73 .......sWN LMDs
2201  // 0010 63 61 6e 64 61 74 61 63 66 67 20 1f 00 01 01 00 candatacfg .....
2202  // 0020 00 00 00 00 00 00 00 01 5c
2204  }
2205  else
2206  {
2207  std::vector<unsigned char> lmdScanDataCfgReply;
2208  result = sendSopasAndCheckAnswer(requestLMDscandatacfg, &lmdScanDataCfgReply);
2209  }
2210 
2211 
2212  // check setting
2213  char requestLMDscandatacfgRead[MAX_STR_LEN];
2214  // Uses sprintf-Mask to set bitencoded echos and rssi enable flag
2215 
2216  strcpy(requestLMDscandatacfgRead, sopasCmdVec[CMD_GET_PARTIAL_SCANDATA_CFG].c_str());
2217  if (useBinaryCmd)
2218  {
2219  std::vector<unsigned char> reqBinary;
2220  this->convertAscii2BinaryCmd(requestLMDscandatacfgRead, &reqBinary);
2222  }
2223  else
2224  {
2225  std::vector<unsigned char> lmdScanDataCfgReadReply;
2226  result = sendSopasAndCheckAnswer(requestLMDscandatacfgRead, &lmdScanDataCfgReadReply);
2227  }
2228 
2229 
2230  }
2231  //BBB
2232  // set scanning angle for tim5xx and for mrs1104
2233  double scan_freq = 0;
2234  double ang_res = 0;
2235  pn.getParam("scan_freq", scan_freq); // filter_echos
2236  pn.getParam("ang_res", ang_res); // filter_echos
2237  if (scan_freq != 0 || ang_res != 0)
2238  {
2239  if (scan_freq != 0 && ang_res != 0)
2240  {
2242  {
2243  ROS_INFO("variable ang_res and scan_freq setings for NAV 3xx has not been implemented yet using 20 Hz 0.75 deg");
2244  }
2245  else
2246  {
2247  char requestLMDscancfg[MAX_STR_LEN];
2248  // sopasCmdMaskVec[CMD_SET_PARTIAL_SCAN_CFG] = "\x02sMN mLMPsetscancfg %d 1 %d 0 0\x03";//scanfreq [1/100 Hz],angres [1/10000°],
2249  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_PARTIAL_SCAN_CFG].c_str();
2250  sprintf(requestLMDscancfg, pcCmdMask, (long) (scan_freq * 100 + 1e-9), (long) (ang_res * 10000 + 1e-9));
2251  if (useBinaryCmd)
2252  {
2253  std::vector<unsigned char> reqBinary;
2254  this->convertAscii2BinaryCmd(requestLMDscancfg, &reqBinary);
2256  }
2257  else
2258  {
2259  std::vector<unsigned char> lmdScanCfgReply;
2260  result = sendSopasAndCheckAnswer(requestLMDscancfg, &lmdScanCfgReply);
2261  }
2262 
2263 
2264  // check setting
2265  char requestLMDscancfgRead[MAX_STR_LEN];
2266  // Uses sprintf-Mask to set bitencoded echos and rssi enable flag
2267 
2268  strcpy(requestLMDscancfgRead, sopasCmdVec[CMD_GET_PARTIAL_SCAN_CFG].c_str());
2269  if (useBinaryCmd)
2270  {
2271  std::vector<unsigned char> reqBinary;
2272  this->convertAscii2BinaryCmd(requestLMDscancfgRead, &reqBinary);
2274  }
2275  else
2276  {
2277  std::vector<unsigned char> lmdScanDataCfgReadReply;
2278  result = sendSopasAndCheckAnswer(requestLMDscancfgRead, &lmdScanDataCfgReadReply);
2279  }
2280 
2281  }
2282  }
2283  else
2284  {
2285  ROS_ERROR("ang_res and scan_freq have to be set, only one param is set skiping scan_fre/ang_res config");
2286  }
2287  }
2288  // Config Mean filter
2289  /*
2290  char requestMeanSetting[MAX_STR_LEN];
2291  int meanFilterSetting = 0;
2292  int MeanFilterActive=0;
2293  pn.getParam("mean_filter", meanFilterSetting); // filter_echos
2294  if(meanFilterSetting>2)
2295  {
2296  MeanFilterActive=1;
2297  }
2298  else{
2299  //needs to be at leas 2 even if filter is disabled
2300  meanFilterSetting = 2;
2301  }
2302  // Uses sprintf-Mask to set bitencoded echos and rssi enable flag
2303  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_MEAN_FILTER].c_str();
2304 
2305  //First echo : 0
2306  //All echos : 1
2307  //Last echo : 2
2308 
2309  sprintf(requestMeanSetting, pcCmdMask, MeanFilterActive, meanFilterSetting);
2310  std::vector<unsigned char> outputFilterMeanReply;
2311 
2312 
2313  if (useBinaryCmd)
2314  {
2315  std::vector<unsigned char> reqBinary;
2316  this->convertAscii2BinaryCmd(requestMeanSetting, &reqBinary);
2317  result = sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_SET_ECHO_FILTER]);
2318  }
2319  else
2320  {
2321  result = sendSopasAndCheckAnswer(requestMeanSetting, &outputFilterMeanReply);
2322  }
2323 
2324 */
2325  // CONFIG ECHO-Filter (only for MRS1000 not available for TiM5xx
2326  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() >= 4)
2327  {
2328  char requestEchoSetting[MAX_STR_LEN];
2329  int filterEchoSetting = 0;
2330  pn.getParam("filter_echos", filterEchoSetting); // filter_echos
2331  if (filterEchoSetting < 0)
2332  { filterEchoSetting = 0; }
2333  if (filterEchoSetting > 2)
2334  { filterEchoSetting = 2; }
2335  // Uses sprintf-Mask to set bitencoded echos and rssi enable flag
2336  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_ECHO_FILTER].c_str();
2337  /*
2338  First echo : 0
2339  All echos : 1
2340  Last echo : 2
2341  */
2342  sprintf(requestEchoSetting, pcCmdMask, filterEchoSetting);
2343  std::vector<unsigned char> outputFilterEchoRangeReply;
2344 
2345 
2346  if (useBinaryCmd)
2347  {
2348  std::vector<unsigned char> reqBinary;
2349  this->convertAscii2BinaryCmd(requestEchoSetting, &reqBinary);
2351  }
2352  else
2353  {
2354  result = sendSopasAndCheckAnswer(requestEchoSetting, &outputFilterEchoRangeReply);
2355  }
2356 
2357  }
2358 
2359 
2360  }
2362 
2363 
2364  //-----------------------------------------------------------------
2365  //
2366  // Start sending LMD-Scandata messages
2367  //
2368  //-----------------------------------------------------------------
2369  std::vector<int> startProtocolSequence;
2370  bool deviceIsRadar = false;
2372  {
2373  ros::NodeHandle tmpParam("~");
2374  bool transmitRawTargets = true;
2375  bool transmitObjects = true;
2376  int trackingMode = 0;
2377  std::string trackingModeDescription[] = {"BASIC", "VEHICLE"};
2378 
2379  int numTrackingModes = sizeof(trackingModeDescription) / sizeof(trackingModeDescription[0]);
2380 
2381  tmpParam.getParam("transmit_raw_targets", transmitRawTargets);
2382  tmpParam.getParam("transmit_objects", transmitObjects);
2383  tmpParam.getParam("tracking_mode", trackingMode);
2384 
2385 
2386  if ((trackingMode < 0) || (trackingMode >= numTrackingModes))
2387  {
2388  ROS_WARN("tracking mode id invalid. Switch to tracking mode 0");
2389  trackingMode = 0;
2390  }
2391  ROS_INFO("Raw target transmission is switched [%s]", transmitRawTargets ? "ON" : "OFF");
2392  ROS_INFO("Object transmission is switched [%s]", transmitObjects ? "ON" : "OFF");
2393  ROS_INFO("Tracking mode is set to id [%d] [%s]", trackingMode, trackingModeDescription[trackingMode].c_str());
2394 
2395  deviceIsRadar = true;
2396 
2397  // Asking some informational from the radar
2398  startProtocolSequence.push_back(CMD_DEVICE_TYPE);
2399  startProtocolSequence.push_back(CMD_SERIAL_NUMBER);
2400  startProtocolSequence.push_back(CMD_ORDER_NUMBER);
2401 
2402  /*
2403  * With "sWN TCTrackingMode 0" BASIC-Tracking activated
2404  * With "sWN TCTrackingMode 1" TRAFFIC-Tracking activated
2405  *
2406  */
2407  if (transmitRawTargets)
2408  {
2409  startProtocolSequence.push_back(CMD_SET_TRANSMIT_RAWTARGETS_ON); // raw targets will be transmitted
2410  }
2411  else
2412  {
2413  startProtocolSequence.push_back(CMD_SET_TRANSMIT_RAWTARGETS_OFF); // NO raw targets will be transmitted
2414  }
2415 
2416  if (transmitObjects)
2417  {
2418  startProtocolSequence.push_back(CMD_SET_TRANSMIT_OBJECTS_ON); // tracking objects will be transmitted
2419  }
2420  else
2421  {
2422  startProtocolSequence.push_back(CMD_SET_TRANSMIT_OBJECTS_OFF); // NO tracking objects will be transmitted
2423  }
2424 
2425  switch (trackingMode)
2426  {
2427  case 0:
2428  startProtocolSequence.push_back(CMD_SET_TRACKING_MODE_0);
2429  break;
2430  case 1:
2431  startProtocolSequence.push_back(CMD_SET_TRACKING_MODE_1);
2432  break;
2433  default:
2434  ROS_DEBUG("Tracking mode switching sequence unknown\n");
2435  break;
2436 
2437  }
2438  // leave user level
2439 
2440  // sWN TransmitTargets 1
2441  // initializing sequence for radar based devices
2442  startProtocolSequence.push_back(CMD_RUN); // leave user level
2443  startProtocolSequence.push_back(CMD_START_RADARDATA);
2444  }
2445  else
2446  {
2447  // initializing sequence for laserscanner
2448  // is this device a TiM240????
2449  // The TiM240 can not interpret CMD_START_MEASUREMENT
2451  {
2452  // the TiM240 operates directly in the ros coordinate system
2453  // do nothing for a TiM240
2454  }
2455  else
2456  {
2457  startProtocolSequence.push_back(CMD_START_MEASUREMENT);
2458  }
2459  startProtocolSequence.push_back(CMD_RUN); // leave user level
2460  startProtocolSequence.push_back(CMD_START_SCANDATA);
2461 
2463  {
2464 
2465  // Activate LFErec, LIDoutputstate and LIDinputstate messages
2466  ros::NodeHandle tmpParam("~");
2467  bool activate_lferec = true, activate_lidoutputstate = true, activate_lidinputstate = true;
2468  if (true == tmpParam.getParam("activate_lferec", activate_lferec) && true == activate_lferec)
2469  {
2470  startProtocolSequence.push_back(CMD_SET_LFEREC_ACTIVE); // TiM781S: activate LFErec messages, send "sEN LFErec 1"
2471  ROS_INFO_STREAM(parser_->getCurrentParamPtr()->getScannerName() << ": activating field monitoring by lferec messages");
2472  }
2473  if (true == tmpParam.getParam("activate_lidoutputstate", activate_lidoutputstate) && true == activate_lidoutputstate)
2474  {
2475  startProtocolSequence.push_back(CMD_SET_LID_OUTPUTSTATE_ACTIVE); // TiM781S: activate LIDoutputstate messages, send "sEN LIDoutputstate 1"
2476  ROS_INFO_STREAM(parser_->getCurrentParamPtr()->getScannerName() << ": activating field monitoring by lidoutputstate messages");
2477  }
2478  if (true == tmpParam.getParam("activate_lidinputstate", activate_lidinputstate) && true == activate_lidinputstate)
2479  {
2480  startProtocolSequence.push_back(CMD_SET_LID_INPUTSTATE_ACTIVE); // TiM781S: activate LIDinputstate messages, send "sEN LIDinputstate 1"
2481  ROS_INFO_STREAM(parser_->getCurrentParamPtr()->getScannerName() << ": activating field monitoring by lidinputstate messages");
2482  }
2483  }
2484 
2485  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 4) // MRS1104 - start IMU-Transfer
2486  {
2487  ros::NodeHandle tmp("~");
2488  bool imu_enable = false;
2489  tmp.getParam("imu_enable", imu_enable);
2490  if (imu_enable)
2491  {
2492  if (useBinaryCmdNow == true)
2493  {
2494  ROS_INFO("Enable IMU data transfer");
2495  // TODO Flag to decide between IMU on or off
2496  startProtocolSequence.push_back(CMD_START_IMU_DATA);
2497  }
2498  else
2499  {
2500  ROS_FATAL(
2501  "IMU USAGE NOT POSSIBLE IN ASCII COMMUNICATION MODE.\nTo use the IMU the communication with the scanner must be set to binary mode.\n This can be done by inserting the line:\n<param name=\"use_binary_protocol\" type=\"bool\" value=\"True\" />\n into the launchfile.\n See also https://github.com/SICKAG/sick_scan/blob/master/doc/IMU.md");
2502  exit(0);
2503  }
2504 
2505  }
2506  }
2507  }
2508 
2509  std::vector<int>::iterator it;
2510  for (it = startProtocolSequence.begin(); it != startProtocolSequence.end(); it++)
2511  {
2512  int cmdId = *it;
2513  std::vector<unsigned char> tmpReply;
2514  // sendSopasAndCheckAnswer(sopasCmdVec[cmdId].c_str(), &tmpReply);
2515 
2516  std::string sopasCmd = sopasCmdVec[cmdId];
2517  std::vector<unsigned char> replyDummy;
2518  std::vector<unsigned char> reqBinary;
2519  std::vector<unsigned char> sopasVec;
2520  sopasVec = stringToVector(sopasCmd);
2521  ROS_DEBUG("Command: %s", stripControl(sopasVec).c_str());
2522  if (useBinaryCmd)
2523  {
2524  this->convertAscii2BinaryCmd(sopasCmd.c_str(), &reqBinary);
2525  result = sendSopasAndCheckAnswer(reqBinary, &replyDummy, cmdId);
2526  sopasReplyBinVec[cmdId] = replyDummy;
2527 
2528  switch (cmdId)
2529  {
2530  case CMD_START_SCANDATA:
2531  // ROS_DEBUG("Sleeping for a couple of seconds of start measurement\n");
2532  // ros::Duration(10.0).sleep();
2533  break;
2534  }
2535  }
2536  else
2537  {
2538  result = sendSopasAndCheckAnswer(sopasCmd.c_str(), &replyDummy, cmdId);
2539  }
2540 
2541  if (result != 0)
2542  {
2543  ROS_ERROR("%s", sopasCmdErrMsg[cmdId].c_str());
2545  }
2546  else
2547  {
2548  sopasReplyStrVec[cmdId] = replyToString(replyDummy);
2549  }
2550 
2551 
2552  if (cmdId == CMD_START_RADARDATA)
2553  {
2554  ROS_DEBUG("Starting radar data ....\n");
2555  }
2556 
2557 
2558  if (cmdId == CMD_START_SCANDATA)
2559  {
2560  ROS_DEBUG("Starting scan data ....\n");
2561  }
2562 
2563  if (cmdId == CMD_RUN)
2564  {
2565  bool waitForDeviceState = true;
2566  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 1)
2567  {
2568  waitForDeviceState = false; // do nothing for tim5xx
2569  }
2570  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() == 24)
2571  {
2572  waitForDeviceState = false; // do nothing for MRS6xxx
2573  }
2574 
2575  if (waitForDeviceState)
2576  {
2577  int maxWaitForDeviceStateReady = 45; // max. 30 sec. (see manual)
2578  bool scannerReady = false;
2579  for (int i = 0; i < maxWaitForDeviceStateReady; i++)
2580  {
2581  double shortSleepTime = 1.0;
2582  std::string sopasCmd = sopasCmdVec[CMD_DEVICE_STATE];
2583  std::vector<unsigned char> replyDummy;
2584 
2585  int iRetVal = 0;
2586  int deviceState = 0;
2587 
2588  std::vector<unsigned char> reqBinary;
2589  std::vector<unsigned char> sopasVec;
2590  sopasVec = stringToVector(sopasCmd);
2591  ROS_DEBUG("Command: %s", stripControl(sopasVec).c_str());
2592  if (useBinaryCmd)
2593  {
2594  this->convertAscii2BinaryCmd(sopasCmd.c_str(), &reqBinary);
2595  result = sendSopasAndCheckAnswer(reqBinary, &replyDummy);
2596  sopasReplyBinVec[CMD_DEVICE_STATE] = replyDummy;
2597  }
2598  else
2599  {
2600  result = sendSopasAndCheckAnswer(sopasCmd.c_str(), &replyDummy);
2602  }
2603 
2604 
2605  if (useBinaryCmd)
2606  {
2607  long dummy0, dummy1;
2608  dummy0 = 0;
2609  dummy1 = 0;
2610  deviceState = 0;
2611  iRetVal = binScanfVec(&(sopasReplyBinVec[CMD_DEVICE_STATE]), "%4y%4ysRA SCdevicestate %1y", &dummy0,
2612  &dummy1, &deviceState);
2613  }
2614  else
2615  {
2616  iRetVal = sscanf(sopasReplyStrVec[CMD_DEVICE_STATE].c_str(), "sRA SCdevicestate %d", &deviceState);
2617  }
2618  if (iRetVal > 0) // 1 or 3 (depending of ASCII or Binary)
2619  {
2620  if (deviceState == 1) // scanner is ready
2621  {
2622  scannerReady = true; // interrupt waiting for scanner ready
2623  ROS_INFO("Scanner ready for measurement after %d [sec]", i);
2624  break;
2625  }
2626  }
2627  ROS_INFO("Waiting for scanner ready state since %d secs", i);
2628  ros::Duration(shortSleepTime).sleep();
2629 
2630  if (scannerReady)
2631  {
2632  break;
2633  }
2634  }
2635  }
2636  }
2637  tmpReply.clear();
2638 
2639  }
2640  return ExitSuccess;
2641  }
2642 
2643 
2649  std::string sick_scan::SickScanCommon::replyToString(const std::vector<unsigned char> &reply)
2650  {
2651  std::string reply_str;
2652  std::vector<unsigned char>::const_iterator it_start, it_end;
2653  int binLen = this->checkForBinaryAnswer(&reply);
2654  if (binLen == -1) // ASCII-Cmd
2655  {
2656  it_start = reply.begin();
2657  it_end = reply.end();
2658  }
2659  else
2660  {
2661  it_start = reply.begin() + 8; // skip header and length id
2662  it_end = reply.end() - 1; // skip CRC
2663  }
2664  bool inHexPrintMode = false;
2665  for (std::vector<unsigned char>::const_iterator it = it_start; it != it_end; it++)
2666  {
2667  // inHexPrintMode means that we should continue printing hex value after we started with hex-Printing
2668  // That is easier to debug for a human instead of switching between ascii binary and then back to ascii
2669  if (*it >= 0x20 && (inHexPrintMode == false)) // filter control characters for display
2670  {
2671  reply_str.push_back(*it);
2672  }
2673  else
2674  {
2675  if (binLen != -1) // binary
2676  {
2677  char szTmp[255] = {0};
2678  unsigned char val = *it;
2679  inHexPrintMode = true;
2680  sprintf(szTmp, "\\x%02x", val);
2681  for (size_t ii = 0; ii < strlen(szTmp); ii++)
2682  {
2683  reply_str.push_back(szTmp[ii]);
2684  }
2685  }
2686  }
2687 
2688  }
2689  return reply_str;
2690  }
2691 
2692  bool sick_scan::SickScanCommon::dumpDatagramForDebugging(unsigned char *buffer, int bufLen)
2693  {
2694  bool ret = true;
2695  static int cnt = 0;
2696  char szDumpFileName[511] = {0};
2697  char szDir[255] = {0};
2698  if (cnt == 0)
2699  {
2700  ROS_INFO("Attention: verboseLevel is set to 1. Datagrams are stored in the /tmp folder.");
2701  }
2702 #ifdef _MSC_VER
2703  strcpy(szDir, "C:\\temp\\");
2704 #else
2705  strcpy(szDir, "/tmp/");
2706 #endif
2707  sprintf(szDumpFileName, "%ssick_datagram_%06d.bin", szDir, cnt);
2708  bool isBinary = this->parser_->getCurrentParamPtr()->getUseBinaryProtocol();
2709  if (isBinary)
2710  {
2711  FILE *ftmp;
2712  ftmp = fopen(szDumpFileName, "wb");
2713  if (ftmp != NULL)
2714  {
2715  fwrite(buffer, bufLen, 1, ftmp);
2716  fclose(ftmp);
2717  }
2718  }
2719  cnt++;
2720 
2721  return (true);
2722 
2723  }
2724 
2725 
2731  bool sick_scan::SickScanCommon::isCompatibleDevice(const std::string identStr) const
2732  {
2733  char device_string[7];
2734  int version_major = -1;
2735  int version_minor = -1;
2736 
2737  strcpy(device_string, "???");
2738  // special for TiM3-Firmware
2739  if (sscanf(identStr.c_str(), "sRA 0 6 %6s E V%d.%d", device_string,
2740  &version_major, &version_minor) == 3
2741  && strncmp("TiM3", device_string, 4) == 0
2742  && version_major >= 2 && version_minor >= 50)
2743  {
2744  ROS_ERROR("This scanner model/firmware combination does not support ranging output!");
2745  ROS_ERROR("Supported scanners: TiM5xx: all firmware versions; TiM3xx: firmware versions < V2.50.");
2746  ROS_ERROR("This is a %s, firmware version %d.%d", device_string, version_major, version_minor);
2747 
2748  return false;
2749  }
2750 
2751  bool supported = false;
2752 
2753  // DeviceIdent 8 MRS1xxxx 8 1.3.0.0R.
2754  if (sscanf(identStr.c_str(), "sRA 0 6 %6s E V%d.%d", device_string, &version_major, &version_minor) == 3)
2755  {
2756  std::string devStr = device_string;
2757 
2758 
2759  if (devStr.compare(0, 4, "TiM5") == 0)
2760  {
2761  supported = true;
2762  }
2763 
2764  if (supported == true)
2765  {
2766  ROS_INFO("Device %s V%d.%d found and supported by this driver.", identStr.c_str(), version_major,
2767  version_minor);
2768  }
2769 
2770  }
2771 
2772  if ((identStr.find("MRS1xxx") !=
2773  std::string::npos) // received pattern contains 4 'x' but we check only for 3 'x' (MRS1104 should be MRS1xxx)
2774  || (identStr.find("LMS1xxx") != std::string::npos)
2775  )
2776  {
2777  ROS_INFO("Deviceinfo %s found and supported by this driver.", identStr.c_str());
2778  supported = true;
2779  }
2780 
2781 
2782  if (identStr.find("MRS6") !=
2783  std::string::npos) // received pattern contains 4 'x' but we check only for 3 'x' (MRS1104 should be MRS1xxx)
2784  {
2785  ROS_INFO("Deviceinfo %s found and supported by this driver.", identStr.c_str());
2786  supported = true;
2787  }
2788 
2789  if (identStr.find("RMS3xx") !=
2790  std::string::npos) // received pattern contains 4 'x' but we check only for 3 'x' (MRS1104 should be MRS1xxx)
2791  {
2792  ROS_INFO("Deviceinfo %s found and supported by this driver.", identStr.c_str());
2793  supported = true;
2794  }
2795 
2796 
2797  if (supported == false)
2798  {
2799  ROS_WARN("Device %s V%d.%d found and maybe unsupported by this driver.", device_string, version_major,
2800  version_minor);
2801  ROS_WARN("Full SOPAS answer: %s", identStr.c_str());
2802  }
2803  return true;
2804  }
2805 
2806 
2812  {
2813  static int cnt = 0;
2814  diagnostics_.update();
2815 
2816  unsigned char receiveBuffer[65536];
2817  int actual_length = 0;
2818  static unsigned int iteration_count = 0;
2819  bool useBinaryProtocol = this->parser_->getCurrentParamPtr()->getUseBinaryProtocol();
2820 
2821  ros::Time recvTimeStamp = ros::Time::now(); // timestamp incoming package, will be overwritten by get_datagram
2822  // tcp packet
2823  ros::Time recvTimeStampPush = ros::Time::now(); // timestamp
2824 
2825  /*
2826  * Try to get datagram
2827  *
2828  *
2829  */
2830 
2831 
2832  int packetsInLoop = 0;
2833 
2834  const int maxNumAllowedPacketsToProcess = 25; // maximum number of packets, which will be processed in this loop.
2835 
2836  int numPacketsProcessed = 0; // count number of processed datagrams
2837 
2838  static bool firstTimeCalled = true;
2839  static bool dumpData = false;
2840  static int verboseLevel = 0;
2841  static bool slamBundle = false;
2842  float timeIncrement;
2843  static std::string echoForSlam = "";
2844  if (firstTimeCalled == true)
2845  {
2846 
2847  /* Dump Binary Protocol */
2848  ros::NodeHandle tmpParam("~");
2849  tmpParam.getParam("slam_echo", echoForSlam);
2850  tmpParam.getParam("slam_bundle", slamBundle);
2851  tmpParam.getParam("verboseLevel", verboseLevel);
2852  firstTimeCalled = false;
2853  }
2854  do
2855  {
2856 
2857  int result = get_datagram(recvTimeStamp, receiveBuffer, 65536, &actual_length, useBinaryProtocol, &packetsInLoop);
2858  numPacketsProcessed++;
2859 
2860  ros::Duration dur = recvTimeStampPush - recvTimeStamp;
2861 
2862  if (result != 0)
2863  {
2864  ROS_ERROR("Read Error when getting datagram: %i.", result);
2865  diagnostics_.broadcast(getDiagnosticErrorCode(), "Read Error when getting datagram.");
2866  return ExitError; // return failure to exit node
2867  }
2868  if (actual_length <= 0)
2869  {
2870  return ExitSuccess;
2871  } // return success to continue looping
2872 
2873  // ----- if requested, skip frames
2874  if (iteration_count++ % (config_.skip + 1) != 0)
2875  {
2876  return ExitSuccess;
2877  }
2878 
2879  ROS_DEBUG_STREAM("SickScanCommon::loopOnce: received " << actual_length << " byte data " << DataDumper::binDataToAsciiString(&receiveBuffer[0], std::min(32, actual_length)) << " ... ");
2880 
2881 
2882  if (publish_datagram_)
2883  {
2884  std_msgs::String datagram_msg;
2885  datagram_msg.data = std::string(reinterpret_cast<char *>(receiveBuffer));
2886  datagram_pub_.publish(datagram_msg);
2887  }
2888 
2889 
2890  if (verboseLevel > 0)
2891  {
2892  dumpDatagramForDebugging(receiveBuffer, actual_length);
2893  }
2894 
2895 
2896  bool deviceIsRadar = false;
2897 
2898  if (this->parser_->getCurrentParamPtr()->getDeviceIsRadar() == true)
2899  {
2900  deviceIsRadar = true;
2901  }
2902 
2903  if (true == deviceIsRadar)
2904  {
2906  int errorCode = ExitSuccess;
2907  // parse radar telegram and send pointcloud2-debug messages
2908  errorCode = radar->parseDatagram(recvTimeStamp, (unsigned char *) receiveBuffer, actual_length,
2909  useBinaryProtocol);
2910  return errorCode; // return success to continue looping
2911  }
2912 
2913  static SickScanImu scanImu(this); // todo remove static
2914  if (scanImu.isImuDatagram((char *) receiveBuffer, actual_length))
2915  {
2916  int errorCode = ExitSuccess;
2917  if (scanImu.isImuAckDatagram((char *) receiveBuffer, actual_length))
2918  {
2919 
2920  }
2921  else
2922  {
2923  // parse radar telegram and send pointcloud2-debug messages
2924  errorCode = scanImu.parseDatagram(recvTimeStamp, (unsigned char *) receiveBuffer, actual_length,
2925  useBinaryProtocol);
2926 
2927  }
2928  return errorCode; // return success to continue looping
2929  }
2930  else if(memcmp(&receiveBuffer[8], "sSN LIDoutputstate", strlen("sSN LIDoutputstate")) == 0)
2931  {
2932  int errorCode = ExitSuccess;
2933  ROS_DEBUG_STREAM("SickScanCommon: received " << actual_length << " byte LIDoutputstate " << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length));
2934  // Parse and convert LIDoutputstate message
2935  std::string scanner_name = parser_->getCurrentParamPtr()->getScannerName();
2936  EVAL_FIELD_SUPPORT eval_field_logic = this->parser_->getCurrentParamPtr()->getUseEvalFields();
2937  sick_scan::LIDoutputstateMsg outputstate_msg;
2938  if (sick_scan::SickScanMessages::parseLIDoutputstateMsg(recvTimeStamp, receiveBuffer, actual_length, useBinaryProtocol, scanner_name, outputstate_msg))
2939  {
2940  // Publish LIDoutputstate message
2942  {
2943  lidoutputstate_pub_.publish(outputstate_msg);
2944  }
2945  if(cloud_marker_)
2946  {
2947  cloud_marker_->updateMarker(outputstate_msg, eval_field_logic);
2948  }
2949  }
2950  else
2951  {
2952  ROS_WARN_STREAM("## ERROR SickScanCommon: parseLIDoutputstateMsg failed, received " << actual_length << " byte LIDoutputstate " << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length));
2953  }
2954  return errorCode; // return success to continue looping
2955  }
2956  else if(memcmp(&receiveBuffer[8], "sSN LIDinputstate", strlen("sSN LIDinputstate")) == 0)
2957  {
2958  int errorCode = ExitSuccess;
2959  // Parse active_fieldsetfrom LIDinputstate message
2961  if(fieldMon && useBinaryProtocol && actual_length > 32)
2962  {
2963  // int fieldset = (receiveBuffer[32] & 0xFF);
2964  // fieldMon->setActiveFieldset(fieldset);
2965  fieldMon->parseBinaryLIDinputstateMsg(receiveBuffer, actual_length);
2966  ROS_DEBUG_STREAM("SickScanCommon: received " << actual_length << " byte LIDinputstate " << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length)
2967  << ", active fieldset = " << fieldMon->getActiveFieldset());
2968  }
2969  return errorCode; // return success to continue looping
2970  }
2971  else if(memcmp(&receiveBuffer[8], "sSN LFErec", strlen("sSN LFErec")) == 0)
2972  {
2973  int errorCode = ExitSuccess;
2974  ROS_DEBUG_STREAM("SickScanCommon: received " << actual_length << " byte LFErec " << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length));
2975  // Parse and convert LFErec message
2976  sick_scan::LFErecMsg lferec_msg;
2977  std::string scanner_name = parser_->getCurrentParamPtr()->getScannerName();
2978  EVAL_FIELD_SUPPORT eval_field_logic = parser_->getCurrentParamPtr()->getUseEvalFields(); // == USE_EVAL_FIELD_LMS5XX_LOGIC
2979  if (sick_scan::SickScanMessages::parseLFErecMsg(recvTimeStamp, receiveBuffer, actual_length, useBinaryProtocol, eval_field_logic, scanner_name, lferec_msg))
2980  {
2981  // Publish LFErec message
2982  if(publish_lferec_)
2983  {
2984  lferec_pub_.publish(lferec_msg);
2985  }
2986  if(cloud_marker_)
2987  {
2988  cloud_marker_->updateMarker(lferec_msg, eval_field_logic);
2989  }
2990  }
2991  else
2992  {
2993  ROS_WARN_STREAM("## ERROR SickScanCommon: parseLFErecMsg failed, received " << actual_length << " byte LFErec " << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length));
2994  }
2995  return errorCode; // return success to continue looping
2996  }
2997  else if(memcmp(&receiveBuffer[8], "sSN LMDscandatamon", strlen("sSN LMDscandatamon")) == 0)
2998  {
2999  int errorCode = ExitSuccess;
3000  ROS_DEBUG_STREAM("SickScanCommon: received " << actual_length << " byte LMDscandatamon (ignored) ..."); // << DataDumper::binDataToAsciiString(&receiveBuffer[0], actual_length));
3001  return errorCode; // return success to continue looping
3002  }
3003  else
3004  {
3005 
3006  sensor_msgs::LaserScan msg;
3007  sick_scan::Encoder EncoderMsg;
3008  EncoderMsg.header.stamp = recvTimeStamp + ros::Duration(config_.time_offset);
3009  //TODO remove this hardcoded variable
3010  bool FireEncoder = false;
3011  EncoderMsg.header.frame_id = "Encoder";
3012  EncoderMsg.header.seq = numPacketsProcessed;
3013  msg.header.stamp = recvTimeStamp + ros::Duration(config_.time_offset);
3014  double elevationAngleInRad = 0.0;
3015  /*
3016  * datagrams are enclosed in <STX> (0x02), <ETX> (0x03) pairs
3017  */
3018  char *buffer_pos = (char *) receiveBuffer;
3019  char *dstart, *dend;
3020  bool dumpDbg = false;
3021  bool dataToProcess = true;
3022  std::vector<float> vang_vec;
3023  vang_vec.clear();
3024  dstart = NULL;
3025  dend = NULL;
3026 
3027  while (dataToProcess)
3028  {
3029  const int maxAllowedEchos = 5;
3030 
3031  int numValidEchos = 0;
3032  int aiValidEchoIdx[maxAllowedEchos] = {0};
3033  size_t dlength;
3034  int success = -1;
3035  int numEchos = 0;
3036  int echoMask = 0;
3037  bool publishPointCloud = true;
3038 
3039  if (useBinaryProtocol)
3040  {
3041  // if binary protocol used then parse binary message
3042  std::vector<unsigned char> receiveBufferVec = std::vector<unsigned char>(receiveBuffer,
3043  receiveBuffer + actual_length);
3044 #ifdef DEBUG_DUMP_TO_CONSOLE_ENABLED
3045  if (actual_length > 1000)
3046  {
3047  DataDumper::instance().dumpUcharBufferToConsole(receiveBuffer, actual_length);
3048 
3049  }
3050 
3051  DataDumper::instance().dumpUcharBufferToConsole(receiveBuffer, actual_length);
3052 #endif
3053  if (receiveBufferVec.size() > 8)
3054  {
3055  long idVal = 0;
3056  long lenVal = 0;
3057  memcpy(&idVal, receiveBuffer + 0, 4); // read identifier
3058  memcpy(&lenVal, receiveBuffer + 4, 4); // read length indicator
3059  swap_endian((unsigned char *) &lenVal, 4);
3060 
3061  if (idVal == 0x02020202) // id for binary message
3062  {
3063 #if 0
3064  {
3065  static int cnt = 0;
3066  char szFileName[255];
3067 
3068 #ifdef _MSC_VER
3069  sprintf(szFileName, "c:\\temp\\dump%05d.bin", cnt);
3070 #else
3071  sprintf(szFileName, "/tmp/dump%05d.txt", cnt);
3072 #endif
3073  FILE *fout;
3074  fout = fopen(szFileName, "wb");
3075  fwrite(receiveBuffer, actual_length, 1, fout);
3076  fclose(fout);
3077  cnt++;
3078  }
3079 #endif
3080  // binary message
3081  if (lenVal < actual_length)
3082  {
3083  short elevAngleX200 = 0; // signed short (F5 B2 -> Layer 24
3084  // F5B2h -> -2638/200= -13.19°
3085  int scanFrequencyX100 = 0;
3086  double elevAngle = 0.00;
3087  double scanFrequency = 0.0;
3088  long measurementFrequencyDiv100 = 0; // multiply with 100
3089  int numOfEncoders = 0;
3090  int numberOf16BitChannels = 0;
3091  int numberOf8BitChannels = 0;
3092  uint32_t SystemCountScan = 0;
3093  static uint32_t lastSystemCountScan = 0;// this variable is used to ensure that only the first time stamp of an multi layer scann is used for PLL updating
3094  uint32_t SystemCountTransmit = 0;
3095 
3096  memcpy(&elevAngleX200, receiveBuffer + 50, 2);
3097  swap_endian((unsigned char *) &elevAngleX200, 2);
3098 
3099  elevationAngleInRad = -elevAngleX200 / 200.0 * deg2rad_const;
3100  //TODO check this ??
3101  msg.header.seq = elevAngleX200; // should be multiple of 0.625° starting with -2638 (corresponding to 13.19°)
3102 
3103  memcpy(&SystemCountScan, receiveBuffer + 0x26, 4);
3104  swap_endian((unsigned char *) &SystemCountScan, 4);
3105 
3106  memcpy(&SystemCountTransmit, receiveBuffer + 0x2A, 4);
3107  swap_endian((unsigned char *) &SystemCountTransmit, 4);
3108  double timestampfloat = recvTimeStamp.sec + recvTimeStamp.nsec * 1e-9;
3109  bool bRet;
3110  if (SystemCountScan !=
3111  lastSystemCountScan)//MRS 6000 sends 6 packets with same SystemCountScan we should only update the pll once with this time stamp since the SystemCountTransmit are different and this will only increase jitter of the pll
3112  {
3113  bRet = SoftwarePLL::instance().updatePLL(recvTimeStamp.sec, recvTimeStamp.nsec,
3114  SystemCountTransmit);
3115  lastSystemCountScan = SystemCountScan;
3116  }
3117  ros::Time tmp_time = recvTimeStamp;
3118  bRet = SoftwarePLL::instance().getCorrectedTimeStamp(recvTimeStamp.sec, recvTimeStamp.nsec,
3119  SystemCountScan);
3120  double timestampfloat_coor = recvTimeStamp.sec + recvTimeStamp.nsec * 1e-9;
3121  double DeltaTime = timestampfloat - timestampfloat_coor;
3122  //ROS_INFO("%F,%F,%u,%u,%F",timestampfloat,timestampfloat_coor,SystemCountTransmit,SystemCountScan,DeltaTime);
3123  //TODO Handle return values
3124  if (config_.sw_pll_only_publish == true && bRet == false)
3125  {
3126  int packets_expected_to_drop = SoftwarePLL::instance().fifoSize - 1;
3128  ROS_INFO("%i / %i Packet dropped Software PLL not yet locked.",
3129  SoftwarePLL::instance().packeds_droped, packets_expected_to_drop);
3130  if (SoftwarePLL::instance().packeds_droped == packets_expected_to_drop)
3131  {
3132  ROS_INFO("Software PLL is expected to be ready now!");
3133  }
3134  if (SoftwarePLL::instance().packeds_droped > packets_expected_to_drop)
3135  {
3136  ROS_WARN("More packages than expected were dropped!!\n"
3137  "Check the network connection.\n"
3138  "Check if the system time has been changed in a leap.\n"
3139  "If the problems can persist, disable the software PLL with the option sw_pll_only_publish=False !");
3140  }
3141  dataToProcess = false;
3142  break;
3143  }
3144 
3145 #ifdef DEBUG_DUMP_ENABLED
3146  double elevationAngleInDeg = elevationAngleInRad = -elevAngleX200 / 200.0;
3147  // DataDumper::instance().pushData((double)SystemCountScan, "LAYER", elevationAngleInDeg);
3148  //DataDumper::instance().pushData((double)SystemCountScan, "LASESCANTIME", SystemCountScan);
3149  //DataDumper::instance().pushData((double)SystemCountTransmit, "LASERTRANSMITTIME", SystemCountTransmit);
3150  //DataDumper::instance().pushData((double)SystemCountScan, "LASERTRANSMITDELAY", debug_duration.toSec());
3151 #endif
3152 
3153  /*
3154  uint16_t u16_active_fieldset = 0;
3155  memcpy(&u16_active_fieldset, receiveBuffer + 46, 2); // byte 46 + 47: input status (0 0), active fieldset
3156  swap_endian((unsigned char *) &u16_active_fieldset, 2);
3157  SickScanFieldMonSingleton *fieldMon = SickScanFieldMonSingleton::getInstance();
3158  if(fieldMon)
3159  {
3160  fieldMon->setActiveFieldset(u16_active_fieldset & 0xFF);
3161  ROS_INFO("Binary scandata: active_fieldset = %d", fieldMon->getActiveFieldset());
3162  }
3163  */
3164  // byte 48 + 49: output status (0 0)
3165  // byte 50 + 51: reserved
3166 
3167  memcpy(&scanFrequencyX100, receiveBuffer + 52, 4);
3168  swap_endian((unsigned char *) &scanFrequencyX100, 4);
3169 
3170  memcpy(&measurementFrequencyDiv100, receiveBuffer + 56, 4);
3171  swap_endian((unsigned char *) &measurementFrequencyDiv100, 4);
3172 
3173 
3174  msg.scan_time = 1.0 / (scanFrequencyX100 / 100.0);
3175 
3176  //due firmware inconsistency
3177  if (measurementFrequencyDiv100 > 10000)
3178  {
3179  measurementFrequencyDiv100 /= 100;
3180  }
3181  msg.time_increment = 1.0 / (measurementFrequencyDiv100 * 100.0);
3182  timeIncrement = msg.time_increment;
3183  msg.range_min = parser_->get_range_min();
3184  msg.range_max = parser_->get_range_max();
3185 
3186  memcpy(&numOfEncoders, receiveBuffer + 60, 2);
3187  swap_endian((unsigned char *) &numOfEncoders, 2);
3188  int encoderDataOffset = 6 * numOfEncoders;
3189  int32_t EncoderPosTicks[4] = {0};
3190  int16_t EncoderSpeed[4] = {0};
3191 
3192  if (numOfEncoders > 0 && numOfEncoders < 5)
3193  {
3194  FireEncoder = true;
3195  for (int EncoderNum = 0; EncoderNum < numOfEncoders; EncoderNum++)
3196  {
3197  memcpy(&EncoderPosTicks[EncoderNum], receiveBuffer + 62 + EncoderNum * 6, 4);
3198  swap_endian((unsigned char *) &EncoderPosTicks[EncoderNum], 4);
3199  memcpy(&EncoderSpeed[EncoderNum], receiveBuffer + 66 + EncoderNum * 6, 2);
3200  swap_endian((unsigned char *) &EncoderSpeed[EncoderNum], 2);
3201  }
3202  }
3203  //TODO handle multi encoder with multiple encode msg or different encoder msg definition now using only first encoder
3204  EncoderMsg.enc_position = EncoderPosTicks[0];
3205  EncoderMsg.enc_speed = EncoderSpeed[0];
3206  memcpy(&numberOf16BitChannels, receiveBuffer + 62 + encoderDataOffset, 2);
3207  swap_endian((unsigned char *) &numberOf16BitChannels, 2);
3208 
3209  int parseOff = 64 + encoderDataOffset;
3210 
3211 
3212  char szChannel[255] = {0};
3213  float scaleFactor = 1.0;
3214  float scaleFactorOffset = 0.0;
3215  int32_t startAngleDiv10000 = 1;
3216  int32_t sizeOfSingleAngularStepDiv10000 = 1;
3217  double startAngle = 0.0;
3218  double sizeOfSingleAngularStep = 0.0;
3219  short numberOfItems = 0;
3220 
3221  static int cnt = 0;
3222  cnt++;
3223  // get number of 8 bit channels
3224  // we must jump of the 16 bit data blocks including header ...
3225  for (int i = 0; i < numberOf16BitChannels; i++)
3226  {
3227  int numberOfItems = 0x00;
3228  memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3229  swap_endian((unsigned char *) &numberOfItems, 2);
3230  parseOff += 21; // 21 Byte header followed by data entries
3231  parseOff += numberOfItems * 2;
3232  }
3233 
3234  // now we can read the number of 8-Bit-Channels
3235  memcpy(&numberOf8BitChannels, receiveBuffer + parseOff, 2);
3236  swap_endian((unsigned char *) &numberOf8BitChannels, 2);
3237 
3238  parseOff = 64 + encoderDataOffset;
3239  enum datagram_parse_task
3240  {
3241  process_dist,
3242  process_vang,
3243  process_rssi,
3244  process_idle
3245  };
3246  int rssiCnt = 0;
3247  int vangleCnt = 0;
3248  int distChannelCnt = 0;
3249 
3250  for (int processLoop = 0; processLoop < 2; processLoop++)
3251  {
3252  int totalChannelCnt = 0;
3253 
3254 
3255  bool bCont = true;
3256 
3257  datagram_parse_task task = process_idle;
3258  bool parsePacket = true;
3259  parseOff = 64 + encoderDataOffset;
3260  bool processData = false;
3261 
3262  if (processLoop == 0)
3263  {
3264  distChannelCnt = 0;
3265  rssiCnt = 0;
3266  vangleCnt = 0;
3267  }
3268 
3269  if (processLoop == 1)
3270  {
3271  processData = true;
3272  numEchos = distChannelCnt;
3273  msg.ranges.resize(numberOfItems * numEchos);
3274  if (rssiCnt > 0)
3275  {
3276  msg.intensities.resize(numberOfItems * rssiCnt);
3277  }
3278  else
3279  {
3280  }
3281  if (vangleCnt > 0) // should be 0 or 1
3282  {
3283  vang_vec.resize(numberOfItems * vangleCnt);
3284  }
3285  else
3286  {
3287  vang_vec.clear();
3288  }
3289  echoMask = (1 << numEchos) - 1;
3290 
3291  // reset count. We will use the counter for index calculation now.
3292  distChannelCnt = 0;
3293  rssiCnt = 0;
3294  vangleCnt = 0;
3295 
3296  }
3297 
3298  szChannel[6] = '\0';
3299  scaleFactor = 1.0;
3300  scaleFactorOffset = 0.0;
3301  startAngleDiv10000 = 1;
3302  sizeOfSingleAngularStepDiv10000 = 1;
3303  startAngle = 0.0;
3304  sizeOfSingleAngularStep = 0.0;
3305  numberOfItems = 0;
3306 
3307 
3308 #if 1 // prepared for multiecho parsing
3309 
3310  bCont = true;
3311  bool doVangVecProc = false;
3312  // try to get number of DIST and RSSI from binary data
3313  task = process_idle;
3314  do
3315  {
3316  task = process_idle;
3317  doVangVecProc = false;
3318  int processDataLenValuesInBytes = 2;
3319 
3320  if (totalChannelCnt == numberOf16BitChannels)
3321  {
3322  parseOff += 2; // jump of number of 8 bit channels- already parsed above
3323  }
3324 
3325  if (totalChannelCnt >= numberOf16BitChannels)
3326  {
3327  processDataLenValuesInBytes = 1; // then process 8 bit values ...
3328  }
3329  bCont = false;
3330  strcpy(szChannel, "");
3331 
3332  if (totalChannelCnt < (numberOf16BitChannels + numberOf8BitChannels))
3333  {
3334  szChannel[5] = '\0';
3335  strncpy(szChannel, (const char *) receiveBuffer + parseOff, 5);
3336  }
3337  else
3338  {
3339  // all channels processed (16 bit and 8 bit channels)
3340  }
3341 
3342  if (strstr(szChannel, "DIST") == szChannel)
3343  {
3344  task = process_dist;
3345  distChannelCnt++;
3346  bCont = true;
3347  numberOfItems = 0;
3348  memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3349  swap_endian((unsigned char *) &numberOfItems, 2);
3350 
3351  }
3352  if (strstr(szChannel, "VANG") == szChannel)
3353  {
3354  vangleCnt++;
3355  task = process_vang;
3356  bCont = true;
3357  numberOfItems = 0;
3358  memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3359  swap_endian((unsigned char *) &numberOfItems, 2);
3360 
3361  vang_vec.resize(numberOfItems);
3362 
3363  }
3364  if (strstr(szChannel, "RSSI") == szChannel)
3365  {
3366  task = process_rssi;
3367  rssiCnt++;
3368  bCont = true;
3369  numberOfItems = 0;
3370  // copy two byte value (unsigned short to numberOfItems
3371  memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3372  swap_endian((unsigned char *) &numberOfItems, 2); // swap
3373 
3374  }
3375  if (bCont)
3376  {
3377  scaleFactor = 0.0;
3378  scaleFactorOffset = 0.0;
3379  startAngleDiv10000 = 0;
3380  sizeOfSingleAngularStepDiv10000 = 0;
3381  numberOfItems = 0;
3382 
3383  memcpy(&scaleFactor, receiveBuffer + parseOff + 5, 4);
3384  memcpy(&scaleFactorOffset, receiveBuffer + parseOff + 9, 4);
3385  memcpy(&startAngleDiv10000, receiveBuffer + parseOff + 13, 4);
3386  memcpy(&sizeOfSingleAngularStepDiv10000, receiveBuffer + parseOff + 17, 2);
3387  memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3388 
3389 
3390  swap_endian((unsigned char *) &scaleFactor, 4);
3391  swap_endian((unsigned char *) &scaleFactorOffset, 4);
3392  swap_endian((unsigned char *) &startAngleDiv10000, 4);
3393  swap_endian((unsigned char *) &sizeOfSingleAngularStepDiv10000, 2);
3394  swap_endian((unsigned char *) &numberOfItems, 2);
3395 
3396  if (processData)
3397  {
3398  unsigned short *data = (unsigned short *) (receiveBuffer + parseOff + 21);
3399 
3400  unsigned char *swapPtr = (unsigned char *) data;
3401  // copy RSSI-Values +2 for 16-bit values +1 for 8-bit value
3402  for (int i = 0;
3403  i < numberOfItems * processDataLenValuesInBytes; i += processDataLenValuesInBytes)
3404  {
3405  if (processDataLenValuesInBytes == 1)
3406  {
3407  }
3408  else
3409  {
3410  unsigned char tmp;
3411  tmp = swapPtr[i + 1];
3412  swapPtr[i + 1] = swapPtr[i];
3413  swapPtr[i] = tmp;
3414  }
3415  }
3416  int idx = 0;
3417 
3418  switch (task)
3419  {
3420 
3421  case process_dist:
3422  {
3423  startAngle = startAngleDiv10000 / 10000.00;
3424  sizeOfSingleAngularStep = sizeOfSingleAngularStepDiv10000 / 10000.0;
3425  sizeOfSingleAngularStep *= (M_PI / 180.0);
3426 
3427  msg.angle_min = startAngle / 180.0 * M_PI - M_PI / 2;
3428  msg.angle_increment = sizeOfSingleAngularStep;
3429  msg.angle_max = msg.angle_min + (numberOfItems - 1) * msg.angle_increment;
3430 
3432  {
3433  msg.angle_min -= M_PI/2;
3434  msg.angle_max -= M_PI/2;
3435 
3436  msg.angle_min *= -1.0;
3437  msg.angle_increment *= -1.0;
3438  msg.angle_max *= -1.0;
3439 
3440  }
3441  float *rangePtr = NULL;
3442 
3443  if (numberOfItems > 0)
3444  {
3445  rangePtr = &msg.ranges[0];
3446  }
3447  float scaleFactor_001 = 0.001F * scaleFactor;// to avoid repeated multiplication
3448  for (int i = 0; i < numberOfItems; i++)
3449  {
3450  idx = i + numberOfItems * (distChannelCnt - 1);
3451  rangePtr[idx] = (float) data[i] * scaleFactor_001 + scaleFactorOffset;
3452 #ifdef DEBUG_DUMP_ENABLED
3453  if (distChannelCnt == 1)
3454  {
3455  if (i == floor(numberOfItems / 2))
3456  {
3457  double curTimeStamp = SystemCountScan + i * msg.time_increment * 1E6;
3458  //DataDumper::instance().pushData(curTimeStamp, "DIST", rangePtr[idx]);
3459  }
3460  }
3461 #endif
3462  //XXX
3463  }
3464 
3465  }
3466  break;
3467  case process_rssi:
3468  {
3469  // Das muss vom Protokoll abgeleitet werden. !!!
3470 
3471  float *intensityPtr = NULL;
3472 
3473  if (numberOfItems > 0)
3474  {
3475  intensityPtr = &msg.intensities[0];
3476 
3477  }
3478  for (int i = 0; i < numberOfItems; i++)
3479  {
3480  idx = i + numberOfItems * (rssiCnt - 1);
3481  // we must select between 16 bit and 8 bit values
3482  float rssiVal = 0.0;
3483  if (processDataLenValuesInBytes == 2)
3484  {
3485  rssiVal = (float) data[i];
3486  }
3487  else
3488  {
3489  unsigned char *data8Ptr = (unsigned char *) data;
3490  rssiVal = (float) data8Ptr[i];
3491  }
3492  intensityPtr[idx] = rssiVal * scaleFactor + scaleFactorOffset;
3493  }
3494  }
3495  break;
3496 
3497  case process_vang:
3498  float *vangPtr = NULL;
3499  if (numberOfItems > 0)
3500  {
3501  vangPtr = &vang_vec[0]; // much faster, with vang_vec[i] each time the size will be checked
3502  }
3503  for (int i = 0; i < numberOfItems; i++)
3504  {
3505  vangPtr[i] = (float) data[i] * scaleFactor + scaleFactorOffset;
3506  }
3507  break;
3508  }
3509  }
3510  parseOff += 21 + processDataLenValuesInBytes * numberOfItems;
3511 
3512 
3513  }
3514  totalChannelCnt++;
3515  } while (bCont);
3516  }
3517 #endif
3518 
3519  elevAngle = elevAngleX200 / 200.0;
3520  scanFrequency = scanFrequencyX100 / 100.0;
3521 
3522 
3523  }
3524  }
3525  }
3526 
3527  //TODO timing issue posible here
3528  parser_->checkScanTiming(msg.time_increment, msg.scan_time, msg.angle_increment, 0.00001f);
3529 
3530  success = ExitSuccess;
3531  // change Parsing Mode
3532  dataToProcess = false; // only one package allowed - no chaining
3533  }
3534  else // Parsing of Ascii-Encoding of datagram, xxx
3535  {
3536  dstart = strchr(buffer_pos, 0x02);
3537  if (dstart != NULL)
3538  {
3539  dend = strchr(dstart + 1, 0x03);
3540  }
3541  if ((dstart != NULL) && (dend != NULL))
3542  {
3543  dataToProcess = true; // continue parasing
3544  dlength = dend - dstart;
3545  *dend = '\0';
3546  dstart++;
3547  }
3548  else
3549  {
3550  dataToProcess = false;
3551  break; //
3552  }
3553 
3554  if (dumpDbg)
3555  {
3556  {
3557  static int cnt = 0;
3558  char szFileName[255];
3559 
3560 #ifdef _MSC_VER
3561  sprintf(szFileName, "c:\\temp\\dump%05d.txt", cnt);
3562 #else
3563  sprintf(szFileName, "/tmp/dump%05d.txt", cnt);
3564 #endif
3565 #if 0
3566  FILE *fout;
3567  fout = fopen(szFileName, "wb");
3568  fwrite(dstart, dlength, 1, fout);
3569  fclose(fout);
3570 #endif
3571  cnt++;
3572  }
3573  }
3574 
3575  // HEADER of data followed by DIST1 ... DIST2 ... DIST3 .... RSSI1 ... RSSI2.... RSSI3...
3576 
3577  // <frameid>_<sign>00500_DIST[1|2|3]
3578  numEchos = 1;
3579  // numEchos contains number of echos (1..5)
3580  // _msg holds ALL data of all echos
3581  success = parser_->parse_datagram(dstart, dlength, config_, msg, numEchos, echoMask);
3582  publishPointCloud = true; // for MRS1000
3583 
3584  numValidEchos = 0;
3585  for (int i = 0; i < maxAllowedEchos; i++)
3586  {
3587  aiValidEchoIdx[i] = 0;
3588  }
3589  }
3590 
3591 
3592  int numOfLayers = parser_->getCurrentParamPtr()->getNumberOfLayers();
3593 
3594  if (success == ExitSuccess)
3595  {
3596  bool elevationPreCalculated = false;
3597  double elevationAngleDegree = 0.0;
3598 
3599 
3600  std::vector<float> rangeTmp = msg.ranges; // copy all range value
3601  std::vector<float> intensityTmp = msg.intensities; // copy all intensity value
3602 
3603  int intensityTmpNum = intensityTmp.size();
3604  float *intensityTmpPtr = NULL;
3605  if (intensityTmpNum > 0)
3606  {
3607  intensityTmpPtr = &intensityTmp[0];
3608  }
3609 
3610  // Helpful: https://answers.ros.org/question/191265/pointcloud2-access-data/
3611  // https://gist.github.com/yuma-m/b5dcce1b515335c93ce8
3612  // Copy to pointcloud
3613  int layer = 0;
3614  int baseLayer = 0;
3615  bool useGivenElevationAngle = false;
3616  switch (numOfLayers)
3617  {
3618  case 1: // TIM571 etc.
3619  baseLayer = 0;
3620  break;
3621  case 4:
3622 
3623  baseLayer = -1;
3624  if (msg.header.seq == 250)
3625  { layer = -1; }
3626  else if (msg.header.seq == 0)
3627  { layer = 0; }
3628  else if (msg.header.seq == -250)
3629  { layer = 1; }
3630  else if (msg.header.seq == -500)
3631  { layer = 2; }
3632  elevationAngleDegree = this->parser_->getCurrentParamPtr()->getElevationDegreeResolution();
3633  elevationAngleDegree = elevationAngleDegree / 180.0 * M_PI;
3634  // 0.0436332 /*2.5 degrees*/;
3635  break;
3636  case 24: // Preparation for MRS6000
3637  baseLayer = -1;
3638  layer = (msg.header.seq - (-2638)) / 125;
3639  layer = (23 - layer) - 1;
3640 #if 0
3641  elevationAngleDegree = this->parser_->getCurrentParamPtr()->getElevationDegreeResolution();
3642  elevationAngleDegree = elevationAngleDegree / 180.0 * M_PI;
3643 #endif
3644 
3645  elevationPreCalculated = true;
3646  if (vang_vec.size() > 0)
3647  {
3648  useGivenElevationAngle = true;
3649  }
3650  break;
3651  default:
3652  assert(0);
3653  break; // unsupported
3654 
3655  }
3656 
3657 
3658 
3659 
3660 
3661  // XXX - HIER MEHRERE SCANS publish, falls Mehrzielszenario läuft
3662  if (numEchos > 5)
3663  {
3664  ROS_WARN("Too much echos");
3665  }
3666  else
3667  {
3668 
3669  size_t startOffset = 0;
3670  size_t endOffset = 0;
3671  int echoPartNum = msg.ranges.size() / numEchos;
3672  for (int i = 0; i < numEchos; i++)
3673  {
3674 
3675  bool sendMsg = false;
3676  if ((echoMask & (1 << i)) & outputChannelFlagId)
3677  {
3678  aiValidEchoIdx[numValidEchos] = i; // save index
3679  numValidEchos++;
3680  sendMsg = true;
3681  }
3682  startOffset = i * echoPartNum;
3683  endOffset = (i + 1) * echoPartNum;
3684 
3685  msg.ranges.clear();
3686  msg.intensities.clear();
3687  msg.ranges = std::vector<float>(
3688  rangeTmp.begin() + startOffset,
3689  rangeTmp.begin() + endOffset);
3690  // check also for MRS1104
3691  if (endOffset <= intensityTmp.size() && (intensityTmp.size() > 0))
3692  {
3693  msg.intensities = std::vector<float>(
3694  intensityTmp.begin() + startOffset,
3695  intensityTmp.begin() + endOffset);
3696  }
3697  else
3698  {
3699  msg.intensities.resize(echoPartNum); // fill with zeros
3700  }
3701  {
3702  // numEchos
3703  char szTmp[255] = {0};
3704  if (this->parser_->getCurrentParamPtr()->getNumberOfLayers() > 1)
3705  {
3706  const char *cpFrameId = config_.frame_id.c_str();
3707 #if 0
3708  sprintf(szTmp, "%s_%+04d_DIST%d", cpFrameId, msg.header.seq, i + 1);
3709 #else // experimental
3710  char szSignName[10] = {0};
3711  if ((int) msg.header.seq < 0)
3712  {
3713  strcpy(szSignName, "NEG");
3714  }
3715  else
3716  {
3717  strcpy(szSignName, "POS");
3718 
3719  }
3720 
3721  sprintf(szTmp, "%s_%s_%03d_DIST%d", cpFrameId, szSignName, abs((int) msg.header.seq), i + 1);
3722 #endif
3723  }
3724  else
3725  {
3726  strcpy(szTmp, config_.frame_id.c_str());
3727  }
3728 
3729  msg.header.frame_id = std::string(szTmp);
3730  // Hector slam can only process ONE valid frame id.
3731  if (echoForSlam.length() > 0)
3732  {
3733  if (slamBundle)
3734  {
3735  // try to map first echos to horizontal layers.
3736  if (i == 0)
3737  {
3738  // first echo
3739  msg.header.frame_id = echoForSlam;
3740  strcpy(szTmp, echoForSlam.c_str()); //
3741  if (elevationAngleInRad != 0.0)
3742  {
3743  float cosVal = cos(elevationAngleInRad);
3744  int rangeNum = msg.ranges.size();
3745  for (int j = 0; j < rangeNum; j++)
3746  {
3747  msg.ranges[j] *= cosVal;
3748  }
3749  }
3750  }
3751  }
3752 
3753  if (echoForSlam.compare(szTmp) == 0)
3754  {
3755  sendMsg = true;
3756  }
3757  else
3758  {
3759  sendMsg = false;
3760  }
3761  }
3762 
3763  }
3764 #ifndef _MSC_VER
3765  if (parser_->getCurrentParamPtr()->getEncoderMode() >= 0 && FireEncoder == true)//
3766  {
3767  Encoder_pub.publish(EncoderMsg);
3768  }
3769  if (numOfLayers > 4)
3770  {
3771  sendMsg = false; // too many layers for publish as scan message. Only pointcloud messages will be pub.
3772  }
3773  if (sendMsg &
3774  outputChannelFlagId) // publish only configured channels - workaround for cfg-bug MRS1104
3775  {
3776 
3777  pub_.publish(msg);
3778 
3779  }
3780 #else
3781  printf("MSG received...");
3782 #endif
3783  }
3784  }
3785 
3786 
3787  if (publishPointCloud == true)
3788  {
3789 
3790 
3791  const int numChannels = 4; // x y z i (for intensity)
3792 
3793  int numTmpLayer = numOfLayers;
3794 
3795 
3796  cloud_.header.stamp = recvTimeStamp + ros::Duration(config_.time_offset);
3797 
3798 
3799  cloud_.header.frame_id = config_.frame_id;
3800  cloud_.header.seq = 0;
3801  cloud_.height = numTmpLayer * numValidEchos; // due to multi echo multiplied by num. of layers
3802  cloud_.width = msg.ranges.size();
3803  cloud_.is_bigendian = false;
3804  cloud_.is_dense = true;
3805  cloud_.point_step = numChannels * sizeof(float);
3806  cloud_.row_step = cloud_.point_step * cloud_.width;
3807  cloud_.fields.resize(numChannels);
3808  for (int i = 0; i < numChannels; i++)
3809  {
3810  std::string channelId[] = {"x", "y", "z", "intensity"};
3811  cloud_.fields[i].name = channelId[i];
3812  cloud_.fields[i].offset = i * sizeof(float);
3813  cloud_.fields[i].count = 1;
3814  cloud_.fields[i].datatype = sensor_msgs::PointField::FLOAT32;
3815  }
3816 
3817  cloud_.data.resize(cloud_.row_step * cloud_.height);
3818 
3819  unsigned char *cloudDataPtr = &(cloud_.data[0]);
3820 
3821 
3822  // prepare lookup for elevation angle table
3823 
3824  std::vector<float> cosAlphaTable; // Lookup table for cos
3825  std::vector<float> sinAlphaTable; // Lookup table for sin
3826  size_t rangeNum = rangeTmp.size() / numValidEchos;
3827  cosAlphaTable.resize(rangeNum);
3828  sinAlphaTable.resize(rangeNum);
3829  float mirror_factor = 1.0;
3830  float angleShift=0;
3832  {
3833 // mirror_factor = -1.0;
3834 // angleShift = +M_PI/2.0; // add 90 deg for NAV3xx-series
3835  }
3836 
3837  for (size_t iEcho = 0; iEcho < numValidEchos; iEcho++)
3838  {
3839 
3840  float angle = config_.min_ang;
3841 
3842 
3843  float *cosAlphaTablePtr = &cosAlphaTable[0];
3844  float *sinAlphaTablePtr = &sinAlphaTable[0];
3845 
3846  float *vangPtr = NULL;
3847  float *rangeTmpPtr = &rangeTmp[0];
3848  if (vang_vec.size() > 0)
3849  {
3850  vangPtr = &vang_vec[0];
3851  }
3852  for (size_t i = 0; i < rangeNum; i++)
3853  {
3854  enum enum_index_descr
3855  {
3856  idx_x,
3857  idx_y,
3858  idx_z,
3859  idx_intensity,
3860  idx_num
3861  };
3862  long adroff = i * (numChannels * (int) sizeof(float));
3863 
3864  adroff += (layer - baseLayer) * cloud_.row_step;
3865 
3866  adroff += iEcho * cloud_.row_step * numTmpLayer;
3867 
3868  unsigned char *ptr = cloudDataPtr + adroff;
3869  float *fptr = (float *) (cloudDataPtr + adroff);
3870 
3871  geometry_msgs::Point32 point;
3872  float range_meter = rangeTmpPtr[iEcho * rangeNum + i];
3873  float phi = angle; // azimuth angle
3874  float alpha = 0.0; // elevation angle
3875 
3876  if (useGivenElevationAngle) // FOR MRS6124
3877  {
3878  alpha = -vangPtr[i] * deg2rad_const;
3879  }
3880  else
3881  {
3882  if (elevationPreCalculated) // FOR MRS6124 without VANGL
3883  {
3884  alpha = elevationAngleInRad;
3885  }
3886  else
3887  {
3888  alpha = layer * elevationAngleDegree; // for MRS1104
3889  }
3890  }
3891 
3892  if (iEcho == 0)
3893  {
3894  cosAlphaTablePtr[i] = cos(alpha); // for z-value (elevation)
3895  sinAlphaTablePtr[i] = sin(alpha);
3896  }
3897  else
3898  {
3899  // Just for Debugging: printf("%3d %8.3lf %8.3lf\n", (int)i, cosAlphaTablePtr[i], sinAlphaTablePtr[i]);
3900  }
3901  // Thanks to Sebastian Pütz <spuetz@uos.de> for his hint
3902  float rangeCos = range_meter * cosAlphaTablePtr[i];
3903 
3904  double phi_used = phi + angleShift;
3905  if (this->angleCompensator != NULL)
3906  {
3907  phi_used = angleCompensator->compensateAngleInRadFromRos(phi_used);
3908  }
3909  fptr[idx_x] = rangeCos * cos(phi_used); // copy x value in pointcloud
3910  fptr[idx_y] = rangeCos * sin(phi_used); // copy y value in pointcloud
3911  fptr[idx_z] = range_meter * sinAlphaTablePtr[i] * mirror_factor;// copy z value in pointcloud
3912 
3913  fptr[idx_intensity] = 0.0;
3914  if (config_.intensity)
3915  {
3916  int intensityIndex = aiValidEchoIdx[iEcho] * rangeNum + i;
3917  // intensity values available??
3918  if (intensityIndex < intensityTmpNum)
3919  {
3920  fptr[idx_intensity] = intensityTmpPtr[intensityIndex]; // copy intensity value in pointcloud
3921  }
3922  }
3923  angle += msg.angle_increment;
3924  }
3925  // Publish
3926  static int cnt = 0;
3927  int layerOff = (layer - baseLayer);
3928 
3929  }
3930  // if ( (msg.header.seq == 0) || (layerOff == 0)) // FIXEN!!!!
3931  bool shallIFire = false;
3932  if ((msg.header.seq == 0) || (msg.header.seq == 237))
3933  {
3934  shallIFire = true;
3935  }
3936 
3937 
3938  static int layerCnt = 0;
3939  static int layerSeq[4];
3940 
3941  if (config_.cloud_output_mode > 0)
3942  {
3943 
3944  layerSeq[layerCnt % 4] = layer;
3945  if (layerCnt >= 4) // mind. erst einmal vier Layer zusammensuchen
3946  {
3947  shallIFire = true; // here are at least 4 layers available
3948  }
3949  else
3950  {
3951  shallIFire = false;
3952  }
3953 
3954  layerCnt++;
3955  }
3956 
3957  if (shallIFire) // shall i fire the signal???
3958  {
3959  if (config_.cloud_output_mode == 0)
3960  {
3961  // standard handling of scans
3963 
3964  }
3965  else if (config_.cloud_output_mode == 2)
3966  {
3967  // Following cases are interesting:
3968  // LMS5xx: seq is always 0 -> publish every scan
3969  // MRS1104: Every 4th-Layer is 0 -> publish pointcloud every 4th layer message
3970  // LMS1104: Publish every layer. The timing for the LMS1104 seems to be:
3971  // Every 67 ms receiving of a new scan message
3972  // Scan message contains 367 measurements
3973  // angle increment is 0.75° (yields 274,5° covery -> OK)
3974  // MRS6124: Publish very 24th layer at the layer = 237 , MRS6124 contains no sequence with seq 0
3975  //BBB
3976 #ifndef _MSC_VER
3977  int numTotalShots = 360; //TODO where is this from ?
3978  int numPartialShots = 40; //
3979 
3980  for (int i = 0; i < numTotalShots; i += numPartialShots)
3981  {
3982  sensor_msgs::PointCloud2 partialCloud;
3983  partialCloud = cloud_;
3984  ros::Time partialTimeStamp = cloud_.header.stamp;
3985 
3986  partialTimeStamp += ros::Duration((i + 0.5 * (numPartialShots - 1)) * timeIncrement);
3987  partialTimeStamp += ros::Duration((3 * numTotalShots) * timeIncrement);
3988  partialCloud.header.stamp = partialTimeStamp;
3989  partialCloud.width = numPartialShots * 3; // die sind sicher in diesem Bereich
3990 
3991  int diffTo1100 = cloud_.width - 3 * (numTotalShots + i);
3992  if (diffTo1100 > numPartialShots)
3993  {
3994  diffTo1100 = numPartialShots;
3995  }
3996  if (diffTo1100 < 0)
3997  {
3998  diffTo1100 = 0;
3999  }
4000  partialCloud.width += diffTo1100;
4001  // printf("Offset: %4d Breite: %4d\n", i, partialCloud.width);
4002  partialCloud.height = 1;
4003 
4004 
4005  partialCloud.is_bigendian = false;
4006  partialCloud.is_dense = true;
4007  partialCloud.point_step = numChannels * sizeof(float);
4008  partialCloud.row_step = partialCloud.point_step * partialCloud.width;
4009  partialCloud.fields.resize(numChannels);
4010  for (int ii = 0; ii < numChannels; ii++)
4011  {
4012  std::string channelId[] = {"x", "y", "z", "intensity"};
4013  partialCloud.fields[ii].name = channelId[ii];
4014  partialCloud.fields[ii].offset = ii * sizeof(float);
4015  partialCloud.fields[ii].count = 1;
4016  partialCloud.fields[ii].datatype = sensor_msgs::PointField::FLOAT32;
4017  }
4018 
4019  partialCloud.data.resize(partialCloud.row_step);
4020 
4021  int partOff = 0;
4022  for (int j = 0; j < 4; j++)
4023  {
4024  int layerIdx = (j + (layerCnt)) % 4; // j = 0 -> oldest
4025  int rowIdx = 1 + layerSeq[layerIdx % 4]; // +1, da es bei -1 beginnt
4026  int colIdx = j * numTotalShots + i;
4027  int maxAvail = cloud_.width - colIdx; //
4028  if (maxAvail < 0)
4029  {
4030  maxAvail = 0;
4031  }
4032 
4033  if (maxAvail > numPartialShots)
4034  {
4035  maxAvail = numPartialShots;
4036  }
4037 
4038  // printf("Most recent LayerIdx: %2d RowIdx: %4d ColIdx: %4d\n", layer, rowIdx, colIdx);
4039  if (maxAvail > 0)
4040  {
4041  memcpy(&(partialCloud.data[partOff]),
4042  &(cloud_.data[(rowIdx * cloud_.width + colIdx + i) * cloud_.point_step]),
4043  cloud_.point_step * maxAvail);
4044 
4045  }
4046 
4047  partOff += maxAvail * partialCloud.point_step;
4048  }
4049  assert(partialCloud.data.size() == partialCloud.width * partialCloud.point_step);
4050 
4051 
4052  cloud_pub_.publish(partialCloud);
4053 #if 0
4054  memcpy(&(partialCloud.data[0]), &(cloud_.data[0]) + i * cloud_.point_step, cloud_.point_step * numPartialShots);
4055  cloud_pub_.publish(partialCloud);
4056 #endif
4057  }
4058  }
4059  // cloud_pub_.publish(cloud_);
4060 
4061 #else
4062  printf("PUBLISH:\n");
4063 #endif
4064  }
4065  }
4066  }
4067  // Start Point
4068  if (dend != NULL)
4069  {
4070  buffer_pos = dend + 1;
4071  }
4072  } // end of while loop
4073  }
4074 
4075  // shall we process more data? I.e. are there more packets to process in the input queue???
4076 
4077  } while ((packetsInLoop > 0) && (numPacketsProcessed < maxNumAllowedPacketsToProcess));
4078  return ExitSuccess; // return success to continue looping
4079  }
4080 
4081 
4085  void SickScanCommon::check_angle_range(SickScanConfig &conf)
4086  {
4087  if (conf.min_ang > conf.max_ang)
4088  {
4089  ROS_WARN("Maximum angle must be greater than minimum angle. Adjusting >min_ang<.");
4090  conf.min_ang = conf.max_ang;
4091  }
4092  }
4093 
4099  void SickScanCommon::update_config(sick_scan::SickScanConfig &new_config, uint32_t level)
4100  {
4101  check_angle_range(new_config);
4102  config_ = new_config;
4103  }
4104 
4111  int SickScanCommon::convertAscii2BinaryCmd(const char *requestAscii, std::vector<unsigned char> *requestBinary)
4112  {
4113  requestBinary->clear();
4114  if (requestAscii == NULL)
4115  {
4116  return (-1);
4117  }
4118  int cmdLen = strlen(requestAscii);
4119  if (cmdLen == 0)
4120  {
4121  return (-1);
4122  }
4123  if (requestAscii[0] != 0x02)
4124  {
4125  return (-1);
4126  }
4127  if (requestAscii[cmdLen - 1] != 0x03)
4128  {
4129  return (-1);
4130  }
4131  // Here we know, that the ascii format is correctly framed with <stx> .. <etx>
4132  for (int i = 0; i < 4; i++)
4133  {
4134  requestBinary->push_back(0x02);
4135  }
4136 
4137  for (int i = 0; i < 4; i++) // Puffer for Length identifier
4138  {
4139  requestBinary->push_back(0x00);
4140  }
4141 
4142  unsigned long msgLen = cmdLen - 2; // without stx and etx
4143 
4144  // special handling for the following commands
4145  // due to higher number of command arguments
4146  std::string keyWord0 = "sMN SetAccessMode";
4147  std::string keyWord1 = "sWN FREchoFilter";
4148  std::string keyWord2 = "sEN LMDscandata";
4149  std::string keyWord3 = "sWN LMDscandatacfg";
4150  std::string keyWord4 = "sWN SetActiveApplications";
4151  std::string keyWord5 = "sEN IMUData";
4152  std::string keyWord6 = "sWN EIIpAddr";
4153  std::string keyWord7 = "sMN mLMPsetscancfg";
4154  std::string keyWord8 = "sWN TSCTCupdatetime";
4155  std::string keyWord9 = "sWN TSCTCSrvAddr";
4156  std::string keyWord10 = "sWN LICencres";
4157  std::string keyWord11 = "sWN LFPmeanfilter";
4158  std::string KeyWord12 = "sRN field";
4159 
4160  //BBB
4161 
4162  std::string cmdAscii = requestAscii;
4163 
4164 
4165  int copyUntilSpaceCnt = 2;
4166  int spaceCnt = 0;
4167  char hexStr[255] = {0};
4168  int level = 0;
4169  unsigned char buffer[255];
4170  int bufferLen = 0;
4171  if (cmdAscii.find(keyWord0) != std::string::npos) // SetAccessMode
4172  {
4173  copyUntilSpaceCnt = 2;
4174  int keyWord0Len = keyWord0.length();
4175  sscanf(requestAscii + keyWord0Len + 1, " %d %s", &level, hexStr);
4176  buffer[0] = (unsigned char) (0xFF & level);
4177  bufferLen = 1;
4178  char hexTmp[3] = {0};
4179  for (int i = 0; i < 4; i++)
4180  {
4181  int val;
4182  hexTmp[0] = hexStr[i * 2];
4183  hexTmp[1] = hexStr[i * 2 + 1];
4184  hexTmp[2] = 0x00;
4185  sscanf(hexTmp, "%x", &val);
4186  buffer[i + 1] = (unsigned char) (0xFF & val);
4187  bufferLen++;
4188  }
4189  }
4190  if (cmdAscii.find(keyWord1) != std::string::npos)
4191  {
4192  int echoCodeNumber = 0;
4193  int keyWord1Len = keyWord1.length();
4194  sscanf(requestAscii + keyWord1Len + 1, " %d", &echoCodeNumber);
4195  buffer[0] = (unsigned char) (0xFF & echoCodeNumber);
4196  bufferLen = 1;
4197  }
4198  if (cmdAscii.find(keyWord2) != std::string::npos)
4199  {
4200  int scanDataStatus = 0;
4201  int keyWord2Len = keyWord2.length();
4202  sscanf(requestAscii + keyWord2Len + 1, " %d", &scanDataStatus);
4203  buffer[0] = (unsigned char) (0xFF & scanDataStatus);
4204  bufferLen = 1;
4205  }
4206 
4207  if (cmdAscii.find(keyWord3) != std::string::npos)
4208  {
4209  int scanDataStatus = 0;
4210  int keyWord3Len = keyWord3.length();
4211  int dummyArr[12] = {0};
4212  //sWN LMDscandatacfg %02d 00 %d %d 0 0 %02d 0 0 0 1 1\x03"
4213  int sscanfresult = sscanf(requestAscii + keyWord3Len + 1, " %d %d %d %d %d %d %d %d %d %d %d %d",
4214  &dummyArr[0], // Data Channel Idx LSB
4215  &dummyArr[1], // Data Channel Idx MSB
4216  &dummyArr[2], // Remission
4217  &dummyArr[3], // Remission data format
4218  &dummyArr[4], // Unit
4219  &dummyArr[5], // Encoder Setting LSB
4220  &dummyArr[6], // Encoder Setting MSB
4221  &dummyArr[7], // Position
4222  &dummyArr[8], // Send Name
4223  &dummyArr[9], // Send Comment
4224  &dummyArr[10], // Time information
4225  &dummyArr[11]); // n-th Scan (packed - not sent as single byte sequence) !!!
4226  if (1 < sscanfresult)
4227  {
4228 
4229  for (int i = 0; i < 13; i++)
4230  {
4231  buffer[i] = 0x00;
4232  }
4233  buffer[0] = (unsigned char) (0xFF & dummyArr[0]); //Data Channel 2 Bytes
4234  buffer[1] = (unsigned char) (0xFF & dummyArr[1]);; // MSB of Data Channel (here Little Endian!!)
4235  buffer[2] = (unsigned char) (0xFF & dummyArr[2]); // Remission
4236  buffer[3] = (unsigned char) (0xFF & dummyArr[3]); // Remission data format 0=8 bit 1= 16 bit
4237  buffer[4] = (unsigned char) (0xFF & dummyArr[4]); //Unit of remission data
4238  buffer[5] = (unsigned char) (0xFF & dummyArr[5]); //encoder Data LSB
4239  buffer[6] = (unsigned char) (0xFF & dummyArr[6]); //encoder Data MSB
4240  buffer[7] = (unsigned char) (0xFF & dummyArr[7]); // Position
4241  buffer[8] = (unsigned char) (0xFF & dummyArr[8]); // Send Scanner Name
4242  buffer[9] = (unsigned char) (0xFF & dummyArr[9]); // Comment
4243  buffer[10] = (unsigned char) (0xFF & dummyArr[10]); // Time information
4244  buffer[11] = (unsigned char) (0xFF & (dummyArr[11] >> 8)); // BIG Endian High Byte nth-Scan
4245  buffer[12] = (unsigned char) (0xFF & (dummyArr[11] >> 0)); // BIG Endian Low Byte nth-Scan
4246  bufferLen = 13;
4247 
4248  }
4249 
4250  }
4251 
4252  if (cmdAscii.find(keyWord4) != std::string::npos)
4253  {
4254  char tmpStr[1024] = {0};
4255  char szApplStr[255] = {0};
4256  int keyWord4Len = keyWord4.length();
4257  int scanDataStatus = 0;
4258  int dummy0, dummy1;
4259  strcpy(tmpStr, requestAscii + keyWord4Len + 2);
4260  sscanf(tmpStr, "%d %s %d", &dummy0, szApplStr, &dummy1);
4261  // rebuild string
4262  buffer[0] = 0x00;
4263  buffer[1] = dummy0 ? 0x01 : 0x00;
4264  for (int ii = 0; ii < 4; ii++)
4265  {
4266  buffer[2 + ii] = szApplStr[ii]; // idx: 1,2,3,4
4267  }
4268  buffer[6] = dummy1 ? 0x01 : 0x00;
4269  bufferLen = 7;
4270  }
4271 
4272  if (cmdAscii.find(keyWord5) != std::string::npos)
4273  {
4274  int imuSetStatus = 0;
4275  int keyWord5Len = keyWord5.length();
4276  sscanf(requestAscii + keyWord5Len + 1, " %d", &imuSetStatus);
4277  buffer[0] = (unsigned char) (0xFF & imuSetStatus);
4278  bufferLen = 1;
4279  }
4280 
4281  if (cmdAscii.find(keyWord6) != std::string::npos)
4282  {
4283  int adrPartArr[4];
4284  int imuSetStatus = 0;
4285  int keyWord6Len = keyWord6.length();
4286  sscanf(requestAscii + keyWord6Len + 1, " %x %x %x %x", &(adrPartArr[0]), &(adrPartArr[1]), &(adrPartArr[2]),
4287  &(adrPartArr[3]));
4288  buffer[0] = (unsigned char) (0xFF & adrPartArr[0]);
4289  buffer[1] = (unsigned char) (0xFF & adrPartArr[1]);
4290  buffer[2] = (unsigned char) (0xFF & adrPartArr[2]);
4291  buffer[3] = (unsigned char) (0xFF & adrPartArr[3]);
4292  bufferLen = 4;
4293  }
4294  //\x02sMN mLMPsetscancfg %d 1 %d 0 0\x03";
4295  //02 02 02 02 00 00 00 25 73 4D 4E 20 6D 4C 4D 50 73 65 74 73 63 61 6E 63 66 67 20
4296  // 00 00 13 88 4byte freq
4297  // 00 01 2 byte sectors always 1
4298  // 00 00 13 88 ang_res
4299  // FF F9 22 30 sector start always 0
4300  // 00 22 55 10 sector stop always 0
4301  // 21
4302  if (cmdAscii.find(keyWord7) != std::string::npos)
4303  {
4305  {
4306  {
4307  bufferLen = 18;
4308  for (int i = 0; i < bufferLen; i++)
4309  {
4310  unsigned char uch = 0x00;
4311  switch (i)
4312  {
4313  case 5:
4314  uch = 0x01;
4315  break;
4316  }
4317  buffer[i] = uch;
4318  }
4319  char tmpStr[1024] = {0};
4320  char szApplStr[255] = {0};
4321  int keyWord7Len = keyWord7.length();
4322  int scanDataStatus = 0;
4323  int dummy0, dummy1;
4324  strcpy(tmpStr, requestAscii + keyWord7Len + 2);
4325  sscanf(tmpStr, "%d 1 %d", &dummy0, &dummy1);
4326 
4327  buffer[0] = (unsigned char) (0xFF & (dummy0 >> 24));
4328  buffer[1] = (unsigned char) (0xFF & (dummy0 >> 16));
4329  buffer[2] = (unsigned char) (0xFF & (dummy0 >> 8));
4330  buffer[3] = (unsigned char) (0xFF & (dummy0 >> 0));
4331 
4332 
4333  buffer[6] = (unsigned char) (0xFF & (dummy1 >> 24));
4334  buffer[7] = (unsigned char) (0xFF & (dummy1 >> 16));
4335  buffer[8] = (unsigned char) (0xFF & (dummy1 >> 8));
4336  buffer[9] = (unsigned char) (0xFF & (dummy1 >> 0));
4337  }
4338  }
4339  else
4340  {
4341  int keyWord7Len = keyWord7.length();
4342  int dummyArr[14] = {0};
4343  if (14 == sscanf(requestAscii + keyWord7Len + 1, " %d %d %d %d %d %d %d %d %d %d %d %d %d %d",
4344  &dummyArr[0], &dummyArr[1], &dummyArr[2],
4345  &dummyArr[3], &dummyArr[4], &dummyArr[5],
4346  &dummyArr[6], &dummyArr[7], &dummyArr[8],
4347  &dummyArr[9], &dummyArr[10], &dummyArr[11], &dummyArr[12], &dummyArr[13]))
4348  {
4349  for (int i = 0; i < 54; i++)
4350  {
4351  buffer[i] = 0x00;
4352  }
4353  int targetPosArr[] = {0, 4, 6, 10, 14, 18, 22, 26, 30, 34, 38, 42, 46, 50, 54};
4354  int numElem = (sizeof(targetPosArr) / sizeof(targetPosArr[0])) - 1;
4355  for (int i = 0; i < numElem; i++)
4356  {
4357  int lenOfBytesToRead = targetPosArr[i + 1] - targetPosArr[i];
4358  int adrPos = targetPosArr[i];
4359  unsigned char *destPtr = buffer + adrPos;
4360  memcpy(destPtr, &(dummyArr[i]), lenOfBytesToRead);
4361  swap_endian(destPtr, lenOfBytesToRead);
4362  }
4363  bufferLen = targetPosArr[numElem];
4364  /*
4365  * 00 00 03 20 00 01
4366  00 00 09 C4 00 00 00 00 00 36 EE 80 00 00 09 C4 00 00 00 00 00 00 00 00 00 00 09 C4 00 00 00 00 00
4367  00 00 00 00 00 09 C4 00 00 00 00 00 00 00 00 00 00 09 C4 00 00 00 00 00 00 00 00 E4
4368  */
4369 
4370  }
4371  }
4372 
4373  }
4374  if (cmdAscii.find(keyWord8) != std::string::npos)
4375  {
4376  uint32_t updatetime = 0;
4377  int keyWord8Len = keyWord8.length();
4378  sscanf(requestAscii + keyWord8Len + 1, " %d", &updatetime);
4379  buffer[0] = (unsigned char) (0xFF & (updatetime >> 24));
4380  buffer[1] = (unsigned char) (0xFF & (updatetime >> 16));
4381  buffer[2] = (unsigned char) (0xFF & (updatetime >> 8));
4382  buffer[3] = (unsigned char) (0xFF & (updatetime >> 0));
4383  bufferLen = 4;
4384  }
4385  if (cmdAscii.find(keyWord9) != std::string::npos)
4386  {
4387  int adrPartArr[4];
4388  int imuSetStatus = 0;
4389  int keyWord9Len = keyWord9.length();
4390  sscanf(requestAscii + keyWord9Len + 1, " %x %x %x %x", &(adrPartArr[0]), &(adrPartArr[1]), &(adrPartArr[2]),
4391  &(adrPartArr[3]));
4392  buffer[0] = (unsigned char) (0xFF & adrPartArr[0]);
4393  buffer[1] = (unsigned char) (0xFF & adrPartArr[1]);
4394  buffer[2] = (unsigned char) (0xFF & adrPartArr[2]);
4395  buffer[3] = (unsigned char) (0xFF & adrPartArr[3]);
4396  bufferLen = 4;
4397  }
4398  if (cmdAscii.find(keyWord10) != std::string::npos)
4399  {
4400  float EncResolution = 0;
4401  bufferLen = 4;
4402  int keyWord10Len = keyWord10.length();
4403  sscanf(requestAscii + keyWord10Len + 1, " %f", &EncResolution);
4404  memcpy(buffer, &EncResolution, bufferLen);
4405  swap_endian(buffer, bufferLen);
4406 
4407  }
4408  if (cmdAscii.find(keyWord11) != std::string::npos)
4409  {
4410  char tmpStr[1024] = {0};
4411  char szApplStr[255] = {0};
4412  int keyWord11Len = keyWord11.length();
4413  int dummy0, dummy1,dummy2;
4414  strcpy(tmpStr, requestAscii + keyWord11Len + 2);
4415  sscanf(tmpStr, "%d %d %d", &dummy0, &dummy1, &dummy2);
4416  // rebuild string
4417  buffer[0] = dummy0 ? 0x01 : 0x00;
4418  buffer[1] =dummy1/256;//
4419  buffer[2] =dummy1%256;//
4420  buffer[3] =dummy2;
4421  bufferLen = 4;
4422  }
4423  if (cmdAscii.find(KeyWord12) != std::string::npos)
4424  {
4425  uint32_t fieldID = 0;
4426  int keyWord12Len = KeyWord12.length();
4427  sscanf(requestAscii + keyWord12Len + 1, "%d", &fieldID);
4428  bufferLen = 0;
4429  }
4430  // copy base command string to buffer
4431  bool switchDoBinaryData = false;
4432  for (int i = 1; i <= (int) (msgLen); i++) // STX DATA ETX --> 0 1 2
4433  {
4434  char c = requestAscii[i];
4435  if (switchDoBinaryData == true)
4436  {
4437  if (0 == bufferLen) // no keyword handling before this point
4438  {
4439  if (c >= '0' && c <= '9') // standard data format expected - only one digit
4440  {
4441  c -= '0'; // convert ASCII-digit to hex-digit
4442  } // 48dez to 00dez and so on.
4443  }
4444  else
4445  {
4446  break;
4447  }
4448  }
4449  requestBinary->push_back(c);
4450  if (requestAscii[i] == 0x20) // space
4451  {
4452  spaceCnt++;
4453  if (spaceCnt >= copyUntilSpaceCnt)
4454  {
4455  switchDoBinaryData = true;
4456  }
4457  }
4458 
4459  }
4460  // if there are already process bytes (due to special key word handling)
4461  // copy these data bytes to the buffer
4462  for (int i = 0; i < bufferLen; i++) // append variable data
4463  {
4464  requestBinary->push_back(buffer[i]);
4465  }
4466 
4467  msgLen = requestBinary->size();
4468  msgLen -= 8;
4469  for (int i = 0; i < 4; i++)
4470  {
4471  unsigned char bigEndianLen = msgLen & (0xFF << (3 - i) * 8);
4472  (*requestBinary)[i + 4] = ((unsigned char) (bigEndianLen)); // HIER WEITERMACHEN!!!!
4473  }
4474  unsigned char xorVal = 0x00;
4475  xorVal = sick_crc8((unsigned char *) (&((*requestBinary)[8])), requestBinary->size() - 8);
4476  requestBinary->push_back(xorVal);
4477 #if 0
4478  for (int i = 0; i < requestBinary->size(); i++)
4479  {
4480  unsigned char c = (*requestBinary)[i];
4481  printf("[%c]%02x ", (c < ' ') ? '.' : c, c) ;
4482  }
4483  printf("\n");
4484 #endif
4485  return (0);
4486 
4487  };
4488 
4489 
4497  {
4498  bool retValue = true;
4499  bool shouldUseBinary = this->parser_->getCurrentParamPtr()->getUseBinaryProtocol();
4500  if (shouldUseBinary == useBinaryCmdNow)
4501  {
4502  retValue = true; // !!!! CHANGE ONLY FOR TEST!!!!!
4503  }
4504  else
4505  {
4506  /*
4507  // we must reconnect and set the new protocoltype
4508  int iRet = this->close_device();
4509  ROS_INFO("SOPAS - Close and reconnected to scanner due to protocol change and wait 15 sec. ");
4510  ROS_INFO("SOPAS - Changing from %s to %s\n", shouldUseBinary ? "ASCII" : "BINARY", shouldUseBinary ? "BINARY" : "ASCII");
4511  // Wait a few seconds after rebooting
4512  ros::Duration(15.0).sleep();
4513 
4514  iRet = this->init_device();
4515  */
4516  if (shouldUseBinary == true)
4517  {
4518  this->setProtocolType(CoLa_B);
4519  }
4520  else
4521  {
4522  this->setProtocolType(CoLa_A);
4523  }
4524 
4525  useBinaryCmdNow = shouldUseBinary;
4526  retValue = false;
4527  }
4528  return (retValue);
4529  }
4530 
4531 
4532  bool SickScanCommon::setNewIpAddress(boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
4533  {
4534  int eepwritetTimeOut = 1;
4535  bool result = false;
4536 
4537 
4538  unsigned long adrBytesLong[4];
4539  std::string s = ipNewIPAddr.to_string(); // convert to string, to_bytes not applicable for older linux version
4540  const char *ptr = s.c_str(); // char * to address
4541  // decompose pattern like aaa.bbb.ccc.ddd
4542  sscanf(ptr, "%lu.%lu.%lu.%lu", &(adrBytesLong[0]), &(adrBytesLong[1]), &(adrBytesLong[2]), &(adrBytesLong[3]));
4543 
4544  // convert into byte array
4545  unsigned char ipbytearray[4];
4546  for (int i = 0; i < 4; i++)
4547  {
4548  ipbytearray[i] = adrBytesLong[i] & 0xFF;
4549  }
4550 
4551 
4552  char ipcommand[255];
4553  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_IP_ADDR].c_str();
4554  sprintf(ipcommand, pcCmdMask, ipbytearray[0], ipbytearray[1], ipbytearray[2], ipbytearray[3]);
4555  if (useBinaryCmd)
4556  {
4557  std::vector<unsigned char> reqBinary;
4558  this->convertAscii2BinaryCmd(ipcommand, &reqBinary);
4559  result = (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_SET_IP_ADDR]));
4560  reqBinary.clear();
4561  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_WRITE_EEPROM].c_str(), &reqBinary);
4562  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_WRITE_EEPROM]));
4563  reqBinary.clear();
4564  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_RUN].c_str(), &reqBinary);
4565  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_RUN]));
4566  reqBinary.clear();
4567  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_SET_ACCESS_MODE_3].c_str(), &reqBinary);
4568  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_SET_ACCESS_MODE_3]));
4569  reqBinary.clear();
4570  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_REBOOT].c_str(), &reqBinary);
4571  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_REBOOT]));
4572  }
4573  else
4574  {
4575  std::vector<unsigned char> ipcomandReply;
4576  std::vector<unsigned char> resetReply;
4577  std::string runCmd = sopasCmdVec[CMD_RUN];
4578  std::string restartCmd = sopasCmdVec[CMD_REBOOT];
4579  std::string EEPCmd = sopasCmdVec[CMD_WRITE_EEPROM];
4580  std::string UserLvlCmd = sopasCmdVec[CMD_SET_ACCESS_MODE_3];
4581  result = (0 == sendSopasAndCheckAnswer(ipcommand, &ipcomandReply));
4582  result &= (0 == sendSopasAndCheckAnswer(EEPCmd, &resetReply));
4583  result &= (0 == sendSopasAndCheckAnswer(runCmd, &resetReply));
4584  result &= (0 == sendSopasAndCheckAnswer(UserLvlCmd, &resetReply));
4585  result &= (0 == sendSopasAndCheckAnswer(restartCmd, &resetReply));
4586  }
4587  return (result);
4588  }
4589 
4590  bool SickScanCommon::setNTPServerAndStart(boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
4591  {
4592  bool result = false;
4593 
4594 
4595  unsigned long adrBytesLong[4];
4596  std::string s = ipNewIPAddr.to_string(); // convert to string, to_bytes not applicable for older linux version
4597  const char *ptr = s.c_str(); // char * to address
4598  // decompose pattern like aaa.bbb.ccc.ddd
4599  sscanf(ptr, "%lu.%lu.%lu.%lu", &(adrBytesLong[0]), &(adrBytesLong[1]), &(adrBytesLong[2]), &(adrBytesLong[3]));
4600 
4601  // convert into byte array
4602  unsigned char ipbytearray[4];
4603  for (int i = 0; i < 4; i++)
4604  {
4605  ipbytearray[i] = adrBytesLong[i] & 0xFF;
4606  }
4607 
4608 
4609  char ntpipcommand[255];
4610  char ntpupdatetimecommand[255];
4611  const char *pcCmdMask = sopasCmdMaskVec[CMD_SET_NTP_SERVER_IP_ADDR].c_str();
4612  sprintf(ntpipcommand, pcCmdMask, ipbytearray[0], ipbytearray[1], ipbytearray[2], ipbytearray[3]);
4613 
4614  const char *pcCmdMaskUpdatetime = sopasCmdMaskVec[CMD_SET_NTP_UPDATETIME].c_str();
4615  sprintf(ntpupdatetimecommand, pcCmdMaskUpdatetime, 5);
4616  std::vector<unsigned char> outputFilterntpupdatetimecommand;
4617  //
4618  if (useBinaryCmd)
4619  {
4620  std::vector<unsigned char> reqBinary;
4621  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_SET_NTP_INTERFACE_ETH].c_str(), &reqBinary);
4623  reqBinary.clear();
4624  this->convertAscii2BinaryCmd(ntpipcommand, &reqBinary);
4626  reqBinary.clear();
4627  this->convertAscii2BinaryCmd(ntpupdatetimecommand, &reqBinary);
4628  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_SET_NTP_UPDATETIME]));
4629  reqBinary.clear();
4630  this->convertAscii2BinaryCmd(sopasCmdVec[CMD_ACTIVATE_NTP_CLIENT].c_str(), &reqBinary);
4631  result &= (0 == sendSopasAndCheckAnswer(reqBinary, &sopasReplyBinVec[CMD_ACTIVATE_NTP_CLIENT]));
4632  reqBinary.clear();
4633 
4634  }
4635  else
4636  {
4637  std::vector<unsigned char> ipcomandReply;
4638  std::vector<unsigned char> resetReply;
4639  std::string ntpInterFaceETHCmd = sopasCmdVec[CMD_SET_NTP_INTERFACE_ETH];
4640  std::string activateNTPCmd = sopasCmdVec[CMD_ACTIVATE_NTP_CLIENT];
4641  result &= (0 == sendSopasAndCheckAnswer(ntpInterFaceETHCmd, &resetReply));
4642  result &= (0 == sendSopasAndCheckAnswer(ntpipcommand, &ipcomandReply));
4643  result &= (0 == sendSopasAndCheckAnswer(activateNTPCmd, &resetReply));
4644  result &= (0 == sendSopasAndCheckAnswer(ntpupdatetimecommand, &outputFilterntpupdatetimecommand));
4645  }
4646  return (result);
4647  }
4648 
4650  {
4651  sensorIsRadar = _isRadar;
4652  }
4653 
4655  {
4656  return (sensorIsRadar);
4657  }
4658 
4659  // SopasProtocol m_protocolId;
4660 
4661 } /* namespace sick_scan */
4662 
4663 
4664 
const std::vector< SickScanMonField > & getMonFields(void) const
msg
void setReadTimeOutInMs(int timeOutInMs)
set timeout in milliseconds
std::vector< std::string > sopasCmdErrMsg
void check_angle_range(SickScanConfig &conf)
check angle setting in the config and adjust the min_ang to the max_ang if min_ang greater than max_a...
int loopOnce()
parsing datagram and publishing ros messages
bool isImuDatagram(char *datagram, size_t datagram_length)
virtual int init_scanner()
initialize scanner
std::vector< std::string > sopasCmdMaskVec
int binScanfGuessDataLenFromMask(const char *scanfMask)
Definition: binScanf.cpp:438
#define ROS_FATAL(...)
#define PARAM_MIN_ANG
std::vector< std::string > sopasReplyStrVec
static std::string binDataToAsciiString(const uint8_t *binary_data, int length)
Definition: dataDumper.cpp:108
void publish(const boost::shared_ptr< M > &message) const
std::vector< std::string > sopasCmdVec
void updateMarker(const std::vector< SickScanMonField > &fields, int fieldset, int eval_field_logic)
double getElevationDegreeResolution(void)
get angular resolution in VERTICAL direction for multilayer scanner
uint16_t UINT16
int getReadTimeOutInMs()
get timeout in milliseconds
f
void update_config(sick_scan::SickScanConfig &new_config, uint32_t level=0)
updating configuration
bool getUseSafetyPasWD()
flag to mark the device uses the safety scanner password Bool true for safety password false for nor...
std::vector< unsigned char > stringToVector(std::string s)
Universal swapping function.
const std::string binScanfGetStringFromVec(std::vector< unsigned char > *replyDummy, int off, long len)
Convert part of unsigned char vector into a std::string.
void setHardwareID(const std::string &hwid)
std::string stripControl(std::vector< unsigned char > s)
Converts a SOPAS command to a human readable string.
static SoftwarePLL & instance()
Definition: softwarePLL.h:23
bool isImuAckDatagram(char *datagram, size_t datagram_length)
bool sleep() const
double getExpectedFrequency(void)
get expected scan frequency
ros::Publisher lidoutputstate_pub_
bool dumpDatagramForDebugging(unsigned char *buffer, int bufLen)
static bool parseLIDoutputstateMsg(const ros::Time &timeStamp, uint8_t *receiveBuffer, int receiveLength, bool useBinaryProtocol, const std::string &frame_id, sick_scan::LIDoutputstateMsg &output_msg)
SickScanCommon(SickGenericParser *parser)
Construction of SickScanCommon.
float get_range_min(void)
Getting minimum range.
data
int convertAscii2BinaryCmd(const char *requestAscii, std::vector< unsigned char > *requestBinary)
Convert ASCII-message to Binary-message.
virtual int init_device()=0
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
void swap_endian(unsigned char *ptr, int numBytes)
Universal swapping function.
std::string getHumanReadableFormula(void)
#define ROS_WARN(...)
int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
#define deg2rad_const
int binScanfVec(const std::vector< unsigned char > *vec, const char *fmt,...)
Definition: binScanf.cpp:417
Command Language ASCI.
bool setNewIpAddress(boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
#define rad2deg(x)
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
dynamic_reconfigure::Server< sick_scan::SickScanConfig > dynamic_reconfigure_server_
int packeds_droped
Definition: softwarePLL.h:83
bool getCorrectedTimeStamp(uint32_t &sec, uint32_t &nanoSec, uint32_t tick)
diagnostic_updater::Updater diagnostics_
std::vector< std::string > sopasReplyVec
double compensateAngleInRadFromRos(double angleInRadFromRos)
Compensate raw angle given in [RAD] in the ROS axis orientation system.
bool checkForProtocolChangeAndMaybeReconnect(bool &useBinaryCmdNow)
checks the current protocol type and gives information about necessary change
virtual bool rebootScanner()
Send a SOPAS command to the scanner that should cause a soft reset.
int getNumberOfLayers(void)
Getting number of scanner layers.
int getProtocolType(void)
get protocol type as enum
void setEncoderMode(int8_t _EncoderMode)
Prama for encoder mode.
int getNumberOfMaximumEchos(void)
Get number of maximum echoes for this laser scanner type.
static SickScanFieldMonSingleton * getInstance()
void setProtocolType(SopasProtocol cola_dialect_id)
set protocol type as enum
#define ROS_INFO(...)
bool param(const std::string &param_name, T &param_val, const T &default_val) const
std::vector< int > sopasCmdChain
void addFrameToBuffer(UINT8 *sendBuffer, UINT8 *cmdBuffer, UINT16 *len)
Definition: colab.cpp:99
std::string replyToString(const std::vector< unsigned char > &reply)
Converts reply from sendSOPASCommand to string.
virtual int parse_datagram(char *datagram, size_t datagram_length, SickScanConfig &config, sensor_msgs::LaserScan &msg, int &numEchos, int &echoMask)
Parsing Ascii datagram.
static int getDiagnosticErrorCode()
return diagnostic error code (small helper function) This small helper function was introduced to all...
void checkScanTiming(float time_increment, float scan_time, float angle_increment, float tol)
bool setNTPServerAndStart(boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
float get_range_max(void)
Getting maximum range.
int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
Command Language binary.
bool getUseBinaryProtocol(void)
flag to decide between usage of ASCII-sopas or BINARY-sopas
std::string generateExpectedAnswerString(const std::vector< unsigned char > requestStr)
Generate expected answer string from the command string.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
int parseAsciiDatagram(std::vector< unsigned char > datagramm)
Parsing Ascii datagram.
static SickScanRadarSingleton * getInstance()
#define PARAM_MAX_ANG
#define ROS_WARN_STREAM(args)
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
#define ROS_DEBUG_STREAM(args)
static DataDumper & instance()
Definition: dataDumper.h:13
#define SICK_SCANNER_TIM_240_NAME
SickGenericParser * parser_
double getAngularDegreeResolution(void)
Get angular resolution in degress.
std::string getScannerName(void)
Getting name (type) of scanner.
int8_t getEncoderMode()
Getter-Method for encoder mode.
int checkForBinaryAnswer(const std::vector< unsigned char > *reply)
Check block for correct framing and starting sequence of a binary message.
void setSensorIsRadar(bool _isRadar)
#define SICK_SCANNER_NAV_3XX_NAME
virtual ~SickScanCommon()
Destructor of SickScanCommon.
SickScanMarker * cloud_marker_
#define SICK_SCANNER_MRS_1XXX_NAME
#define ROS_INFO_STREAM(args)
int sendSopasAndCheckAnswer(std::string request, std::vector< unsigned char > *reply, int cmdId)
send command and check answer
unsigned long convertBigEndianCharArrayToUnsignedLong(const unsigned char *vecArr)
Convert little endian to big endian (should be replaced by swap-routine)
virtual int init()
init routine of scanner
#define PARAM_RES_ANG
void setIntensityResolutionIs16Bit(bool _IntensityResolutionIs16Bit)
Set the RSSI Value length.
bool getParam(const std::string &key, std::string &s) const
unsigned char sick_crc8(unsigned char *msgBlock, int len)
calculate crc-code for last byte of binary message XOR-calucation is done ONLY over message content (...
static bool parseLFErecMsg(const ros::Time &timeStamp, uint8_t *receiveBuffer, int receiveLength, bool useBinaryProtocol, EVAL_FIELD_SUPPORT eval_field_logic, const std::string &frame_id, sick_scan::LFErecMsg &output_msg)
static Time now()
virtual int stop_scanner()
Stops sending scan data.
virtual int get_datagram(ros::Time &recvTimeStamp, unsigned char *receiveBuffer, int bufferSize, int *actual_length, bool isBinaryProtocol, int *numberOfRemainingFifoEntries)=0
Read a datagram from the device.
#define SICK_SCANNER_LMS_5XX_NAME
void broadcast(int lvl, const std::string msg)
bool isCompatibleDevice(const std::string identStr) const
check the identification string
#define ROS_ERROR_STREAM(args)
int parseBinaryLIDinputstateMsg(unsigned char *datagram, int datagram_length)
Parse binary LIDinputstate message and set active field set.
#define ROS_ASSERT(cond)
static const int fifoSize
Definition: softwarePLL.h:82
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * diagnosticPub_
SopasProtocol
#define SICK_SCANNER_NAV_2XX_NAME
int parseBinaryDatagram(std::vector< unsigned char > datagramm)
sensor_msgs::PointCloud2 cloud_
int dumpUcharBufferToConsole(unsigned char *buffer, int bufLen)
Definition: dataDumper.cpp:67
#define ROS_ERROR(...)
EVAL_FIELD_SUPPORT getUseEvalFields()
void setParam(const std::string &key, const XmlRpc::XmlRpcValue &v) const
static sick_scan::SickScanCommonTcp * s
std::vector< std::vector< unsigned char > > sopasReplyBinVec
AngleCompensator * angleCompensator
bool updatePLL(uint32_t sec, uint32_t nanoSec, uint32_t curtick)
Updates PLL internale State should be called only with network send timestamps.
int init_cmdTables()
init command tables and define startup sequence
int parseReply(bool isBinary, std::vector< unsigned char > &replyVec)
Parse reply of angle compensation values given the command MCAngleCompSin (see testbed) ...
bool getDeviceIsRadar(void)
flag to mark the device as radar (instead of laser scanner)
virtual int sendSOPASCommand(const char *request, std::vector< unsigned char > *reply, int cmdLen=-1)=0
Send a SOPAS command to the device and print out the response to the console.
#define ROS_DEBUG(...)


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