43 #define WIN32_LEAN_AND_MEAN 
   44 #include "boost/filesystem.hpp" 
   45 #include <boost/regex.hpp> 
   46 #include <boost/algorithm/string.hpp> 
   68 #include "sick_scan/rosconsole_simu.hpp" 
   74 #define MAX_NAME_LEN (1024) 
   77 #define SICK_SCAN_TEST_MAJOR_VER "001" 
   78 #define SICK_SCAN_TEST_MINOR_VER "000"   
   79 #define SICK_SCAN_TEST_PATCH_LEVEL "000" 
   86         paramEntryAscii(std::string _nameVal, std::string _typeVal, std::string _valueVal)
 
  104         void setValues(std::string _nameVal, std::string _typeVal, std::string _valueVal)
 
  186   kill(tokill, SIGTERM);
 
  193         std::vector<paramEntryAscii> tmpList;
 
  199                 std::string nameVal = 
"";
 
  200                 std::string typeVal = 
"";
 
  201                 std::string valueVal = 
"";
 
  202     std::string minValueVal = 
"";
 
  203     std::string maxValueVal = 
"";
 
  205     bool minValFnd = 
false;
 
  206     bool maxValFnd = 
false;
 
  209                 const char *val = paramEntry->
Value();
 
  210                 bool searchAttributes = 
true;
 
  211                 if (strcmp(val,
"param") == 0)
 
  217                         searchAttributes = 
false;
 
  225                         searchAttributes = 
false;
 
  227                 if (searchAttributes)
 
  231                         const char *tag = node->Name();
 
  232                         const char *val = node->Value();
 
  234                         if (strcmp(tag, 
"name") == 0)
 
  238                         if (strcmp(tag, 
"type") == 0)
 
  242                         if (strcmp(tag, 
"value") == 0)
 
  246       if (strcmp(tag, 
"valueMin") == 0)
 
  252       if (strcmp(tag, 
"valueMax") == 0)
 
  265     if (maxValFnd && minValFnd)
 
  271                 tmpList.push_back(tmpEntry);
 
  283         bool fndParam = 
false;
 
  288                 if (paramEntry != NULL)
 
  293         } 
while (fndParam == 
true);
 
  295         for (
int i = 0; i < paramOrgList.size(); i++)
 
  310   std::string 
cmd = cmdLine;
 
  311   typedef std::vector<std::string > split_vector_type;
 
  313   split_vector_type splitVec; 
 
  314   boost::split(splitVec, cmdLine, boost::is_any_of(
" "), boost::token_compress_on); 
 
  328       execl(
"/opt/ros/kinetic/bin/roslaunch", splitVec[0].c_str(), splitVec[1].c_str(),  splitVec[2].c_str(), NULL); 
 
  349 int createTestLaunchFile(std::string launchFileFullName, std::vector<paramEntryAscii> entryList, std::string& testLaunchFile)
 
  351         printf(
"Try loading launchfile :%s",launchFileFullName.c_str());
 
  353         doc.
LoadFile(launchFileFullName.c_str());
 
  355         if (doc.
Error() == 
true)
 
  364                 std::vector<paramEntryAscii> paramOrgList = 
getParamList(node);
 
  365                 for (
int i = 0; i < entryList.size(); i++)
 
  367                         bool replaceEntry = 
false;
 
  368                         for (
int j = 0; j < paramOrgList.size(); j++)
 
  370                                 if (entryList[i].
getName().compare(paramOrgList[j].
getName()) == 0)
 
  372                                         paramOrgList[j].setValues(entryList[i].
getName(), entryList[i].getType(), entryList[i].getValue());
 
  376                         if (replaceEntry == 
false)  
 
  379                                 paramOrgList.push_back(tmp);
 
  387         size_t pos = launchFileFullName.rfind(
'.');
 
  388         std::string resultFileName = 
"";
 
  390         if (pos != std::string::npos)
 
  392                 resultFileName = launchFileFullName.substr(0, pos);
 
  393                 resultFileName += 
"_test.launch";
 
  394                 doc.
