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 67 #include "sick_scan/rosconsole_simu.hpp" 72 #include <sick_scan/RadarScan.h> 74 #include "sick_scan/Encoder.h" 79 #define _USE_MATH_DEFINES 84 #define rad2deg(x) ((x) / M_PI * 180.0) 87 #define deg2rad_const (0.017453292519943295769236907684886f) 104 unsigned char *buf = (ptr);
105 unsigned char tmpChar;
106 for (
int i = 0; i < numBytes / 2; i++)
108 tmpChar = buf[numBytes - 1 - i];
109 buf[numBytes - 1 - i] = buf[i];
124 std::vector<unsigned char> result;
125 for (
size_t j = 0; j < s.length(); j++)
127 result.push_back(s[j]);
145 return (diagnostic_msgs::DiagnosticStatus::ERROR);
160 for (
int i = 0; i < len; i++)
162 char ch = (char) ((*replyDummy)[i + off]);
177 unsigned char sick_crc8(
unsigned char *msgBlock,
int len)
179 unsigned char xorVal = 0x00;
181 for (
int i = off; i < len; i++)
184 unsigned char val = msgBlock[i];
197 bool isParamBinary =
false;
201 for (
size_t i = 0; i < s.size(); i++)
205 isParamBinary =
false;
219 isParamBinary =
true;
222 if (isParamBinary ==
true)
226 unsigned long lenId = 0x00;
227 char szDummy[255] = {0};
228 for (
size_t i = 0; i < s.size(); i++)
247 lenId |= s[i] << (8 * (7 - i));
250 sprintf(szDummy,
"<Len=%04lu>", lenId);
257 unsigned long dataProcessed = i - 8;
267 if (dataProcessed >= (lenId - 1))
277 char ch = dest[dest.length() - 1];
282 sprintf(szDummy,
"0x%02x", s[i]);
285 unsigned long dataProcessed = i - 8;
286 if (dataProcessed >= (lenId - 1))
294 sprintf(szDummy,
" CRC:<0x%02x>", s[i]);
305 for (
size_t i = 0; i < s.size(); i++)
336 diagnosticPub_(NULL), parser_(parser)
344 dynamic_reconfigure::Server<sick_scan::SickScanConfig>::CallbackType
f;
352 double min_angle, max_angle, res_angle;
356 cfg.min_ang = min_angle;
357 cfg.max_ang = max_angle;
365 if (publish_datagram_)
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);
392 ROS_INFO(
"Publishing laserscan-pointcloud2 to %s", cloud_topic_val.c_str());
428 const char requestScanData0[] = {
"\x02sEN LMDscandata 0\x03\0"};
433 printf(
"\nSOPAS - Error stopping streaming scan data!\n");
437 printf(
"\nSOPAS - Stopped streaming scan data.\n");
447 printf(
"\nSOPAS - Error stopping streaming LFErec, LIDoutputstate and LIDinputstate messages!\n");
451 printf(
"\nSOPAS - Stopped streaming LFErec, LIDoutputstate and LIDinputstate messages\n");
465 unsigned long val = 0;
466 for (
int i = 0; i < 4; i++)
489 if (reply->size() < 8)
495 const unsigned char *ptr = &((*reply)[0]);
498 if (binId == 0x02020202)
500 int replyLen = reply->size();
501 if (replyLen == 8 + cmdLen + 1)
522 std::vector<unsigned char> access_reply;
524 int result =
sendSOPASCommand(
"\x02sMN SetAccessMode 3 F4724744\x03\0", &access_reply);
527 ROS_ERROR(
"SOPAS - Error setting access mode");
532 if (access_reply_str !=
"sAN SetAccessMode 1")
534 ROS_ERROR_STREAM(
"SOPAS - Error setting access mode, unexpected response : " << access_reply_str);
542 std::vector<unsigned char> reboot_reply;
546 ROS_ERROR(
"SOPAS - Error rebooting scanner");
551 if (reboot_reply_str !=
"sAN mSCreboot")
553 ROS_ERROR_STREAM(
"SOPAS - Error rebooting scanner, unexpected response : " << reboot_reply_str);
558 ROS_INFO(
"SOPAS - Rebooted scanner");
574 printf(
"sick_scan driver exiting.\n");
585 std::string expectedAnswer =
"";
587 char cntWhiteCharacter = 0;
588 int initalTokenCnt = 2;
589 std::map<std::string, int> specialTokenLen;
590 char firstToken[1024] = {0};
591 specialTokenLen[
"sRI"] = 1;
592 std::string tmpStr =
"";
594 bool isBinary =
false;
595 for (
size_t i = 0; i < 4; i++)
597 if (i < requestStr.size())
599 if (requestStr[i] == 0x02)
607 int iStop = requestStr.size();
612 for (
int i = 0; i < 4; i++)
614 cmdLen |= cmdLen << 8;
615 cmdLen |= requestStr[i + 4];
621 int iStart = (isBinary ==
true) ? 8 : 0;
622 for (
int i = iStart; i < iStop; i++)
624 tmpStr += (char) requestStr[i];
628 tmpStr =
"\x2" + tmpStr;
630 if (sscanf(tmpStr.c_str(),
"\x2%s", firstToken) == 1)
632 if (specialTokenLen.find(firstToken) != specialTokenLen.end())
634 initalTokenCnt = specialTokenLen[firstToken];
639 for (
int i = iStart; i < iStop; i++)
641 if ((requestStr[i] ==
' ') || (requestStr[i] ==
'\x3'))
645 if (cntWhiteCharacter >= initalTokenCnt)
649 if (requestStr[i] ==
'\x2')
654 expectedAnswer += requestStr[i];
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";
668 for (std::map<std::string, std::string>::iterator it = keyWordMap.begin(); it != keyWordMap.end(); it++)
671 std::string keyWord = it->first;
672 std::string newKeyWord = it->second;
674 size_t pos = expectedAnswer.find(keyWord);
675 if (pos == std::string::npos)
683 expectedAnswer.replace(pos, keyWord.length(), newKeyWord);
687 ROS_WARN(
"Unexpected position of key identifier.\n");
692 return (expectedAnswer);
705 std::vector<unsigned char> requestStringVec;
706 for (
size_t i = 0; i < requestStr.length(); i++)
708 requestStringVec.push_back(requestStr[i]);
726 std::string cmdStr =
"";
728 for (
size_t i = 0; i < requestStr.size(); i++)
731 cmdStr += (char) requestStr[i];
735 std::string errString;
738 errString =
"Error unexpected Sopas Answer for request " +
stripControl(requestStr);
753 std::vector<unsigned char> replyVec;
754 replyStr =
"<STX>" + replyStr +
"<ETX>";
760 std::string tmpStr =
"SOPAS Communication -" + errString;
769 if (answerStr.find(searchPattern) != std::string::npos)
777 ROS_INFO(
"IMU-Data transfer started. No checking of reply to avoid confusing with LMD Scandata\n");
782 std::string tmpMsg =
"Error Sopas answer mismatch " + errString +
"Answer= >>>" + answerStr +
"<<<";
841 ROS_FATAL(
"Failed to init device: %d", result);
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.",
875 std::string unknownStr =
"Command or Error message not defined";
1084 bool isNav2xxOr3xx =
false;
1087 isNav2xxOr3xx =
true;
1091 isNav2xxOr3xx =
true;
1099 bool tryToStopMeasurement =
true;
1102 tryToStopMeasurement =
false;
1110 tryToStopMeasurement =
false;
1113 if (tryToStopMeasurement)
1118 switch (numberOfLayers)
1165 const int MAX_STR_LEN = 1024;
1167 int maxNumberOfEchos = 1;
1173 bool rssiFlag =
false;
1174 bool rssiResolutionIs16Bit =
true;
1175 int activeEchos = 0;
1178 pn.
getParam(
"intensity", rssiFlag);
1179 pn.
getParam(
"intensity_resolution_16bit", rssiResolutionIs16Bit);
1181 std::string sNewIPAddr =
"";
1182 boost::asio::ip::address_v4 ipNewIPAddr;
1183 bool setNewIPAddr =
false;
1184 setNewIPAddr = pn.
getParam(
"new_IP_address", sNewIPAddr);
1187 boost::system::error_code ec;
1188 ipNewIPAddr = boost::asio::ip::address_v4::from_string(sNewIPAddr, ec);
1189 if (ec == boost::system::errc::success)
1196 setNewIPAddr =
false;
1197 ROS_ERROR(
"ERROR: IP ADDRESS could not be parsed Boost Error %s:%d", ec.category().name(), ec.value());;
1201 std::string sNTPIpAdress =
"";
1202 boost::asio::ip::address_v4 NTPIpAdress;
1203 bool setUseNTP =
false;
1204 setUseNTP = pn.
getParam(
"ntp_server_address", sNTPIpAdress);
1207 boost::system::error_code ec;
1208 NTPIpAdress = boost::asio::ip::address_v4::from_string(sNTPIpAdress, ec);
1209 if (ec != boost::system::errc::success)
1212 ROS_ERROR(
"ERROR: NTP Server IP ADDRESS could not be parsed Boost Error %s:%d", ec.category().name(),
1219 pn.
getParam(
"active_echos", activeEchos);
1221 ROS_INFO(
"Parameter setting for <active_echo: %d>", activeEchos);
1222 std::vector<bool> outputChannelFlag;
1223 outputChannelFlag.resize(maxNumberOfEchos);
1226 for (i = 0; i < outputChannelFlag.size(); i++)
1244 outputChannelFlag[i] =
true;
1248 if (numOfFlags == 0)
1250 outputChannelFlag[0] =
true;
1252 ROS_WARN(
"Activate at least one echo.");
1256 int EncoderSetings = -1;
1257 pn.
getParam(
"encoder_mode", EncoderSetings);
1291 int angleRes10000th = 0;
1292 int angleStart10000th = 0;
1293 int angleEnd10000th = 0;
1306 volatile bool useBinaryCmd =
false;
1309 useBinaryCmd =
true;
1312 bool useBinaryCmdNow =
false;
1315 const int shortTimeOutInMs = 5000;
1316 const int defaultTimeOutInMs = 120000;
1320 bool restartDueToProcolChange =
false;
1325 bool NAV3xxOutputRangeSpecialHandling=
false;
1328 NAV3xxOutputRangeSpecialHandling =
true;
1337 std::vector<unsigned char> replyDummy;
1338 std::vector<unsigned char> reqBinary;
1341 for (
size_t j = 0; j < sopasCmd.length(); j++)
1343 sopasCmdVec.push_back(sopasCmd[j]);
1351 for (
int iLoop = 0; iLoop < maxCmdLoop; iLoop++)
1355 useBinaryCmdNow = useBinaryCmd;
1360 useBinaryCmdNow = !useBinaryCmdNow;
1361 useBinaryCmd = useBinaryCmdNow;
1368 if (useBinaryCmdNow)
1409 if (
false == protocolCheck)
1411 restartDueToProcolChange =
true;
1413 useBinaryCmd = useBinaryCmdNow;
1420 if (
false == protocolCheck)
1422 restartDueToProcolChange =
true;
1425 useBinaryCmd = useBinaryCmdNow;
1436 std::string deviceIdent =
"";
1443 std::string deviceIdentKeyWord =
"sRA DeviceIdent";
1444 char *ptr = (
char *) (&(replyDummy[0]));
1446 ptr += deviceIdentKeyWord.length();
1448 sscanf(ptr,
"%d", &idLen);
1449 char *ptr2 = strchr(ptr,
' ');
1453 for (
int i = 0; i < idLen; i++)
1455 deviceIdent += *ptr2;
1462 sscanf(ptr,
"%d", &versionLen);
1463 ptr2 = strchr(ptr,
' ');
1467 deviceIdent +=
" V";
1468 for (
int i = 0; i < versionLen; i++)
1470 deviceIdent += *ptr2;
1483 long dummy0, dummy1, identLen, versionLen;
1489 const char *scanMask0 =
"%04y%04ysRA DeviceIdent %02y";
1490 const char *scanMask1 =
"%02y";
1491 unsigned char *replyPtr = &(replyDummy[0]);
1494 binScanfVec(&replyDummy, scanMask0, &dummy0, &dummy1, &identLen);
1497 int off = scanDataLen0 + identLen;
1499 std::vector<unsigned char> restOfReplyDummy = std::vector<unsigned char>(replyDummy.begin() + off,
1503 binScanfVec(&restOfReplyDummy,
"%02y", &versionLen);
1505 std::string fullIdentVersionInfo = identStr +
" V" + versionStr;
1538 int deviceState = -1;
1551 &dummy1, &deviceState);
1559 switch (deviceState)
1584 int operationHours = -1;
1592 long dummy0, dummy1;
1606 double hours = 0.1 * operationHours;
1607 pn.
setParam(
"operationHours", hours);
1614 int powerOnCount = -1;
1618 long dummy0, dummy1;
1629 pn.
setParam(
"powerOnCount", powerOnCount);
1637 char szLocationName[MAX_STR_LEN] = {0};
1639 const char *searchPattern =
"sRA LocationName ";
1640 strcpy(szLocationName,
"unknown location");
1644 long dummy0, dummy1, locationNameLen;
1645 const char *binLocationNameMask =
"%4y%4ysRA LocationName %2y";
1649 locationNameLen = 0;
1658 strcpy(szLocationName, locationNameStr.c_str());
1663 if (strstr(strPtr, searchPattern) == strPtr)
1665 const char *ptr = strPtr + strlen(searchPattern);
1666 strcpy(szLocationName, ptr);
1670 ROS_WARN(
"Location command not supported.\n");
1673 pn.
setParam(
"locationName", std::string(szLocationName));
1688 bool useNegSign =
false;
1689 if (NAV3xxOutputRangeSpecialHandling == 0)
1696 std::vector<unsigned char> tmpVec;
1698 if (useBinaryCmd ==
false)
1700 for (
int i = 0; i < s.length(); i++)
1702 tmpVec.push_back((
unsigned char)s[i]);
1720 if (restartDueToProcolChange)
1732 ROS_INFO(
"IP address changed. Node restart required");
1766 angleRes10000th = (int) (boost::math::round(
1768 std::vector<unsigned char> askOutputAngularRangeReply;
1773 if (NAV3xxOutputRangeSpecialHandling)
1781 std::vector<unsigned char> reqBinary;
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};
1800 int iDummy0, iDummy1;
1801 std::string askOutputAngularRangeStr =
replyToString(askOutputAngularRangeReply);
1817 askTmpAngleRes10000th = 0;
1818 askTmpAngleStart10000th = 0;
1819 askTmpAngleEnd10000th = 0;
1821 const char *askOutputAngularRangeBinMask =
"%4y%4ysRA LMPoutputRange %2y%4y%4y%4y";
1825 &askTmpAngleRes10000th,
1826 &askTmpAngleStart10000th,
1827 &askTmpAngleEnd10000th);
1832 numArgs = sscanf(askOutputAngularRangeStr.c_str(),
"%s %s %d %X %X %X", dummy0, dummy1,
1834 &askTmpAngleRes10000th,
1835 &askTmpAngleStart10000th,
1836 &askTmpAngleEnd10000th);
1840 double askTmpAngleRes = askTmpAngleRes10000th / 10000.0;
1841 double askTmpAngleStart = askTmpAngleStart10000th / 10000.0;
1842 double askTmpAngleEnd = askTmpAngleEnd10000th / 10000.0;
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);
1871 minAngSopas += 90.0;
1872 maxAngSopas += 90.0;
1875 angleStart10000th = (int) (boost::math::round(10000.0 * minAngSopas));
1876 angleEnd10000th = (int) (boost::math::round(10000.0 * maxAngSopas));
1878 char requestOutputAngularRange[MAX_STR_LEN];
1880 std::vector<unsigned char> outputAngularRangeReply;
1883 if (NAV3xxOutputRangeSpecialHandling == 0)
1886 sprintf(requestOutputAngularRange, pcCmdMask,
1887 angleRes10000th, angleStart10000th, angleEnd10000th,
1888 angleRes10000th, angleStart10000th, angleEnd10000th,
1889 angleRes10000th, angleStart10000th, angleEnd10000th,
1890 angleRes10000th, angleStart10000th, angleEnd10000th);
1895 sprintf(requestOutputAngularRange, pcCmdMask, angleRes10000th, angleStart10000th, angleEnd10000th);
1899 unsigned char tmpBuffer[255] = {0};
1900 unsigned char sendBuffer[255] = {0};
1902 std::vector<unsigned char> reqBinary;
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);
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);
1939 reqBinary = std::vector<unsigned char>(sendBuffer, sendBuffer + sendLen);
1963 askOutputAngularRangeReply.clear();
1967 std::vector<unsigned char> reqBinary;
1978 char dummy0[MAX_STR_LEN] = {0};
1979 char dummy1[MAX_STR_LEN] = {0};
1981 int askAngleRes10000th = 0;
1982 int askAngleStart10000th = 0;
1983 int askAngleEnd10000th = 0;
1984 int iDummy0, iDummy1;
1987 std::string askOutputAngularRangeStr =
replyToString(askOutputAngularRangeReply);
2006 askAngleRes10000th = 0;
2007 askAngleStart10000th = 0;
2008 askAngleEnd10000th = 0;
2017 const char *askOutputAngularRangeBinMask =
"%4y%4ysRA LMPoutputRange %2y%4y%4y%4y";
2021 &askAngleRes10000th,
2022 &askAngleStart10000th,
2023 &askAngleEnd10000th);
2028 numArgs = sscanf(askOutputAngularRangeStr.c_str(),
"%s %s %d %X %X %X", dummy0, dummy1,
2030 &askAngleRes10000th,
2031 &askAngleStart10000th,
2032 &askAngleEnd10000th);
2036 double askTmpAngleRes = askAngleRes10000th / 10000.0;
2037 double askTmpAngleStart = askAngleStart10000th / 10000.0;
2038 double askTmpAngleEnd = askAngleEnd10000th / 10000.0;
2040 angleRes10000th = askAngleRes10000th;
2041 ROS_INFO(
"Angle resolution of scanner is %0.5lf [deg] (in 1/10000th deg: 0x%X)", askTmpAngleRes,
2042 askAngleRes10000th);
2045 double askAngleRes = askAngleRes10000th / 10000.0;
2046 double askAngleStart = askAngleStart10000th / 10000.0;
2047 double askAngleEnd = askAngleEnd10000th / 10000.0;
2055 askAngleStart -= 90;
2058 this->
config_.min_ang = askAngleStart / 180.0 * M_PI;
2059 this->
config_.max_ang = askAngleEnd / 180.0 * M_PI;
2065 ROS_INFO(
"MIN_ANG (after command verification): %8.3f [rad] %8.3f [deg]",
config_.min_ang,
2067 ROS_INFO(
"MAX_ANG (after command verification): %8.3f [rad] %8.3f [deg]",
config_.max_ang,
2083 for (
size_t i = 0; i < outputChannelFlag.size(); i++)
2094 ROS_INFO(
"LMS 5xx detected overwriting output channel flag ID");
2096 ROS_INFO(
"LMS 5xx detected overwriting resolution flag (only 8 bit supported)");
2102 ROS_INFO(
"MRS 1xxx detected overwriting resolution flag (only 8 bit supported)");
2113 for(
int fieldnum=0;fieldnum<maxFieldnum;fieldnum++)
2115 char requestFieldcfg[MAX_STR_LEN];
2117 sprintf(requestFieldcfg, pcCmdMask, fieldnum);
2119 std::vector<unsigned char> reqBinary;
2120 std::vector<unsigned char> fieldcfgReply;
2125 std::vector<unsigned char> fieldcfgReply;
2134 std::string LIDinputstateRequest =
"\x02sRN LIDinputstate\x03";
2135 std::vector<unsigned char> LIDinputstateResponse;
2138 std::vector<unsigned char> reqBinary;
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();
2164 for(
int n = 0; n < fieldMon->
getMonFields().size(); n++)
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++)
2173 field_info2 <<
", ";
2174 field_info2 <<
"(" << fieldMon->
getMonFields()[n].getFieldPointsX()[m] <<
"," << fieldMon->
getMonFields()[n].getFieldPointsY()[m] <<
")";
2188 char requestLMDscandatacfg[MAX_STR_LEN];
2192 sprintf(requestLMDscandatacfg, pcCmdMask,
outputChannelFlagId, rssiFlag ? 1 : 0, rssiResolutionIs16Bit ? 1 : 0,
2193 EncoderSetings != -1 ? EncoderSetings : 0);
2196 std::vector<unsigned char> reqBinary;
2207 std::vector<unsigned char> lmdScanDataCfgReply;
2213 char requestLMDscandatacfgRead[MAX_STR_LEN];
2219 std::vector<unsigned char> reqBinary;
2225 std::vector<unsigned char> lmdScanDataCfgReadReply;
2233 double scan_freq = 0;
2235 pn.
getParam(
"scan_freq", scan_freq);
2237 if (scan_freq != 0 || ang_res != 0)
2239 if (scan_freq != 0 && ang_res != 0)
2243 ROS_INFO(
"variable ang_res and scan_freq setings for NAV 3xx has not been implemented yet using 20 Hz 0.75 deg");
2247 char requestLMDscancfg[MAX_STR_LEN];
2250 sprintf(requestLMDscancfg, pcCmdMask, (
long) (scan_freq * 100 + 1e-9), (
long) (ang_res * 10000 + 1e-9));
2253 std::vector<unsigned char> reqBinary;
2259 std::vector<unsigned char> lmdScanCfgReply;
2265 char requestLMDscancfgRead[MAX_STR_LEN];
2271 std::vector<unsigned char> reqBinary;
2277 std::vector<unsigned char> lmdScanDataCfgReadReply;
2285 ROS_ERROR(
"ang_res and scan_freq have to be set, only one param is set skiping scan_fre/ang_res config");
2328 char requestEchoSetting[MAX_STR_LEN];
2329 int filterEchoSetting = 0;
2330 pn.
getParam(
"filter_echos", filterEchoSetting);
2331 if (filterEchoSetting < 0)
2332 { filterEchoSetting = 0; }
2333 if (filterEchoSetting > 2)
2334 { filterEchoSetting = 2; }
2342 sprintf(requestEchoSetting, pcCmdMask, filterEchoSetting);
2343 std::vector<unsigned char> outputFilterEchoRangeReply;
2348 std::vector<unsigned char> reqBinary;
2369 std::vector<int> startProtocolSequence;
2370 bool deviceIsRadar =
false;
2374 bool transmitRawTargets =
true;
2375 bool transmitObjects =
true;
2376 int trackingMode = 0;
2377 std::string trackingModeDescription[] = {
"BASIC",
"VEHICLE"};
2379 int numTrackingModes =
sizeof(trackingModeDescription) /
sizeof(trackingModeDescription[0]);
2381 tmpParam.
getParam(
"transmit_raw_targets", transmitRawTargets);
2382 tmpParam.
getParam(
"transmit_objects", transmitObjects);
2383 tmpParam.
getParam(
"tracking_mode", trackingMode);
2386 if ((trackingMode < 0) || (trackingMode >= numTrackingModes))
2388 ROS_WARN(
"tracking mode id invalid. Switch to tracking mode 0");
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());
2395 deviceIsRadar =
true;
2407 if (transmitRawTargets)
2416 if (transmitObjects)
2425 switch (trackingMode)
2434 ROS_DEBUG(
"Tracking mode switching sequence unknown\n");
2442 startProtocolSequence.push_back(
CMD_RUN);
2459 startProtocolSequence.push_back(
CMD_RUN);
2467 bool activate_lferec =
true, activate_lidoutputstate =
true, activate_lidinputstate =
true;
2468 if (
true == tmpParam.
getParam(
"activate_lferec", activate_lferec) &&
true == activate_lferec)
2473 if (
true == tmpParam.
getParam(
"activate_lidoutputstate", activate_lidoutputstate) &&
true == activate_lidoutputstate)
2478 if (
true == tmpParam.
getParam(
"activate_lidinputstate", activate_lidinputstate) &&
true == activate_lidinputstate)
2488 bool imu_enable =
false;
2489 tmp.
getParam(
"imu_enable", imu_enable);
2492 if (useBinaryCmdNow ==
true)
2494 ROS_INFO(
"Enable IMU data transfer");
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");
2509 std::vector<int>::iterator it;
2510 for (it = startProtocolSequence.begin(); it != startProtocolSequence.end(); it++)
2513 std::vector<unsigned char> tmpReply;
2517 std::vector<unsigned char> replyDummy;
2518 std::vector<unsigned char> reqBinary;
2519 std::vector<unsigned char> sopasVec;
2554 ROS_DEBUG(
"Starting radar data ....\n");
2565 bool waitForDeviceState =
true;
2568 waitForDeviceState =
false;
2572 waitForDeviceState =
false;
2575 if (waitForDeviceState)
2577 int maxWaitForDeviceStateReady = 45;
2578 bool scannerReady =
false;
2579 for (
int i = 0; i < maxWaitForDeviceStateReady; i++)
2581 double shortSleepTime = 1.0;
2583 std::vector<unsigned char> replyDummy;
2586 int deviceState = 0;
2588 std::vector<unsigned char> reqBinary;
2589 std::vector<unsigned char> sopasVec;
2607 long dummy0, dummy1;
2612 &dummy1, &deviceState);
2620 if (deviceState == 1)
2622 scannerReady =
true;
2623 ROS_INFO(
"Scanner ready for measurement after %d [sec]", i);
2627 ROS_INFO(
"Waiting for scanner ready state since %d secs", i);
2651 std::string reply_str;
2652 std::vector<unsigned char>::const_iterator it_start, it_end;
2656 it_start = reply.begin();
2657 it_end = reply.end();
2661 it_start = reply.begin() + 8;
2662 it_end = reply.end() - 1;
2664 bool inHexPrintMode =
false;
2665 for (std::vector<unsigned char>::const_iterator it = it_start; it != it_end; it++)
2669 if (*it >= 0x20 && (inHexPrintMode ==
false))
2671 reply_str.push_back(*it);
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++)
2683 reply_str.push_back(szTmp[ii]);
2696 char szDumpFileName[511] = {0};
2697 char szDir[255] = {0};
2700 ROS_INFO(
"Attention: verboseLevel is set to 1. Datagrams are stored in the /tmp folder.");
2703 strcpy(szDir,
"C:\\temp\\");
2705 strcpy(szDir,
"/tmp/");
2707 sprintf(szDumpFileName,
"%ssick_datagram_%06d.bin", szDir, cnt);
2712 ftmp = fopen(szDumpFileName,
"wb");
2715 fwrite(buffer, bufLen, 1, ftmp);
2733 char device_string[7];
2734 int version_major = -1;
2735 int version_minor = -1;
2737 strcpy(device_string,
"???");
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)
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);
2751 bool supported =
false;
2754 if (sscanf(identStr.c_str(),
"sRA 0 6 %6s E V%d.%d", device_string, &version_major, &version_minor) == 3)
2756 std::string devStr = device_string;
2759 if (devStr.compare(0, 4,
"TiM5") == 0)
2764 if (supported ==
true)
2766 ROS_INFO(
"Device %s V%d.%d found and supported by this driver.", identStr.c_str(), version_major,
2772 if ((identStr.find(
"MRS1xxx") !=
2774 || (identStr.find(
"LMS1xxx") != std::string::npos)
2777 ROS_INFO(
"Deviceinfo %s found and supported by this driver.", identStr.c_str());
2782 if (identStr.find(
"MRS6") !=
2785 ROS_INFO(
"Deviceinfo %s found and supported by this driver.", identStr.c_str());
2789 if (identStr.find(
"RMS3xx") !=
2792 ROS_INFO(
"Deviceinfo %s found and supported by this driver.", identStr.c_str());
2797 if (supported ==
false)
2799 ROS_WARN(
"Device %s V%d.%d found and maybe unsupported by this driver.", device_string, version_major,
2801 ROS_WARN(
"Full SOPAS answer: %s", identStr.c_str());
2816 unsigned char receiveBuffer[65536];
2817 int actual_length = 0;
2818 static unsigned int iteration_count = 0;
2832 int packetsInLoop = 0;
2834 const int maxNumAllowedPacketsToProcess = 25;
2836 int numPacketsProcessed = 0;
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)
2849 tmpParam.
getParam(
"slam_echo", echoForSlam);
2850 tmpParam.
getParam(
"slam_bundle", slamBundle);
2851 tmpParam.
getParam(
"verboseLevel", verboseLevel);
2852 firstTimeCalled =
false;
2857 int result =
get_datagram(recvTimeStamp, receiveBuffer, 65536, &actual_length, useBinaryProtocol, &packetsInLoop);
2858 numPacketsProcessed++;
2864 ROS_ERROR(
"Read Error when getting datagram: %i.", result);
2868 if (actual_length <= 0)
2874 if (iteration_count++ % (
config_.skip + 1) != 0)
2884 std_msgs::String datagram_msg;
2885 datagram_msg.data = std::string(reinterpret_cast<char *>(receiveBuffer));
2890 if (verboseLevel > 0)
2896 bool deviceIsRadar =
false;
2900 deviceIsRadar =
true;
2903 if (
true == deviceIsRadar)
2908 errorCode = radar->
parseDatagram(recvTimeStamp, (
unsigned char *) receiveBuffer, actual_length,
2914 if (scanImu.
isImuDatagram((
char *) receiveBuffer, actual_length))
2924 errorCode = scanImu.
parseDatagram(recvTimeStamp, (
unsigned char *) receiveBuffer, actual_length,
2930 else if(memcmp(&receiveBuffer[8],
"sSN LIDoutputstate", strlen(
"sSN LIDoutputstate")) == 0)
2937 sick_scan::LIDoutputstateMsg outputstate_msg;
2956 else if(memcmp(&receiveBuffer[8],
"sSN LIDinputstate", strlen(
"sSN LIDinputstate")) == 0)
2961 if(fieldMon && useBinaryProtocol && actual_length > 32)
2971 else if(memcmp(&receiveBuffer[8],
"sSN LFErec", strlen(
"sSN LFErec")) == 0)
2976 sick_scan::LFErecMsg lferec_msg;
2997 else if(memcmp(&receiveBuffer[8],
"sSN LMDscandatamon", strlen(
"sSN LMDscandatamon")) == 0)
3000 ROS_DEBUG_STREAM(
"SickScanCommon: received " << actual_length <<
" byte LMDscandatamon (ignored) ...");
3006 sensor_msgs::LaserScan
msg;
3007 sick_scan::Encoder EncoderMsg;
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;
3018 char *buffer_pos = (
char *) receiveBuffer;
3019 char *dstart, *dend;
3020 bool dumpDbg =
false;
3021 bool dataToProcess =
true;
3022 std::vector<float> vang_vec;
3027 while (dataToProcess)
3029 const int maxAllowedEchos = 5;
3031 int numValidEchos = 0;
3032 int aiValidEchoIdx[maxAllowedEchos] = {0};
3037 bool publishPointCloud =
true;
3039 if (useBinaryProtocol)
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)
3053 if (receiveBufferVec.size() > 8)
3057 memcpy(&idVal, receiveBuffer + 0, 4);
3058 memcpy(&lenVal, receiveBuffer + 4, 4);
3061 if (idVal == 0x02020202)
3066 char szFileName[255];
3069 sprintf(szFileName,
"c:\\temp\\dump%05d.bin", cnt);
3071 sprintf(szFileName,
"/tmp/dump%05d.txt", cnt);
3074 fout = fopen(szFileName,
"wb");
3075 fwrite(receiveBuffer, actual_length, 1, fout);
3081 if (lenVal < actual_length)
3083 short elevAngleX200 = 0;
3085 int scanFrequencyX100 = 0;
3086 double elevAngle = 0.00;
3087 double scanFrequency = 0.0;
3088 long measurementFrequencyDiv100 = 0;
3089 int numOfEncoders = 0;
3090 int numberOf16BitChannels = 0;
3091 int numberOf8BitChannels = 0;
3092 uint32_t SystemCountScan = 0;
3093 static uint32_t lastSystemCountScan = 0;
3094 uint32_t SystemCountTransmit = 0;
3096 memcpy(&elevAngleX200, receiveBuffer + 50, 2);
3099 elevationAngleInRad = -elevAngleX200 / 200.0 *
deg2rad_const;
3101 msg.header.seq = elevAngleX200;
3103 memcpy(&SystemCountScan, receiveBuffer + 0x26, 4);
3104 swap_endian((
unsigned char *) &SystemCountScan, 4);
3106 memcpy(&SystemCountTransmit, receiveBuffer + 0x2A, 4);
3107 swap_endian((
unsigned char *) &SystemCountTransmit, 4);
3108 double timestampfloat = recvTimeStamp.sec + recvTimeStamp.nsec * 1e-9;
3110 if (SystemCountScan !=
3111 lastSystemCountScan)
3114 SystemCountTransmit);
3115 lastSystemCountScan = SystemCountScan;
3120 double timestampfloat_coor = recvTimeStamp.sec + recvTimeStamp.nsec * 1e-9;
3121 double DeltaTime = timestampfloat - timestampfloat_coor;
3124 if (
config_.sw_pll_only_publish ==
true && bRet ==
false)
3128 ROS_INFO(
"%i / %i Packet dropped Software PLL not yet locked.",
3132 ROS_INFO(
"Software PLL is expected to be ready now!");
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 !");
3141 dataToProcess =
false;
3145 #ifdef DEBUG_DUMP_ENABLED 3146 double elevationAngleInDeg = elevationAngleInRad = -elevAngleX200 / 200.0;
3167 memcpy(&scanFrequencyX100, receiveBuffer + 52, 4);
3168 swap_endian((
unsigned char *) &scanFrequencyX100, 4);
3170 memcpy(&measurementFrequencyDiv100, receiveBuffer + 56, 4);
3171 swap_endian((
unsigned char *) &measurementFrequencyDiv100, 4);
3174 msg.scan_time = 1.0 / (scanFrequencyX100 / 100.0);
3177 if (measurementFrequencyDiv100 > 10000)
3179 measurementFrequencyDiv100 /= 100;
3181 msg.time_increment = 1.0 / (measurementFrequencyDiv100 * 100.0);
3182 timeIncrement = msg.time_increment;
3186 memcpy(&numOfEncoders, receiveBuffer + 60, 2);
3188 int encoderDataOffset = 6 * numOfEncoders;
3189 int32_t EncoderPosTicks[4] = {0};
3190 int16_t EncoderSpeed[4] = {0};
3192 if (numOfEncoders > 0 && numOfEncoders < 5)
3195 for (
int EncoderNum = 0; EncoderNum < numOfEncoders; EncoderNum++)
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);
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);
3209 int parseOff = 64 + encoderDataOffset;
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;
3225 for (
int i = 0; i < numberOf16BitChannels; i++)
3227 int numberOfItems = 0x00;
3228 memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3231 parseOff += numberOfItems * 2;
3235 memcpy(&numberOf8BitChannels, receiveBuffer + parseOff, 2);
3236 swap_endian((
unsigned char *) &numberOf8BitChannels, 2);
3238 parseOff = 64 + encoderDataOffset;
3239 enum datagram_parse_task
3248 int distChannelCnt = 0;
3250 for (
int processLoop = 0; processLoop < 2; processLoop++)
3252 int totalChannelCnt = 0;
3257 datagram_parse_task task = process_idle;
3258 bool parsePacket =
true;
3259 parseOff = 64 + encoderDataOffset;
3260 bool processData =
false;
3262 if (processLoop == 0)
3269 if (processLoop == 1)
3272 numEchos = distChannelCnt;
3273 msg.ranges.resize(numberOfItems * numEchos);
3276 msg.intensities.resize(numberOfItems * rssiCnt);
3283 vang_vec.resize(numberOfItems * vangleCnt);
3289 echoMask = (1 << numEchos) - 1;
3298 szChannel[6] =
'\0';
3300 scaleFactorOffset = 0.0;
3301 startAngleDiv10000 = 1;
3302 sizeOfSingleAngularStepDiv10000 = 1;
3304 sizeOfSingleAngularStep = 0.0;
3308 #if 1 // prepared for multiecho parsing 3311 bool doVangVecProc =
false;
3313 task = process_idle;
3316 task = process_idle;
3317 doVangVecProc =
false;
3318 int processDataLenValuesInBytes = 2;
3320 if (totalChannelCnt == numberOf16BitChannels)
3325 if (totalChannelCnt >= numberOf16BitChannels)
3327 processDataLenValuesInBytes = 1;
3330 strcpy(szChannel,
"");
3332 if (totalChannelCnt < (numberOf16BitChannels + numberOf8BitChannels))
3334 szChannel[5] =
'\0';
3335 strncpy(szChannel, (
const char *) receiveBuffer + parseOff, 5);
3342 if (strstr(szChannel,
"DIST") == szChannel)
3344 task = process_dist;
3348 memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3352 if (strstr(szChannel,
"VANG") == szChannel)
3355 task = process_vang;
3358 memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3361 vang_vec.resize(numberOfItems);
3364 if (strstr(szChannel,
"RSSI") == szChannel)
3366 task = process_rssi;
3371 memcpy(&numberOfItems, receiveBuffer + parseOff + 19, 2);
3378 scaleFactorOffset = 0.0;
3379 startAngleDiv10000 = 0;
3380 sizeOfSingleAngularStepDiv10000 = 0;
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);
3391 swap_endian((
unsigned char *) &scaleFactorOffset, 4);
3392 swap_endian((
unsigned char *) &startAngleDiv10000, 4);
3393 swap_endian((
unsigned char *) &sizeOfSingleAngularStepDiv10000, 2);
3398 unsigned short *
data = (
unsigned short *) (receiveBuffer + parseOff + 21);
3400 unsigned char *swapPtr = (
unsigned char *) data;
3403 i < numberOfItems * processDataLenValuesInBytes; i += processDataLenValuesInBytes)
3405 if (processDataLenValuesInBytes == 1)
3411 tmp = swapPtr[i + 1];
3412 swapPtr[i + 1] = swapPtr[i];
3423 startAngle = startAngleDiv10000 / 10000.00;
3424 sizeOfSingleAngularStep = sizeOfSingleAngularStepDiv10000 / 10000.0;
3425 sizeOfSingleAngularStep *= (M_PI / 180.0);
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;
3433 msg.angle_min -= M_PI/2;
3434 msg.angle_max -= M_PI/2;
3436 msg.angle_min *= -1.0;
3437 msg.angle_increment *= -1.0;
3438 msg.angle_max *= -1.0;
3441 float *rangePtr = NULL;
3443 if (numberOfItems > 0)
3445 rangePtr = &msg.ranges[0];
3447 float scaleFactor_001 = 0.001F * scaleFactor;
3448 for (
int i = 0; i < numberOfItems; i++)
3450 idx = i + numberOfItems * (distChannelCnt - 1);
3451 rangePtr[idx] = (float) data[i] * scaleFactor_001 + scaleFactorOffset;
3452 #ifdef DEBUG_DUMP_ENABLED 3453 if (distChannelCnt == 1)
3455 if (i == floor(numberOfItems / 2))
3457 double curTimeStamp = SystemCountScan + i * msg.time_increment * 1E6;
3471 float *intensityPtr = NULL;
3473 if (numberOfItems > 0)
3475 intensityPtr = &msg.intensities[0];
3478 for (
int i = 0; i < numberOfItems; i++)
3480 idx = i + numberOfItems * (rssiCnt - 1);
3482 float rssiVal = 0.0;
3483 if (processDataLenValuesInBytes == 2)
3485 rssiVal = (float) data[i];
3489 unsigned char *data8Ptr = (
unsigned char *) data;
3490 rssiVal = (float) data8Ptr[i];
3492 intensityPtr[idx] = rssiVal * scaleFactor + scaleFactorOffset;
3498 float *vangPtr = NULL;
3499 if (numberOfItems > 0)
3501 vangPtr = &vang_vec[0];
3503 for (
int i = 0; i < numberOfItems; i++)
3505 vangPtr[i] = (float) data[i] * scaleFactor + scaleFactorOffset;
3510 parseOff += 21 + processDataLenValuesInBytes * numberOfItems;
3519 elevAngle = elevAngleX200 / 200.0;
3520 scanFrequency = scanFrequencyX100 / 100.0;
3532 dataToProcess =
false;
3536 dstart = strchr(buffer_pos, 0x02);
3539 dend = strchr(dstart + 1, 0x03);
3541 if ((dstart != NULL) && (dend != NULL))
3543 dataToProcess =
true;
3544 dlength = dend - dstart;
3550 dataToProcess =
false;
3558 char szFileName[255];
3561 sprintf(szFileName,
"c:\\temp\\dump%05d.txt", cnt);
3563 sprintf(szFileName,
"/tmp/dump%05d.txt", cnt);
3567 fout = fopen(szFileName,
"wb");
3568 fwrite(dstart, dlength, 1, fout);
3582 publishPointCloud =
true;
3585 for (
int i = 0; i < maxAllowedEchos; i++)
3587 aiValidEchoIdx[i] = 0;
3596 bool elevationPreCalculated =
false;
3597 double elevationAngleDegree = 0.0;
3600 std::vector<float> rangeTmp = msg.ranges;
3601 std::vector<float> intensityTmp = msg.intensities;
3603 int intensityTmpNum = intensityTmp.size();
3604 float *intensityTmpPtr = NULL;
3605 if (intensityTmpNum > 0)
3607 intensityTmpPtr = &intensityTmp[0];
3615 bool useGivenElevationAngle =
false;
3616 switch (numOfLayers)
3624 if (msg.header.seq == 250)
3626 else if (msg.header.seq == 0)
3628 else if (msg.header.seq == -250)
3630 else if (msg.header.seq == -500)
3633 elevationAngleDegree = elevationAngleDegree / 180.0 * M_PI;
3638 layer = (msg.header.seq - (-2638)) / 125;
3639 layer = (23 - layer) - 1;
3642 elevationAngleDegree = elevationAngleDegree / 180.0 * M_PI;
3645 elevationPreCalculated =
true;
3646 if (vang_vec.size() > 0)
3648 useGivenElevationAngle =
true;
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++)
3675 bool sendMsg =
false;
3678 aiValidEchoIdx[numValidEchos] = i;
3682 startOffset = i * echoPartNum;
3683 endOffset = (i + 1) * echoPartNum;
3686 msg.intensities.clear();
3687 msg.ranges = std::vector<float>(
3688 rangeTmp.begin() + startOffset,
3689 rangeTmp.begin() + endOffset);
3691 if (endOffset <= intensityTmp.size() && (intensityTmp.size() > 0))
3693 msg.intensities = std::vector<float>(
3694 intensityTmp.begin() + startOffset,
3695 intensityTmp.begin() + endOffset);
3699 msg.intensities.resize(echoPartNum);
3703 char szTmp[255] = {0};
3706 const char *cpFrameId =
config_.frame_id.c_str();
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)
3713 strcpy(szSignName,
"NEG");
3717 strcpy(szSignName,
"POS");
3721 sprintf(szTmp,
"%s_%s_%03d_DIST%d", cpFrameId, szSignName, abs((
int) msg.header.seq), i + 1);
3726 strcpy(szTmp,
config_.frame_id.c_str());
3729 msg.header.frame_id = std::string(szTmp);
3731 if (echoForSlam.length() > 0)
3739 msg.header.frame_id = echoForSlam;
3740 strcpy(szTmp, echoForSlam.c_str());
3741 if (elevationAngleInRad != 0.0)
3743 float cosVal = cos(elevationAngleInRad);
3744 int rangeNum = msg.ranges.size();
3745 for (
int j = 0; j < rangeNum; j++)
3747 msg.ranges[j] *= cosVal;
3753 if (echoForSlam.compare(szTmp) == 0)
3769 if (numOfLayers > 4)
3774 outputChannelFlagId)
3781 printf(
"MSG received...");
3787 if (publishPointCloud ==
true)
3791 const int numChannels = 4;
3793 int numTmpLayer = numOfLayers;
3796 cloud_.header.stamp = recvTimeStamp + ros::Duration(
config_.time_offset);
3801 cloud_.height = numTmpLayer * numValidEchos;
3802 cloud_.width = msg.ranges.size();
3803 cloud_.is_bigendian =
false;
3805 cloud_.point_step = numChannels *
sizeof(float);
3807 cloud_.fields.resize(numChannels);
3808 for (
int i = 0; i < numChannels; i++)
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;
3819 unsigned char *cloudDataPtr = &(
cloud_.data[0]);
3824 std::vector<float> cosAlphaTable;
3825 std::vector<float> sinAlphaTable;
3826 size_t rangeNum = rangeTmp.size() / numValidEchos;
3827 cosAlphaTable.resize(rangeNum);
3828 sinAlphaTable.resize(rangeNum);
3829 float mirror_factor = 1.0;
3837 for (
size_t iEcho = 0; iEcho < numValidEchos; iEcho++)
3843 float *cosAlphaTablePtr = &cosAlphaTable[0];
3844 float *sinAlphaTablePtr = &sinAlphaTable[0];
3846 float *vangPtr = NULL;
3847 float *rangeTmpPtr = &rangeTmp[0];
3848 if (vang_vec.size() > 0)
3850 vangPtr = &vang_vec[0];
3852 for (
size_t i = 0; i < rangeNum; i++)
3854 enum enum_index_descr
3862 long adroff = i * (numChannels * (int)
sizeof(
float));
3864 adroff += (layer - baseLayer) *
cloud_.row_step;
3866 adroff += iEcho *
cloud_.row_step * numTmpLayer;
3868 unsigned char *ptr = cloudDataPtr + adroff;
3869 float *fptr = (
float *) (cloudDataPtr + adroff);
3871 geometry_msgs::Point32 point;
3872 float range_meter = rangeTmpPtr[iEcho * rangeNum + i];
3876 if (useGivenElevationAngle)
3882 if (elevationPreCalculated)
3884 alpha = elevationAngleInRad;
3888 alpha = layer * elevationAngleDegree;
3894 cosAlphaTablePtr[i] = cos(alpha);
3895 sinAlphaTablePtr[i] = sin(alpha);
3902 float rangeCos = range_meter * cosAlphaTablePtr[i];
3904 double phi_used = phi + angleShift;
3909 fptr[idx_x] = rangeCos * cos(phi_used);
3910 fptr[idx_y] = rangeCos * sin(phi_used);
3911 fptr[idx_z] = range_meter * sinAlphaTablePtr[i] * mirror_factor;
3913 fptr[idx_intensity] = 0.0;
3916 int intensityIndex = aiValidEchoIdx[iEcho] * rangeNum + i;
3918 if (intensityIndex < intensityTmpNum)
3920 fptr[idx_intensity] = intensityTmpPtr[intensityIndex];
3923 angle += msg.angle_increment;
3927 int layerOff = (layer - baseLayer);
3931 bool shallIFire =
false;
3932 if ((msg.header.seq == 0) || (msg.header.seq == 237))
3938 static int layerCnt = 0;
3939 static int layerSeq[4];
3941 if (
config_.cloud_output_mode > 0)
3944 layerSeq[layerCnt % 4] = layer;
3959 if (
config_.cloud_output_mode == 0)
3965 else if (
config_.cloud_output_mode == 2)
3977 int numTotalShots = 360;
3978 int numPartialShots = 40;
3980 for (
int i = 0; i < numTotalShots; i += numPartialShots)
3982 sensor_msgs::PointCloud2 partialCloud;
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;
3991 int diffTo1100 =
cloud_.width - 3 * (numTotalShots + i);
3992 if (diffTo1100 > numPartialShots)
3994 diffTo1100 = numPartialShots;
4000 partialCloud.width += diffTo1100;
4002 partialCloud.height = 1;
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++)
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;
4019 partialCloud.data.resize(partialCloud.row_step);
4022 for (
int j = 0; j < 4; j++)
4024 int layerIdx = (j + (layerCnt)) % 4;
4025 int rowIdx = 1 + layerSeq[layerIdx % 4];
4026 int colIdx = j * numTotalShots + i;
4027 int maxAvail =
cloud_.width - colIdx;
4033 if (maxAvail > numPartialShots)
4035 maxAvail = numPartialShots;
4041 memcpy(&(partialCloud.data[partOff]),
4043 cloud_.point_step * maxAvail);
4047 partOff += maxAvail * partialCloud.point_step;
4049 assert(partialCloud.data.size() == partialCloud.width * partialCloud.point_step);
4054 memcpy(&(partialCloud.data[0]), &(
cloud_.data[0]) + i *
cloud_.point_step,
cloud_.point_step * numPartialShots);
4062 printf(
"PUBLISH:\n");
4070 buffer_pos = dend + 1;
4077 }
while ((packetsInLoop > 0) && (numPacketsProcessed < maxNumAllowedPacketsToProcess));
4087 if (conf.min_ang > conf.max_ang)
4089 ROS_WARN(
"Maximum angle must be greater than minimum angle. Adjusting >min_ang<.");
4090 conf.min_ang = conf.max_ang;
4113 requestBinary->clear();
4114 if (requestAscii == NULL)
4118 int cmdLen = strlen(requestAscii);
4123 if (requestAscii[0] != 0x02)
4127 if (requestAscii[cmdLen - 1] != 0x03)
4132 for (
int i = 0; i < 4; i++)
4134 requestBinary->push_back(0x02);
4137 for (
int i = 0; i < 4; i++)
4139 requestBinary->push_back(0x00);
4142 unsigned long msgLen = cmdLen - 2;
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";
4162 std::string cmdAscii = requestAscii;
4165 int copyUntilSpaceCnt = 2;
4167 char hexStr[255] = {0};
4169 unsigned char buffer[255];
4171 if (cmdAscii.find(keyWord0) != std::string::npos)
4173 copyUntilSpaceCnt = 2;
4174 int keyWord0Len = keyWord0.length();
4175 sscanf(requestAscii + keyWord0Len + 1,
" %d %s", &level, hexStr);
4176 buffer[0] = (
unsigned char) (0xFF & level);
4178 char hexTmp[3] = {0};
4179 for (
int i = 0; i < 4; i++)
4182 hexTmp[0] = hexStr[i * 2];
4183 hexTmp[1] = hexStr[i * 2 + 1];
4185 sscanf(hexTmp,
"%x", &val);
4186 buffer[i + 1] = (
unsigned char) (0xFF & val);
4190 if (cmdAscii.find(keyWord1) != std::string::npos)
4192 int echoCodeNumber = 0;
4193 int keyWord1Len = keyWord1.length();
4194 sscanf(requestAscii + keyWord1Len + 1,
" %d", &echoCodeNumber);
4195 buffer[0] = (
unsigned char) (0xFF & echoCodeNumber);
4198 if (cmdAscii.find(keyWord2) != std::string::npos)
4200 int scanDataStatus = 0;
4201 int keyWord2Len = keyWord2.length();
4202 sscanf(requestAscii + keyWord2Len + 1,
" %d", &scanDataStatus);
4203 buffer[0] = (
unsigned char) (0xFF & scanDataStatus);
4207 if (cmdAscii.find(keyWord3) != std::string::npos)
4209 int scanDataStatus = 0;
4210 int keyWord3Len = keyWord3.length();
4211 int dummyArr[12] = {0};
4213 int sscanfresult = sscanf(requestAscii + keyWord3Len + 1,
" %d %d %d %d %d %d %d %d %d %d %d %d",
4226 if (1 < sscanfresult)
4229 for (
int i = 0; i < 13; i++)
4233 buffer[0] = (
unsigned char) (0xFF & dummyArr[0]);
4234 buffer[1] = (
unsigned char) (0xFF & dummyArr[1]);;
4235 buffer[2] = (
unsigned char) (0xFF & dummyArr[2]);
4236 buffer[3] = (
unsigned char) (0xFF & dummyArr[3]);
4237 buffer[4] = (
unsigned char) (0xFF & dummyArr[4]);
4238 buffer[5] = (
unsigned char) (0xFF & dummyArr[5]);
4239 buffer[6] = (
unsigned char) (0xFF & dummyArr[6]);
4240 buffer[7] = (
unsigned char) (0xFF & dummyArr[7]);
4241 buffer[8] = (
unsigned char) (0xFF & dummyArr[8]);
4242 buffer[9] = (
unsigned char) (0xFF & dummyArr[9]);
4243 buffer[10] = (
unsigned char) (0xFF & dummyArr[10]);
4244 buffer[11] = (
unsigned char) (0xFF & (dummyArr[11] >> 8));
4245 buffer[12] = (
unsigned char) (0xFF & (dummyArr[11] >> 0));
4252 if (cmdAscii.find(keyWord4) != std::string::npos)
4254 char tmpStr[1024] = {0};
4255 char szApplStr[255] = {0};
4256 int keyWord4Len = keyWord4.length();
4257 int scanDataStatus = 0;
4259 strcpy(tmpStr, requestAscii + keyWord4Len + 2);
4260 sscanf(tmpStr,
"%d %s %d", &dummy0, szApplStr, &dummy1);
4263 buffer[1] = dummy0 ? 0x01 : 0x00;
4264 for (
int ii = 0; ii < 4; ii++)
4266 buffer[2 + ii] = szApplStr[ii];
4268 buffer[6] = dummy1 ? 0x01 : 0x00;
4272 if (cmdAscii.find(keyWord5) != std::string::npos)
4274 int imuSetStatus = 0;
4275 int keyWord5Len = keyWord5.length();
4276 sscanf(requestAscii + keyWord5Len + 1,
" %d", &imuSetStatus);
4277 buffer[0] = (
unsigned char) (0xFF & imuSetStatus);
4281 if (cmdAscii.find(keyWord6) != std::string::npos)
4284 int imuSetStatus = 0;
4285 int keyWord6Len = keyWord6.length();
4286 sscanf(requestAscii + keyWord6Len + 1,
" %x %x %x %x", &(adrPartArr[0]), &(adrPartArr[1]), &(adrPartArr[2]),
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]);
4302 if (cmdAscii.find(keyWord7) != std::string::npos)
4308 for (
int i = 0; i < bufferLen; i++)
4310 unsigned char uch = 0x00;
4319 char tmpStr[1024] = {0};
4320 char szApplStr[255] = {0};
4321 int keyWord7Len = keyWord7.length();
4322 int scanDataStatus = 0;
4324 strcpy(tmpStr, requestAscii + keyWord7Len + 2);
4325 sscanf(tmpStr,
"%d 1 %d", &dummy0, &dummy1);
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));
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));
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]))
4349 for (
int i = 0; i < 54; i++)
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++)
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);
4363 bufferLen = targetPosArr[numElem];
4374 if (cmdAscii.find(keyWord8) != std::string::npos)
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));
4385 if (cmdAscii.find(keyWord9) != std::string::npos)
4388 int imuSetStatus = 0;
4389 int keyWord9Len = keyWord9.length();
4390 sscanf(requestAscii + keyWord9Len + 1,
" %x %x %x %x", &(adrPartArr[0]), &(adrPartArr[1]), &(adrPartArr[2]),
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]);
4398 if (cmdAscii.find(keyWord10) != std::string::npos)
4400 float EncResolution = 0;
4402 int keyWord10Len = keyWord10.length();
4403 sscanf(requestAscii + keyWord10Len + 1,
" %f", &EncResolution);
4404 memcpy(buffer, &EncResolution, bufferLen);
4408 if (cmdAscii.find(keyWord11) != std::string::npos)
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);
4417 buffer[0] = dummy0 ? 0x01 : 0x00;
4418 buffer[1] =dummy1/256;
4419 buffer[2] =dummy1%256;
4423 if (cmdAscii.find(KeyWord12) != std::string::npos)
4425 uint32_t fieldID = 0;
4426 int keyWord12Len = KeyWord12.length();
4427 sscanf(requestAscii + keyWord12Len + 1,
"%d", &fieldID);
4431 bool switchDoBinaryData =
false;
4432 for (
int i = 1; i <= (int) (msgLen); i++)
4434 char c = requestAscii[i];
4435 if (switchDoBinaryData ==
true)
4439 if (c >=
'0' && c <=
'9')
4449 requestBinary->push_back(c);
4450 if (requestAscii[i] == 0x20)
4453 if (spaceCnt >= copyUntilSpaceCnt)
4455 switchDoBinaryData =
true;
4462 for (
int i = 0; i < bufferLen; i++)
4464 requestBinary->push_back(buffer[i]);
4467 msgLen = requestBinary->size();
4469 for (
int i = 0; i < 4; i++)
4471 unsigned char bigEndianLen = msgLen & (0xFF << (3 - i) * 8);
4472 (*requestBinary)[i + 4] = ((
unsigned char) (bigEndianLen));
4474 unsigned char xorVal = 0x00;
4475 xorVal =
sick_crc8((
unsigned char *) (&((*requestBinary)[8])), requestBinary->size() - 8);
4476 requestBinary->push_back(xorVal);
4478 for (
int i = 0; i < requestBinary->size(); i++)
4480 unsigned char c = (*requestBinary)[i];
4481 printf(
"[%c]%02x ", (c <
' ') ?
'.' : c, c) ;
4498 bool retValue =
true;
4500 if (shouldUseBinary == useBinaryCmdNow)
4516 if (shouldUseBinary ==
true)
4525 useBinaryCmdNow = shouldUseBinary;
4534 int eepwritetTimeOut = 1;
4535 bool result =
false;
4538 unsigned long adrBytesLong[4];
4539 std::string
s = ipNewIPAddr.to_string();
4540 const char *ptr = s.c_str();
4542 sscanf(ptr,
"%lu.%lu.%lu.%lu", &(adrBytesLong[0]), &(adrBytesLong[1]), &(adrBytesLong[2]), &(adrBytesLong[3]));
4545 unsigned char ipbytearray[4];
4546 for (
int i = 0; i < 4; i++)
4548 ipbytearray[i] = adrBytesLong[i] & 0xFF;
4552 char ipcommand[255];
4554 sprintf(ipcommand, pcCmdMask, ipbytearray[0], ipbytearray[1], ipbytearray[2], ipbytearray[3]);
4557 std::vector<unsigned char> reqBinary;
4575 std::vector<unsigned char> ipcomandReply;
4576 std::vector<unsigned char> resetReply;
4592 bool result =
false;
4595 unsigned long adrBytesLong[4];
4596 std::string
s = ipNewIPAddr.to_string();
4597 const char *ptr = s.c_str();
4599 sscanf(ptr,
"%lu.%lu.%lu.%lu", &(adrBytesLong[0]), &(adrBytesLong[1]), &(adrBytesLong[2]), &(adrBytesLong[3]));
4602 unsigned char ipbytearray[4];
4603 for (
int i = 0; i < 4; i++)
4605 ipbytearray[i] = adrBytesLong[i] & 0xFF;
4609 char ntpipcommand[255];
4610 char ntpupdatetimecommand[255];
4612 sprintf(ntpipcommand, pcCmdMask, ipbytearray[0], ipbytearray[1], ipbytearray[2], ipbytearray[3]);
4615 sprintf(ntpupdatetimecommand, pcCmdMaskUpdatetime, 5);
4616 std::vector<unsigned char> outputFilterntpupdatetimecommand;
4620 std::vector<unsigned char> reqBinary;
4637 std::vector<unsigned char> ipcomandReply;
4638 std::vector<unsigned char> resetReply;
const std::vector< SickScanMonField > & getMonFields(void) const
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)
std::vector< std::string > sopasReplyStrVec
static std::string binDataToAsciiString(const uint8_t *binary_data, int length)
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
int getReadTimeOutInMs()
get timeout in milliseconds
double expectedFrequency_
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...
ros::Publisher lferec_pub_
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()
bool isImuAckDatagram(char *datagram, size_t datagram_length)
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.
int convertAscii2BinaryCmd(const char *requestAscii, std::vector< unsigned char > *requestBinary)
Convert ASCII-message to Binary-message.
virtual int init_device()=0
bool publish_lidoutputstate_
bool getScanMirroredAndShifted()
flag to mark mirroring of rotation direction
void swap_endian(unsigned char *ptr, int numBytes)
Universal swapping function.
std::string getHumanReadableFormula(void)
int parseDatagram(ros::Time timeStamp, unsigned char *receiveBuffer, int actual_length, bool useBinaryProtocol)
int binScanfVec(const std::vector< unsigned char > *vec, const char *fmt,...)
bool setNewIpAddress(boost::asio::ip::address_v4 ipNewIPAddr, bool useBinaryCmd)
bool getIntensityResolutionIs16Bit(void)
Get the RSSI Value length.
TFSIMD_FORCE_INLINE tfScalar angle(const Quaternion &q1, const Quaternion &q2)
dynamic_reconfigure::Server< sick_scan::SickScanConfig > dynamic_reconfigure_server_
int getActiveFieldset(void)
bool getCorrectedTimeStamp(uint32_t &sec, uint32_t &nanoSec, uint32_t tick)
diagnostic_updater::Updater diagnostics_
ros::Publisher Encoder_pub
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.
SopasProtocol m_protocolId
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
bool param(const std::string ¶m_name, T ¶m_val, const T &default_val) const
std::vector< int > sopasCmdChain
ros::Publisher imuScan_pub_
void addFrameToBuffer(UINT8 *sendBuffer, UINT8 *cmdBuffer, UINT16 *len)
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)
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 ROS_WARN_STREAM(args)
ScannerBasicParam * getCurrentParamPtr()
Gets Pointer to parameter object.
#define ROS_DEBUG_STREAM(args)
static DataDumper & instance()
#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.
ros::Publisher datagram_pub_
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
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)
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
int getMaxEvalFields(void)
bool getSensorIsRadar(void)
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.
static const int fifoSize
std::mutex sopasSendMutex
diagnostic_updater::DiagnosedPublisher< sensor_msgs::LaserScan > * diagnosticPub_
#define SICK_SCANNER_NAV_2XX_NAME
int parseBinaryDatagram(std::vector< unsigned char > datagramm)
sensor_msgs::PointCloud2 cloud_
int dumpUcharBufferToConsole(unsigned char *buffer, int bufLen)
ros::Publisher cloud_pub_
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.