00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #define WIN32_LEAN_AND_MEAN
00044 #include "boost/filesystem.hpp"
00045 #include <boost/regex.hpp>
00046 #include <boost/algorithm/string.hpp>
00047 #include <algorithm>
00048
00049
00050 #include <stdio.h>
00051 #include <stdlib.h>
00052 #include <string.h>
00053
00054 #include <iostream>
00055 #ifndef _MSC_VER
00056 #include <sys/wait.h>
00057 #endif
00058 #include <unistd.h>
00059 #include <cstdio>
00060 #include <cstdlib>
00061
00062
00063 #include "sick_scan/sick_generic_laser.h"
00064
00065 #include <ros/console.h>
00066
00067 #ifdef _MSC_VER
00068 #include "sick_scan/rosconsole_simu.hpp"
00069 #endif
00070
00071 #include "tinystr.h"
00072 #include "tinyxml.h"
00073
00074 #define MAX_NAME_LEN (1024)
00075
00076
00077 #define SICK_SCAN_TEST_MAJOR_VER "001"
00078 #define SICK_SCAN_TEST_MINOR_VER "000"
00079 #define SICK_SCAN_TEST_PATCH_LEVEL "000"
00080
00081
00082
00083 class paramEntryAscii
00084 {
00085 public:
00086 paramEntryAscii(std::string _nameVal, std::string _typeVal, std::string _valueVal)
00087 {
00088 nameVal = _nameVal;
00089 typeVal = _typeVal;
00090 valueVal = _valueVal;
00091 setCheckStatus(999,"untested");
00092 minMaxGiven = false;
00093 };
00094
00095 void setPointerToXmlNode(TiXmlElement *paramEntryPtr)
00096 {
00097 this->nodePtr = paramEntryPtr;
00098 }
00099
00100 TiXmlElement * getPointerToXmlNode(void)
00101 {
00102 return( this->nodePtr);
00103 }
00104 void setValues(std::string _nameVal, std::string _typeVal, std::string _valueVal)
00105 {
00106 nameVal = _nameVal;
00107 typeVal = _typeVal;
00108 valueVal = _valueVal;
00109 };
00110
00111
00112 bool isMinMaxGiven()
00113 {
00114 return(minMaxGiven);
00115 }
00116
00117 void setMinMaxValues(std::string _valueMinVal, std::string _valueMaxVal)
00118 {
00119
00120 valueMinVal = _valueMinVal;
00121 valueMaxVal = _valueMaxVal;
00122 minMaxGiven = true;
00123
00124 };
00125
00126 std::string getName()
00127 {
00128 return(nameVal);
00129 }
00130
00131 std::string getType()
00132 {
00133 return(typeVal);
00134 }
00135
00136 std::string getValue()
00137 {
00138 return(valueVal);
00139 }
00140
00141 std::string getMinValue()
00142 {
00143 return(valueMinVal);
00144 }
00145
00146 std::string getMaxValue()
00147 {
00148 return(valueMaxVal);
00149 }
00150
00151 void setCheckStatus(int errCode, std::string errMsg)
00152 {
00153 errorCode = errCode;
00154 errorMsg = errMsg;
00155 };
00156
00157 int getErrorCode()
00158 {
00159 return(errorCode);
00160 }
00161
00162 std::string getErrorMsg()
00163 {
00164 return(errorMsg);
00165 }
00166
00167 private:
00168 std::string nameVal;
00169 std::string typeVal;
00170 std::string valueVal;
00171 std::string valueMinVal;
00172 std::string valueMaxVal;
00173 bool minMaxGiven;
00174 int errorCode;
00175 std::string errorMsg;
00176 TiXmlElement *nodePtr;
00177 };
00178
00179
00180
00181
00182
00183 void sudokill(pid_t tokill)
00184 {
00185 #ifndef _MSC_VER
00186 kill(tokill, SIGTERM);
00187 #endif
00188 sleep(5);
00189 }
00190
00191 std::vector<paramEntryAscii> getParamList(TiXmlNode *paramList)
00192 {
00193 std::vector<paramEntryAscii> tmpList;
00194
00195
00196 TiXmlElement *paramEntry = (TiXmlElement *)paramList->FirstChild("param");
00197 while (paramEntry)
00198 {
00199 std::string nameVal = "";
00200 std::string typeVal = "";
00201 std::string valueVal = "";
00202 std::string minValueVal = "";
00203 std::string maxValueVal = "";
00204
00205 bool minValFnd = false;
00206 bool maxValFnd = false;
00207
00208
00209 const char *val = paramEntry->Value();
00210 bool searchAttributes = true;
00211 if (strcmp(val,"param") == 0)
00212 {
00213
00214 }
00215 else
00216 {
00217 searchAttributes = false;
00218 }
00219 if (paramEntry->Type() == TiXmlNode::TINYXML_ELEMENT)
00220 {
00221
00222 }
00223 else
00224 {
00225 searchAttributes = false;
00226 }
00227 if (searchAttributes)
00228 {
00229 for (TiXmlAttribute* node = paramEntry->FirstAttribute(); ; node = node->Next())
00230 {
00231 const char *tag = node->Name();
00232 const char *val = node->Value();
00233
00234 if (strcmp(tag, "name") == 0)
00235 {
00236 nameVal = val;
00237 }
00238 if (strcmp(tag, "type") == 0)
00239 {
00240 typeVal = val;
00241 }
00242 if (strcmp(tag, "value") == 0)
00243 {
00244 valueVal = val;
00245 }
00246 if (strcmp(tag, "valueMin") == 0)
00247 {
00248 minValFnd = true;
00249 minValueVal = val;
00250
00251 }
00252 if (strcmp(tag, "valueMax") == 0)
00253 {
00254 maxValFnd = true;
00255 maxValueVal = val;
00256 }
00257 if (node == paramEntry->LastAttribute())
00258 {
00259
00260 break;
00261 }
00262 }
00263
00264 paramEntryAscii tmpEntry(nameVal, typeVal, valueVal);
00265 if (maxValFnd && minValFnd)
00266 {
00267 tmpEntry.setMinMaxValues(minValueVal, maxValueVal);
00268 }
00269
00270 tmpEntry.setPointerToXmlNode(paramEntry);
00271 tmpList.push_back(tmpEntry);
00272 }
00273 paramEntry = (TiXmlElement *)paramEntry->NextSibling();
00274 }
00275
00276 return(tmpList);
00277 }
00278
00279
00280
00281 void replaceParamList(TiXmlNode * node, std::vector<paramEntryAscii> paramOrgList)
00282 {
00283 bool fndParam = false;
00284 do
00285 {
00286 fndParam = false;
00287 TiXmlElement *paramEntry = (TiXmlElement *)node->FirstChild("param");
00288 if (paramEntry != NULL)
00289 {
00290 fndParam = true;
00291 node->RemoveChild(paramEntry);
00292 }
00293 } while (fndParam == true);
00294
00295 for (int i = 0; i < paramOrgList.size(); i++)
00296 {
00297 paramEntryAscii tmp = paramOrgList[i];
00298 TiXmlElement *paramTmp = new TiXmlElement("param");
00299 paramTmp->SetAttribute("name", tmp.getName().c_str());
00300 paramTmp->SetAttribute("type", tmp.getType().c_str());
00301 paramTmp->SetAttribute("value", tmp.getValue().c_str());
00302 node->LinkEndChild(paramTmp);
00303 }
00304 }
00305
00306 pid_t pid;
00307
00308 pid_t launchRosFile(std::string cmdLine)
00309 {
00310 std::string cmd = cmdLine;
00311 typedef std::vector<std::string > split_vector_type;
00312
00313 split_vector_type splitVec;
00314 boost::split(splitVec, cmdLine, boost::is_any_of(" "), boost::token_compress_on);
00315
00316
00317
00318 pid_t pid = fork();
00319 int status;
00320
00321 switch (pid)
00322 {
00323 case -1:
00324 perror("fork");
00325 exit(1);
00326
00327 case 0:
00328 execl("/opt/ros/kinetic/bin/roslaunch", splitVec[0].c_str(), splitVec[1].c_str(), splitVec[2].c_str(), NULL);
00329 perror("execl");
00330 exit(1);
00331
00332 default:
00333
00334
00335
00336
00337
00338
00339
00340
00341 break;
00342
00343 }
00344
00345 return(pid);
00346 }
00347
00348
00349 int createTestLaunchFile(std::string launchFileFullName, std::vector<paramEntryAscii> entryList, std::string& testLaunchFile)
00350 {
00351 printf("Try loading launchfile :%s",launchFileFullName.c_str());
00352 TiXmlDocument doc;
00353 doc.LoadFile(launchFileFullName.c_str());
00354
00355 if (doc.Error() == true)
00356 {
00357 ROS_ERROR("ERROR parsing launch file %s\nRow: %d\nCol: %d", doc.ErrorDesc(), doc.ErrorRow(), doc.ErrorCol());
00358 return(-1);
00359 }
00360 TiXmlNode *node = doc.FirstChild("launch");
00361 if (node != NULL)
00362 {
00363 node = node->FirstChild("node");
00364 std::vector<paramEntryAscii> paramOrgList = getParamList(node);
00365 for (int i = 0; i < entryList.size(); i++)
00366 {
00367 bool replaceEntry = false;
00368 for (int j = 0; j < paramOrgList.size(); j++)
00369 {
00370 if (entryList[i].getName().compare(paramOrgList[j].getName()) == 0)
00371 {
00372 paramOrgList[j].setValues(entryList[i].getName(), entryList[i].getType(), entryList[i].getValue());
00373 replaceEntry = true;
00374 }
00375 }
00376 if (replaceEntry == false)
00377 {
00378 paramEntryAscii tmp(entryList[i].getName(), entryList[i].getType(), entryList[i].getValue());
00379 paramOrgList.push_back(tmp);
00380 }
00381 }
00382
00383 replaceParamList(node, paramOrgList);
00384 }
00385
00386
00387 size_t pos = launchFileFullName.rfind('.');
00388 std::string resultFileName = "";
00389 testLaunchFile = "";
00390 if (pos != std::string::npos)
00391 {
00392 resultFileName = launchFileFullName.substr(0, pos);
00393 resultFileName += "_test.launch";
00394 doc.SaveFile(resultFileName.c_str());
00395 testLaunchFile = resultFileName;
00396 }
00397 return(0);
00398 }
00399
00400 int cloud_width = 0;
00401 int cloud_height = 0;
00402 int callbackCnt = 0;
00403 double intensityStdDev = 0.0;
00404 double rangeStdDev = 0.0;
00405
00406
00407
00408 int callbackScanCnt = 0;
00409
00410
00411 void cloud_callback(const sensor_msgs::PointCloud2ConstPtr& cloud_msg)
00412 {
00413 static int cnt = 0;
00414 callbackCnt++;
00415 cloud_width = cloud_msg->width;
00416 cloud_height = cloud_msg->height;
00417 int intensity_idx = -1;
00418 int cartesianIdxArr[3];
00419 for (int i = 0; i < 3; i++)
00420 {
00421 cartesianIdxArr[i] = -1;
00422 }
00423
00424
00425 for (int i = 0; i < cloud_msg->fields.size(); i++)
00426 {
00427 std::string fieldName = cloud_msg->fields[i].name;
00428 if (fieldName.compare("intensity") == 0)
00429 {
00430 intensity_idx = i;
00431 }
00432 if (fieldName.compare("x") == 0)
00433 {
00434 cartesianIdxArr[0] = i;
00435 }
00436 if (fieldName.compare("y") == 0)
00437 {
00438 cartesianIdxArr[1] = i;
00439 }
00440 if (fieldName.compare("z") == 0)
00441 {
00442 cartesianIdxArr[2] = i;
00443 }
00444
00445 }
00446 if (intensity_idx != -1)
00447 {
00448 float intensitySum = 0.0;
00449 float intensity2Sum = 0.0;
00450 int intensityNum = cloud_width * cloud_height;
00451 for (int i = 0; i < cloud_height; i++)
00452 for (int j = 0; j < cloud_width; j++)
00453 {
00454 int idx = i * cloud_width + j;
00455 idx *= cloud_msg->point_step;
00456 int relOff = cloud_msg->fields[intensity_idx].offset;
00457 float *intensityPtr = (float *)(&(cloud_msg->data[idx+relOff]));
00458 float intensity = *intensityPtr;
00459 intensitySum += intensity;
00460 intensity2Sum += intensity * intensity;
00461 }
00462 if (intensityNum > 1)
00463 {
00464 intensityStdDev = (intensity2Sum - 1.0 / intensityNum * (intensitySum * intensitySum));
00465 {
00466 intensityStdDev /= (intensityNum - 1);
00467 intensityStdDev = sqrt(intensityStdDev);
00468 }
00469 }
00470 }
00471
00472 if (cartesianIdxArr[0] != -1 &&cartesianIdxArr[1] != -1 &&cartesianIdxArr[2] != -1)
00473 {
00474 float rangeSum = 0.0;
00475 float range2Sum = 0.0;
00476 int rangeNum = cloud_width * cloud_height;
00477 for (int i = 0; i < cloud_height; i++)
00478 for (int j = 0; j < cloud_width; j++)
00479 {
00480 int idx = i * cloud_width + j;
00481 idx *= cloud_msg->point_step;
00482 int relOffX = cloud_msg->fields[cartesianIdxArr[0]].offset;
00483 float *XPtr = (float *)(&(cloud_msg->data[idx+relOffX]));
00484 float X = *XPtr;
00485 int relOffY = cloud_msg->fields[cartesianIdxArr[1]].offset;
00486 float *YPtr = (float *)(&(cloud_msg->data[idx+relOffY]));
00487 float Y = *YPtr;
00488 int relOffZ = cloud_msg->fields[cartesianIdxArr[2]].offset;
00489 float *ZPtr = (float *)(&(cloud_msg->data[idx+relOffZ]));
00490 float Z = *ZPtr;
00491 float range =sqrt(X*X+Y*Y+Z*Z);
00492 rangeSum += range;
00493 range2Sum += range * range;
00494 }
00495 if (rangeNum > 1)
00496 {
00497 rangeStdDev = (range2Sum - 1.0 / rangeNum * (rangeSum * rangeSum));
00498 {
00499 rangeStdDev /= (rangeNum - 1);
00500 rangeStdDev = sqrt(intensityStdDev);
00501 }
00502 }
00503 }
00504 ROS_INFO("valid PointCloud2 message received");
00505
00506 }
00507
00508 float ERR_CONST = -1E3;
00509 float scan_angle_min = -1E3;
00510 float scan_angle_max = -1E3;
00511 float scan_time_increment = -1E3;
00512 float scan_angle_increment = -1E3;
00513 float range_min = -1E3;
00514 float range_max = -1E3;
00515
00516
00517 void processLaserScan(const sensor_msgs::LaserScan::ConstPtr& scan)
00518 {
00519 if (callbackScanCnt == 0)
00520 {
00521 scan_angle_min = scan->angle_min;
00522 scan_angle_max = scan->angle_max;
00523 scan_time_increment = scan->time_increment;
00524 scan_angle_increment = scan->angle_increment;
00525 range_min = scan->range_min;
00526 range_max = scan->range_max;
00527 }
00528 callbackScanCnt++;
00529 }
00530
00531
00532 int startCallbackTest(int argc, char** argv)
00533 {
00534
00535 ros::NodeHandle nh;
00536 ros::Rate loop_rate(10);
00537 ros::Subscriber sub;
00538 ros::Subscriber scanSub;
00539 ROS_INFO("Cloudtester started."
00540 );
00541 sub = nh.subscribe("cloud", 1, cloud_callback);
00542 scanSub=nh.subscribe<sensor_msgs::LaserScan>("/scan",10,processLaserScan);
00543
00544 while (callbackCnt < 10)
00545 {
00546 ros::spinOnce();
00547 }
00548 sub.shutdown();
00549 ros::shutdown();
00550
00551 ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug);
00552 return(0);
00553
00554 }
00555
00556
00557 void createPrefixFromExeName(std::string exeName, std::string& prefix)
00558 {
00559 #ifdef _MSC_VER
00560 #else
00561 #endif
00562 std::string searchPattern = "(.*)cmake\\-build\\-debug.*";
00563 boost::regex expr(searchPattern);
00564 boost::smatch what;
00565
00566 if (boost::regex_search(exeName, what, expr))
00567 {
00568 std::string prefixPath = what[1];
00569 prefix = prefixPath;
00570 prefix += "test";
00571 }
00572 else
00573 {
00574 prefix = ".";
00575 }
00576
00577 }
00578
00579
00580 void searchForXmlFileInPathList(std::string pathList, std::string& packagePath, std::string xmlFileName)
00581 {
00582 typedef std::vector<std::string > split_vector_type;
00583 packagePath = "???";
00584 split_vector_type splitVec;
00585 boost::split(splitVec, pathList, boost::is_any_of(":"), boost::token_compress_on);
00586 if (splitVec.size() > 0)
00587 {
00588 packagePath = splitVec[0];
00589 }
00590
00591 for (int i = 0; i < splitVec.size(); i++)
00592 {
00593 FILE *fin;
00594 std::string tmpFileName = splitVec[i] + "/" + xmlFileName;
00595 fin = fopen(tmpFileName.c_str(),"r");
00596 if (fin != NULL)
00597 {
00598 packagePath = splitVec[i];
00599 fclose(fin);
00600 }
00601 }
00602 }
00603
00604 bool getPackageRootFolder(std::string exePath, std::string& packageRootFolder)
00605 {
00606 packageRootFolder = "";
00607
00608 typedef std::vector<std::string > split_vector_type;
00609 split_vector_type splitVec;
00610 boost::split(splitVec, exePath, boost::is_any_of("/"), boost::token_compress_on);
00611 bool bFnd = false;
00612 for (int i = splitVec.size() - 1; i >= 0; i--)
00613 {
00614 std::string tmpPath = "";
00615 for (int j = 1; j < i; j++)
00616 {
00617 tmpPath += '/';
00618 tmpPath += splitVec[j];
00619 }
00620
00621 std::string fileTmpPath = tmpPath;
00622 fileTmpPath += "/package.xml";
00623 if (boost::filesystem::exists(fileTmpPath))
00624 {
00625 packageRootFolder = tmpPath;
00626 bFnd = true;
00627 break;
00628 }
00629 }
00630
00631 return(bFnd);
00632
00633 }
00634
00641 int main(int argc, char **argv)
00642 {
00643 int result = 0;
00644 char sep = boost::filesystem::path::preferred_separator;
00645 std::string prefix = ".";
00646 std::string packageRootFolder;
00647
00648 std::string exeName = argv[0];
00649
00650 if (argc == 1)
00651 {
00652 printf("Usage: %s <XML-Test-Ctrl-File>\n", exeName.c_str());
00653 printf("\n");
00654 printf("The XML-Test-Ctrl-File controls the parameter checking of various scanner types.");
00655 printf("The XML-File sick_scan_test.xml in the test-Directory shows an example of this file type.\n");
00656 exit(-1);
00657 }
00658 else
00659 {
00660 printf("Given program arguments:\n");
00661 for (int i = 0; i < argc; i++)
00662 {
00663 printf("%d: %s\n", i, argv[i]);
00664 }
00665 }
00666 #if 0
00667 createPrefixFromExeName(exeName, prefix);
00668 #ifdef _MSC_VER
00669 prefix = std::string("..") + sep + std::string("..") + sep + "test";
00670 #endif
00671 ROS_INFO("sick_scan_test V. %s.%s.%s", SICK_SCAN_TEST_MAJOR_VER, SICK_SCAN_TEST_MINOR_VER, SICK_SCAN_TEST_PATCH_LEVEL);
00672 #endif
00673
00674 ros::init(argc, argv, "cloudtester");
00675
00676 std::string nodeName = ros::this_node::getName();
00677
00678 printf("Nodename: %s\n", nodeName.c_str());
00679 bool bFnd = getPackageRootFolder(argv[0], packageRootFolder);
00680
00681 printf("Package Path: %s\n", packageRootFolder.c_str());
00682
00683 char* pPath;
00684 pPath = getenv("ROS_PACKAGE_PATH");
00685 #ifdef _MSC_VER
00686 pPath = "..\\..:\tmp";
00687 #endif
00688 if (pPath != NULL)
00689 {
00690 ROS_INFO("Current root path entries for launch file search: %s\n", pPath);
00691 }
00692 else
00693 {
00694 ROS_FATAL("Cannot find ROS_PACKAGE_PATH - please run <Workspace>/devel/setup.bash");
00695 }
00696
00697 std::string packagePath;
00698
00699 std::string testCtrlXmlFileName = argv[1];
00700 searchForXmlFileInPathList(pPath, packagePath, testCtrlXmlFileName);
00701
00702
00703
00704 boost::replace_all(testCtrlXmlFileName, "$ROS_PACKAGE_PATH", packagePath);
00705
00706
00707 testCtrlXmlFileName = packagePath + std::string(1,'/') + testCtrlXmlFileName;
00708 TiXmlDocument doc;
00709 doc.LoadFile(testCtrlXmlFileName.c_str());
00710 if (doc.Error())
00711 {
00712 ROS_ERROR("Package root folder %s", packageRootFolder.c_str());
00713 ROS_ERROR("Cannot load/parse %s", testCtrlXmlFileName.c_str());
00714 ROS_ERROR("Details: %s\n", doc.ErrorDesc());
00715 exit(-1);
00716 }
00717
00718 bool launch_only = false;
00719 boost::filesystem::path p(testCtrlXmlFileName);
00720 boost::filesystem::path parentPath = p.parent_path();
00721 std::string pathName = parentPath.string();
00722 std::string launchFilePrefix = parentPath.parent_path().string() + std::string(1, sep) + "launch" + std::string(1, sep);
00723 TiXmlNode *node = doc.FirstChild("launch");
00724 if (node == NULL)
00725 {
00726 ROS_ERROR("Cannot find tag <launch>\n");
00727 exit(-1);
00728 }
00729
00730 if (node)
00731 {
00732 TiXmlElement *fileNameEntry;
00733 fileNameEntry = (TiXmlElement *)node->FirstChild("filename");
00734 if (fileNameEntry == NULL)
00735 {
00736 ROS_ERROR("Cannot find tag <filename>\n");
00737 exit(-1);
00738 }
00739 TiXmlText *fileNameVal = (TiXmlText *)fileNameEntry->FirstChild();
00740 if (fileNameVal != NULL)
00741 {
00742 ROS_INFO("Processing launch file %s\n", fileNameVal->Value());
00743 std::string launchFileFullName = launchFilePrefix + fileNameVal->Value();
00744 ROS_INFO("Processing %s\n", launchFileFullName.c_str());
00745 TiXmlNode *paramListNode = (TiXmlNode *)node->FirstChild("paramList");
00746 if (paramListNode != NULL)
00747 {
00748 std::vector<paramEntryAscii> paramList = getParamList(paramListNode);
00749 for (int i = 0; i < paramList.size(); i++)
00750 {
00751 if (paramList[i].getName().compare("launch_only") == 0)
00752 {
00753 if (paramList[i].getValue().compare("true") == 0)
00754 {
00755 printf("launch_only set to true. Just modifying launch file and launch (without testing).");
00756 launch_only = true;
00757 }
00758 }
00759
00760
00761 }
00762
00763 std::string testLaunchFile;
00764 createTestLaunchFile(launchFileFullName, paramList, testLaunchFile);
00765 std::string commandLine;
00766 boost::filesystem::path p(testLaunchFile);
00767 std::string testOnlyLaunchFileName = p.filename().string();
00768 commandLine = "roslaunch sick_scan " + testOnlyLaunchFileName;
00769 ROS_INFO("launch ROS test ... [%s]", commandLine.c_str());
00770
00771
00772
00773 pid_t pidId = launchRosFile(commandLine.c_str());
00774
00775 if (launch_only)
00776 {
00777 printf("Launch file [ %s ] started ...\n", commandLine.c_str());
00778 printf("No further testing...\n");
00779 exit(0);
00780 }
00781 startCallbackTest(argc, argv);
00782
00783 ros::console::set_logger_level(ROSCONSOLE_DEFAULT_NAME, ros::console::levels::Debug);
00784 ROS_INFO("If you receive an error message like \"... is neither a launch file ... \""
00785 "please source ROS env. via source ./devel/setup.bash");
00786
00787
00788 TiXmlNode *resultListNode = (TiXmlNode *)node->FirstChild("resultList");
00789 if (resultListNode != NULL)
00790 {
00791 std::vector<paramEntryAscii> resultList = getParamList(resultListNode);
00792
00793 enum KeyWord_Idx {MIN_ANG_KEYWORD_IDX, MAX_ANG_KEYWORD_IDX,
00794 SCAN_TIME_INCREMENT_KEYWORD_IDX,
00795 SCAN_ANGLE_INCREMENT_KEYWORD_IDX,
00796 MIN_RANGE_KEYWORD_IDX,
00797 MAX_RANGE_KEYWORD_IDX,
00798 KEYWORD_IDX_NUM};
00799
00800 std::vector<std::string> keyWordList;
00801 keyWordList.resize(KEYWORD_IDX_NUM);
00802
00803 keyWordList[MIN_ANG_KEYWORD_IDX] = "min_ang";
00804 keyWordList[MAX_ANG_KEYWORD_IDX] = "max_ang";
00805 keyWordList[MIN_RANGE_KEYWORD_IDX] = "range_min";
00806 keyWordList[MAX_RANGE_KEYWORD_IDX] = "range_max";
00807 keyWordList[SCAN_ANGLE_INCREMENT_KEYWORD_IDX] = "angle_increment";
00808 keyWordList[SCAN_TIME_INCREMENT_KEYWORD_IDX] = "time_increment";
00809
00810 for (int i = 0; i < resultList.size(); i++)
00811 {
00812
00813 for (int ki = 0; ki < keyWordList.size(); ki++)
00814 {
00815
00816 float measurementVal = .0F;
00817 std::string keyWordTag = keyWordList[ki];
00818
00819 switch(ki)
00820 {
00821 case MIN_ANG_KEYWORD_IDX: measurementVal = scan_angle_min; break;
00822 case MAX_ANG_KEYWORD_IDX: measurementVal = scan_angle_max; break;
00823 case SCAN_ANGLE_INCREMENT_KEYWORD_IDX: measurementVal = scan_angle_increment; break;
00824 case SCAN_TIME_INCREMENT_KEYWORD_IDX: measurementVal = scan_time_increment; break;
00825 case MIN_RANGE_KEYWORD_IDX: measurementVal = range_min; break;
00826 case MAX_RANGE_KEYWORD_IDX: measurementVal = range_max; break;
00827 default: printf("Did not find a correspondence for index %d\n", ki); break;
00828 }
00829 char errMsg[255] = {0};
00830 if (keyWordTag.compare("min_ang") == 0)
00831 {
00832 measurementVal = scan_angle_min;
00833 }
00834 if (resultList[i].getName().compare(keyWordTag) == 0)
00835 {
00836
00837 enum Expected_Idx {MIN_EXP_IDX, DEF_EXP_IDX, MAX_EXP_IDX, EXP_IDX_NUM};
00838 float expectedValues[EXP_IDX_NUM];
00839 std::string valString;
00840
00841 for (int j = 0; j < EXP_IDX_NUM; j++)
00842 {
00843 switch(j)
00844 {
00845 case MIN_EXP_IDX: valString = resultList[i].getMinValue(); break;
00846 case DEF_EXP_IDX: valString = resultList[i].getValue(); break;
00847 case MAX_EXP_IDX: valString = resultList[i].getMaxValue(); break;
00848 default: ROS_ERROR("Check index"); break;
00849
00850 }
00851
00852 const char *valPtr = valString.c_str();
00853 if (valPtr != NULL)
00854 {
00855 float tmpVal = .0F;
00856 sscanf(valPtr, "%f", &tmpVal);
00857 expectedValues[j] = tmpVal;
00858 }
00859 }
00860 valString = resultList[i].getMinValue();
00861
00862 int errorCode = 0;
00863 std::string resultStr = "FAILED";
00864 std::string appendResultStr = " <-----";
00865 if ( (measurementVal >= expectedValues[MIN_EXP_IDX]) && (measurementVal <= expectedValues[MAX_EXP_IDX]))
00866 {
00867 appendResultStr = "";
00868 resultStr = "PASSED";
00869 errorCode = 0;
00870 }
00871 else
00872 {
00873 errorCode = 1;
00874 }
00875 sprintf(errMsg, "CHECK %s! Key: %-20s %14.9f in [%14.9f,%14.9f] %s", resultStr.c_str(), keyWordTag.c_str(), measurementVal,
00876 expectedValues[MIN_EXP_IDX], expectedValues[MAX_EXP_IDX], appendResultStr.c_str());
00877
00878 printf("%s\n", errMsg);
00879 resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? "OK" : errMsg);
00880
00881 }
00882 }
00883
00884
00885 if (resultList[i].getName().compare("shotsPerLayer") == 0)
00886 {
00887 int expectedWidth = -1;
00888 std::string valString = resultList[i].getValue();
00889 const char *valPtr = valString.c_str();
00890 if (valPtr != NULL)
00891 {
00892 sscanf(valPtr, "%d", &expectedWidth);
00893 }
00894
00895
00896 ROS_INFO("Test\n");
00897 int errorCode = 0;
00898 if (expectedWidth == cloud_width)
00899 {
00900 printf("CHECK PASSED! WIDTH %d == %d\n", expectedWidth, cloud_width);
00901 errorCode = 0;
00902 }
00903 else
00904 {
00905 printf("CHECK FAILED! WIDTH %d <> %d\n", expectedWidth, cloud_width);
00906 errorCode = 1;
00907
00908 }
00909 resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? "OK" : "Unexpected number of shots");
00910
00911 }
00912 if (resultList[i].getName().compare("pointCloud2Height") == 0)
00913 {
00914 int expectedHeight = -1;
00915 std::string valString = resultList[i].getValue();
00916 const char *valPtr = valString.c_str();
00917 if (valPtr != NULL)
00918 {
00919 sscanf(valPtr, "%d", &expectedHeight);
00920 }
00921 ROS_INFO("Test\n");
00922 int errorCode = 0;
00923 if (expectedHeight == cloud_height)
00924 {
00925 printf("CHECK PASSED! HEIGHT %d == %d\n", expectedHeight, cloud_height);
00926 errorCode = 0;
00927 }
00928 else
00929 {
00930 printf("CHECK FAILED! HEIGHT %d <> %d\n", expectedHeight, cloud_height);
00931 errorCode = 1;
00932 }
00933 resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? "OK" : "Unexpected pointCloud2 height");
00934 cloud_height = 0;
00935 }
00936
00937 if (resultList[i].getName().compare("RSSIEnabled") == 0)
00938 {
00939 int expectedWidth = -1;
00940 std::string valString = resultList[i].getValue();
00941 bool rssiEnabled = false;
00942 if (boost::iequals(valString, "true"))
00943 {
00944 rssiEnabled = true;
00945 } else if (boost::iequals(valString, "false"))
00946 {
00947 rssiEnabled = false;
00948 } else
00949 {
00950 ROS_WARN("RSSIEnabled parameter wrong. True or False are valid parameters!\n");
00951 }
00952
00953 ROS_INFO("Test\n");
00954 int errorCode = 0;
00955 if (rssiEnabled == true)
00956 {
00957 if (intensityStdDev >= 1e-5)
00958 {
00959 printf("CHECK PASSED! RSSI Standard deviation %.3e is not 0.\n",intensityStdDev);
00960 errorCode = 0;
00961 } else
00962 {
00963 printf("CHECK FAILED! RSSI standard deviation is samller than %.10e even though RSSI is enabled\n",intensityStdDev);
00964 errorCode = 1;
00965
00966 }
00967 }
00968
00969 if (rssiEnabled == false)
00970 {
00971 if (intensityStdDev <= 1e-5)
00972 {
00973 printf("CHECK FAILED! RSSI standard deviation %.3e is bigger than 1e-5 even though RSSI is disabled\n",intensityStdDev);
00974 errorCode = 1;
00975 } else
00976 {
00977 printf("CHECK PASSED! RSSI Standard deviation %.3e is smaller than 1e-5.\n",intensityStdDev);
00978 errorCode = 0;
00979
00980 }
00981 }
00982 }
00983 if (resultList[i].getName().compare("ranges") == 0)
00984 {
00985 int expectedWidth = -1;
00986 std::string valString = resultList[i].getValue();
00987 bool rangeTest=false;
00988 if (boost::iequals(valString, "true"))
00989 {
00990 rangeTest=true;
00991 }
00992 else
00993 {
00994 ROS_WARN("ranges parameter wrong. True or False are valid parameters!\n");
00995 }
00996
00997 ROS_INFO("Test\n");
00998 int errorCode = 0;
00999 if (rangeTest==true)
01000 {
01001 if (rangeStdDev >= 1e-5)
01002 {
01003 printf("CHECK PASSED! Range Standard deviation %.3e is not 0.\n", rangeStdDev);
01004 errorCode = 0;
01005 }
01006 else
01007 {
01008 printf("CHECK FAILED! Range standard deviation %.3e is smaller than 1e-5!\n", rangeStdDev);
01009 errorCode = 1;
01010
01011 }
01012 resultList[i].setCheckStatus(errorCode, (errorCode == 0) ? "OK" : "Range standard deviation is 0 !\n");
01013 }
01014
01015
01016 }
01017 TiXmlElement *paramSet = resultList[i].getPointerToXmlNode();
01018 paramSet->SetAttribute("errorCode", resultList[i].getErrorCode());
01019 paramSet->SetAttribute("errorMsg", resultList[i].getErrorMsg().c_str());
01020 }
01021
01022 }
01023
01024 printf("Killing process %d\n", pidId);
01025 sudokill(pidId);
01026
01027 std::string testCtrlResultXmlFileName = "";
01028 size_t pos = testCtrlXmlFileName.rfind('.');
01029 if (pos != std::string::npos)
01030 {
01031 boost::filesystem::path tmpFilePath =testCtrlXmlFileName.substr(0,pos);
01032 boost::filesystem::path xmlDir= tmpFilePath.parent_path();
01033 std::string xmlDirName = xmlDir.string();
01034 xmlDirName.append("/results");
01035 if (boost::filesystem::exists(xmlDirName))
01036 {
01037
01038 }
01039 else
01040 {
01041 boost::filesystem::create_directory(xmlDirName);
01042 }
01043 std::string tmpFilNamewoExtension= tmpFilePath.stem().string();
01044 std::string resultFileName=xmlDir.string();
01045 resultFileName.append("/");
01046 resultFileName.append(tmpFilNamewoExtension);
01047 resultFileName.append(".res");
01048 printf("Save to %s\n", resultFileName.c_str());
01049 doc.SaveFile(resultFileName.c_str());
01050 }
01051
01052 }
01053 }
01054 else
01055 {
01056 ROS_WARN("Cannot find filename entry");
01057 }
01058
01059
01060 }
01061 return result;
01062
01063 }
01064