SaveFile(resultFileName.c_str());
 
  395                 testLaunchFile = resultFileName;
 
  417         int intensity_idx = -1;
 
  418         int cartesianIdxArr[3];
 
  419         for (
int i = 0; i < 3; i++)
 
  421                 cartesianIdxArr[i] = -1;
 
  425         for (
int i = 0; i < cloud_msg->fields.size(); i++)
 
  427                 std::string fieldName =         cloud_msg->fields[i].name;
 
  428                 if (fieldName.compare(
"intensity") == 0)
 
  432                 if (fieldName.compare(
"x") == 0)
 
  434                         cartesianIdxArr[0] = i;
 
  436                 if (fieldName.compare(
"y") == 0)
 
  438                         cartesianIdxArr[1] = i;
 
  440                 if (fieldName.compare(
"z") == 0)
 
  442                         cartesianIdxArr[2] = i;
 
  446         if (intensity_idx != -1)
 
  448                 float intensitySum = 0.0;
 
  449                 float intensity2Sum = 0.0;
 
  455                         idx *= cloud_msg->point_step;  
 
  456                         int relOff = cloud_msg->fields[intensity_idx].offset;
 
  457                         float *intensityPtr = (
float *)(&(cloud_msg->data[idx+relOff]));
 
  458                         float intensity = *intensityPtr;
 
  459                         intensitySum += intensity;
 
  460                         intensity2Sum += intensity * intensity;
 
  462                 if (intensityNum > 1)
 
  464                         intensityStdDev = (intensity2Sum - 1.0 / intensityNum * (intensitySum * intensitySum));
 
  472         if (cartesianIdxArr[0] != -1 &&cartesianIdxArr[1] != -1 &&cartesianIdxArr[2] != -1)
 
  474                 float rangeSum = 0.0;
 
  475                 float range2Sum = 0.0;
 
  481                                 idx *= cloud_msg->point_step;  
 
  482                                 int relOffX = cloud_msg->fields[cartesianIdxArr[0]].offset;
 
  483                                 float *XPtr = (
float *)(&(cloud_msg->data[idx+relOffX]));
 
  485                                 int relOffY = cloud_msg->fields[cartesianIdxArr[1]].offset;
 
  486                                 float *YPtr = (
float *)(&(cloud_msg->data[idx+relOffY]));
 
  488                                 int relOffZ = cloud_msg->fields[cartesianIdxArr[2]].offset;
 
  489                                 float *ZPtr = (
float *)(&(cloud_msg->data[idx+relOffZ]));
 
  491                                 float range =sqrt(X*X+Y*Y+Z*Z);
 
  493                                 range2Sum += range * range;
 
  497                         rangeStdDev = (range2Sum - 1.0 / rangeNum * (rangeSum * rangeSum));
 
  504         ROS_INFO(
"valid PointCloud2 message received");
 
  562         std::string searchPattern = 
"(.*)cmake\\-build\\-debug.*";
 
  563         boost::regex expr(searchPattern);
 
  566         if (boost::regex_search(exeName, what, expr))
 
  568                 std::string prefixPath = what[1];  
 
  582         typedef std::vector<std::string > split_vector_type;
 
  584         split_vector_type splitVec; 
 
  585         boost::split(splitVec, pathList, boost::is_any_of(
":"), boost::token_compress_on); 
 
  586         if (splitVec.size() > 0)
 
  588                 packagePath = splitVec[0];
 
  591         for (
int i = 0; i < splitVec.size(); i++)
 
  594                 std::string tmpFileName = splitVec[i] + 
"/" + xmlFileName;
 
  595                 fin = fopen(tmpFileName.c_str(),
"r");
 
  598                         packagePath = splitVec[i];
 
  606          packageRootFolder = 
"";
 
  608         typedef std::vector<std::string > split_vector_type;
 
  609         split_vector_type splitVec; 
 
  610         boost::split(splitVec, exePath, boost::is_any_of(
"/"), boost::token_compress_on); 
 
  612         for (
int i = splitVec.size() - 1; i >= 0; i--)  
 
  614                 std::string tmpPath = 
"";
 
  615                 for (
int j = 1; j < i; j++)
 
  618                         tmpPath += splitVec[j];
 
  621                 std::string fileTmpPath = tmpPath;
 
  622                 fileTmpPath += 
"/package.xml";
 
  623                 if (boost::filesystem::exists(fileTmpPath))
 
  625                         packageRootFolder = tmpPath;
 
  641 int main(
int argc, 
char **argv)
 
  644         char sep = boost::filesystem::path::preferred_separator;
 
  645         std::string prefix = 
".";
 
  646         std::string packageRootFolder;
 
  648         std::string exeName = argv[0];
 
  652     printf(
"Usage: %s <XML-Test-Ctrl-File>\n", exeName.c_str());
 
  654     printf(
"The XML-Test-Ctrl-File controls the parameter checking of various scanner types.");
 
  655     printf(
"The XML-File sick_scan_test.xml in the test-Directory shows an example of this file type.\n");
 
  660     printf(
"Given program arguments:\n");
 
  661       for (
int i = 0; i < argc; i++)
 
  663           printf(
"%d: %s\n", i, argv[i]);
 
  669         prefix = std::string(
"..") + sep + std::string(
"..") + sep + 
"test";
 
  678         printf(
"Nodename:  %s\n", nodeName.c_str());
 
  681         printf(
"Package Path: %s\n", packageRootFolder.c_str());
 
  684         pPath = getenv(
"ROS_PACKAGE_PATH");
 
  686         pPath = 
"..\\..:\tmp";
 
  690                 ROS_INFO(
"Current root path entries for launch file search: %s\n", pPath);
 
  694                 ROS_FATAL(
"Cannot find ROS_PACKAGE_PATH - please run <Workspace>/devel/setup.bash");
 
  697         std::string packagePath;
 
  699   std::string testCtrlXmlFileName = argv[1];
 
  704   boost::replace_all(testCtrlXmlFileName, 
"$ROS_PACKAGE_PATH", packagePath);
 
  707         testCtrlXmlFileName = packagePath + std::string(1,
'/') + testCtrlXmlFileName;
 
  709         doc.
LoadFile(testCtrlXmlFileName.c_str());
 
  712                 ROS_ERROR(
"Package root folder %s", packageRootFolder.c_str());
 
  713                 ROS_ERROR(
"Cannot load/parse %s", testCtrlXmlFileName.c_str());
 
  718   bool launch_only = 
false;
 
  719         boost::filesystem::path p(testCtrlXmlFileName);
 
  720         boost::filesystem::path parentPath = p.parent_path();
 
  721         std::string pathName = parentPath.string();
 
  722         std::string launchFilePrefix = parentPath.parent_path().string() + std::string(1, sep) + 
"launch" + std::string(1, sep);
 
  734                 if (fileNameEntry == NULL)
 
  736                         ROS_ERROR(
"Cannot find tag <filename>\n");
 
  740                 if (fileNameVal != NULL)
 
  742                         ROS_INFO(
"Processing launch file %s\n", fileNameVal->
Value());
 
  743                         std::string launchFileFullName = launchFilePrefix + fileNameVal->
Value();
 
  744                         ROS_INFO(
"Processing %s\n", launchFileFullName.c_str());
 
  746                         if (paramListNode != NULL)
 
  748                                 std::vector<paramEntryAscii> paramList = 
getParamList(paramListNode);
 
  749         for (
int i = 0; i < paramList.size(); i++)
 
  751           if (paramList[i].
getName().compare(
"launch_only") == 0)
 
  753             if (paramList[i].getValue().compare(
"true") == 0)
 
  755               printf(
"launch_only set to true. Just modifying launch file and launch (without testing).");
 
  763         std::string testLaunchFile;
 
  765                                 std::string commandLine;
 
  766                                 boost::filesystem::path p(testLaunchFile);
 
  767                                 std::string testOnlyLaunchFileName = p.filename().string();
 
  768                                 commandLine = 
"roslaunch sick_scan " + testOnlyLaunchFileName;
 
  769                                 ROS_INFO(
"launch ROS test ... [%s]", commandLine.c_str());
 
  777           printf(
"Launch file [ %s ] started ...\n", commandLine.c_str());
 
  778           printf(
"No further testing...\n");
 
  784                                 ROS_INFO(
"If you receive an error message like \"... is neither a launch file ... \"" 
  785                                         "please source ROS env. via source ./devel/setup.bash");
 
  789                                 if (resultListNode != NULL)
 
  791                                         std::vector<paramEntryAscii> resultList = 
getParamList(resultListNode);
 
  793           enum KeyWord_Idx {MIN_ANG_KEYWORD_IDX, MAX_ANG_KEYWORD_IDX,
 
  794               SCAN_TIME_INCREMENT_KEYWORD_IDX,
 
  795               SCAN_ANGLE_INCREMENT_KEYWORD_IDX,
 
  796               MIN_RANGE_KEYWORD_IDX,
 
  797               MAX_RANGE_KEYWORD_IDX,
 
  800           std::vector<std::string> keyWordList;
 
  801           keyWordList.resize(KEYWORD_IDX_NUM);
 
  803           keyWordList[MIN_ANG_KEYWORD_IDX] = 
"min_ang";
 
  804           keyWordList[MAX_ANG_KEYWORD_IDX] = 
"max_ang";
 
  805           keyWordList[MIN_RANGE_KEYWORD_IDX] = 
"range_min";
 
  806           keyWordList[MAX_RANGE_KEYWORD_IDX] = 
"range_max";
 
  807           keyWordList[SCAN_ANGLE_INCREMENT_KEYWORD_IDX] = 
"angle_increment";
 
  808           keyWordList[SCAN_TIME_INCREMENT_KEYWORD_IDX] = 
"time_increment";
 
  810                                         for (
int i = 0; i < resultList.size(); i++)
 
  813             for (
int ki = 0; ki < keyWordList.size(); ki++)
 
  816             float measurementVal = .0F;
 
  817             std::string keyWordTag = keyWordList[ki];
 
  825               case   MIN_RANGE_KEYWORD_IDX: measurementVal = 
range_min; 
break;
 
  826               case   MAX_RANGE_KEYWORD_IDX: measurementVal = 
range_max; 
break;
 
  827               default: printf(
"Did not find a correspondence for index %d\n", ki); 
break;
 
  829             char errMsg[255] = {0};
 
  830             if (keyWordTag.compare(
"min_ang") == 0)
 
  834             if (resultList[i].
getName().compare(keyWordTag) == 0)
 
  837               enum Expected_Idx {MIN_EXP_IDX, DEF_EXP_IDX, MAX_EXP_IDX, EXP_IDX_NUM};
 
  838               float expectedValues[EXP_IDX_NUM];
 
  839               std::string valString;
 
  841               for (
int j = 0; j < EXP_IDX_NUM; j++)
 
  845                   case MIN_EXP_IDX:  valString = resultList[i].getMinValue(); 
break;
 
  846                   case DEF_EXP_IDX:  valString = resultList[i].getValue(); 
break;
 
  847                   case MAX_EXP_IDX:  valString = resultList[i].getMaxValue(); 
break;
 
  848                   default: 
ROS_ERROR(
"Check index"); 
break;
 
  852                 const char *valPtr = valString.c_str();
 
  856                   sscanf(valPtr, 
"%f", &tmpVal);
 
  857                   expectedValues[j] = tmpVal;
 
  860               valString = resultList[i].getMinValue();
 
  863               std::string resultStr = 
"FAILED";
 
  864               std::string appendResultStr = 
" <-----";
 
  865               if ( (measurementVal >=  expectedValues[MIN_EXP_IDX]) && (measurementVal <=  expectedValues[MAX_EXP_IDX]))
 
  867                 appendResultStr = 
"";
 
  868                 resultStr = 
"PASSED";
 
  875               sprintf(errMsg, 
"CHECK %s! Key: %-20s %14.9f in [%14.9f,%14.9f] %s", resultStr.c_str(), keyWordTag.c_str(), measurementVal,
 
  876                       expectedValues[MIN_EXP_IDX], expectedValues[MAX_EXP_IDX], appendResultStr.c_str());
 
  878               printf(
"%s\n", errMsg);
 
  879               resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? 
"OK" : errMsg);
 
  885             if (resultList[i].
getName().compare(
"shotsPerLayer") == 0)
 
  887                                                         int expectedWidth = -1;
 
  888                                                         std::string valString = resultList[i].getValue();
 
  889                                                         const char *valPtr = valString.c_str();
 
  892                                                                 sscanf(valPtr, 
"%d", &expectedWidth);
 
  900                                                                 printf(
"CHECK PASSED! WIDTH %d == %d\n", expectedWidth, 
cloud_width);
 
  905                 printf(
"CHECK FAILED! WIDTH %d <> %d\n", expectedWidth, 
cloud_width);
 
  909               resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? 
"OK" : 
"Unexpected number of shots");
 
  912                                                 if (resultList[i].
getName().compare(
"pointCloud2Height") == 0)
 
  914                 int expectedHeight = -1;
 
  915                 std::string valString = resultList[i].getValue();
 
  916                 const char *valPtr = valString.c_str();
 
  919                   sscanf(valPtr, 
"%d", &expectedHeight);
 
  925                   printf(
"CHECK PASSED! HEIGHT %d == %d\n", expectedHeight, 
cloud_height);
 
  930                   printf(
"CHECK FAILED! HEIGHT %d <> %d\n", expectedHeight, 
cloud_height);
 
  933                 resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? 
"OK" : 
"Unexpected pointCloud2 height");
 
  937             if (resultList[i].
getName().compare(
"RSSIEnabled") == 0)
 
  939               int expectedWidth = -1;
 
  940               std::string valString = resultList[i].getValue();
 
  941               bool rssiEnabled = 
false;
 
  942               if (boost::iequals(valString, 
"true"))
 
  945               } 
else if (boost::iequals(valString, 
"false"))
 
  950                 ROS_WARN(
"RSSIEnabled parameter wrong. True or False are valid parameters!\n");
 
  955               if (rssiEnabled == 
true)
 
  959                   printf(
"CHECK PASSED! RSSI Standard deviation %.3e is not 0.\n",
intensityStdDev);
 
  963                   printf(
"CHECK FAILED!  RSSI standard deviation is samller than %.10e even though RSSI is enabled\n",
intensityStdDev);
 
  969               if (rssiEnabled == 
false)
 
  973                   printf(
"CHECK FAILED! RSSI standard deviation %.3e is bigger than 1e-5 even though RSSI is disabled\n",
intensityStdDev);
 
  977                   printf(
"CHECK PASSED!  RSSI Standard deviation %.3e is smaller than 1e-5.\n",
intensityStdDev);
 
  983               if (resultList[i].
getName().compare(
"ranges") == 0)
 
  985                 int expectedWidth = -1;
 
  986                 std::string valString = resultList[i].getValue();
 
  987                 bool rangeTest=
false;
 
  988                 if (boost::iequals(valString, 
"true"))
 
  994                   ROS_WARN(
"ranges parameter wrong. True or False are valid parameters!\n");
 
 1003                     printf(
"CHECK PASSED! Range Standard deviation %.3e is not 0.\n", 
rangeStdDev);
 
 1008                     printf(
"CHECK FAILED!  Range standard deviation %.3e is smaller than 1e-5!\n", 
rangeStdDev);
 
 1012                   resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? 
"OK" : 
"Range standard deviation is 0 !\n");
 
 1017             TiXmlElement *paramSet = resultList[i].getPointerToXmlNode();
 
 1018             paramSet->
SetAttribute(
"errorCode", resultList[i].getErrorCode());
 
 1019             paramSet->
SetAttribute(
"errorMsg", resultList[i].getErrorMsg().c_str());
 
 1024         printf(
"Killing process %d\n", pidId);
 
 1027         std::string testCtrlResultXmlFileName = 
"";
 
 1028         size_t pos = testCtrlXmlFileName.rfind(
'.');
 
 1029         if (pos != std::string::npos)
 
 1031           boost::filesystem::path tmpFilePath =testCtrlXmlFileName.substr(0,pos);
 
 1032           boost::filesystem::path xmlDir= tmpFilePath.parent_path();
 
 1033                                         std::string xmlDirName = xmlDir.string();
 
 1034                                         xmlDirName.append(
"/results");
 
 1035           if (boost::filesystem::exists(xmlDirName))
 
 1041             boost::filesystem::create_directory(xmlDirName);
 
 1043           std::string tmpFilNamewoExtension= tmpFilePath.stem().string();
 
 1044           std::string resultFileName=xmlDir.string();
 
 1045           resultFileName.append(
"/");
 
 1046           resultFileName.append(tmpFilNamewoExtension);
 
 1047           resultFileName.append(
".res");
 
 1048           printf(
"Save to %s\n", resultFileName.c_str());
 
 1049           doc.
SaveFile(resultFileName.c_str());
 
 1056                         ROS_WARN(
"Cannot find filename entry");