69 UFATAL(
"Can't get the HOME variable environment!");
76 return RTABMAP_VERSION;
87 std::stringstream output;
88 for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
90 if(iter != parameters.begin())
95 output << iter->first <<
":" <<
uReplaceChar(iter->second,
',',
'.');
97 UDEBUG(
"output=%s", output.str().c_str());
103 UDEBUG(
"parameters=%s", parameters.c_str());
105 std::list<std::string> tuplets =
uSplit(parameters,
';');
106 for(std::list<std::string>::iterator iter=tuplets.begin(); iter!=tuplets.end(); ++iter)
108 std::list<std::string> p =
uSplit(*iter,
':');
111 std::string key = p.front();
112 std::string value = p.back();
115 bool addParameter =
true;
119 addParameter = oldIter->second.first;
122 key = oldIter->second.second;
123 UWARN(
"Parameter migration from \"%s\" to \"%s\" (value=%s).",
124 oldIter->first.c_str(), oldIter->second.second.c_str(), value.c_str());
126 else if(oldIter->second.second.empty())
128 UWARN(
"Parameter \"%s\" doesn't exist anymore.",
129 oldIter->first.c_str());
133 UWARN(
"Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
142 UWARN(
"Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
152 std::string group =
uSplit(parameter,
'/').front();
153 return group.compare(
"SURF") == 0 ||
154 group.compare(
"SIFT") == 0 ||
155 group.compare(
"ORB") == 0 ||
156 group.compare(
"FAST") == 0 ||
157 group.compare(
"FREAK") == 0 ||
158 group.compare(
"BRIEF") == 0 ||
159 group.compare(
"GFTT") == 0 ||
160 group.compare(
"BRISK") == 0 ||
161 group.compare(
"KAZE") == 0;
168 for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
170 std::string group =
uSplit(iter->first,
'/').front();
172 (stereo && group.compare(
"Stereo") == 0) ||
173 (icp && group.compare(
"Icp") == 0) ||
175 group.compare(
"Reg") == 0 ||
176 (vis && group.compare(
"Vis") == 0) ||
177 iter->first.compare(kRtabmapPublishRAMUsage())==0)
181 if(iter->first.compare(Parameters::kVisEstimationType()) == 0)
186 odomParameters.insert(*iter);
189 return odomParameters;
196 for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
199 std::string group =
uSplit(iter->first,
'/').front();
200 if(group.compare(groupIn) == 0)
202 parameters.insert(*iter);
205 UASSERT_MSG(parameters.size(),
uFormat(
"No parameters found for group %s!", groupIn.c_str()).c_str());
212 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
215 std::string group =
uSplit(iter->first,
'/').front();
216 if(group.compare(groupIn) == 0)
218 output.insert(*iter);
231 removedParameters_.insert(std::make_pair(
"Grid/OctoMapOccupancyThr", std::make_pair(
true, Parameters::kGridGlobalOccupancyThr())));
234 removedParameters_.insert(std::make_pair(
"Grid/Scan2dMaxFilledRange", std::make_pair(
false, Parameters::kGridRangeMax())));
237 removedParameters_.insert(std::make_pair(
"Grid/ProjRayTracing", std::make_pair(
true, Parameters::kGridRayTracing())));
238 removedParameters_.insert(std::make_pair(
"Grid/DepthMin", std::make_pair(
true, Parameters::kGridRangeMin())));
239 removedParameters_.insert(std::make_pair(
"Grid/DepthMax", std::make_pair(
true, Parameters::kGridRangeMax())));
242 removedParameters_.insert(std::make_pair(
"Reg/VarianceFromInliersCount", std::make_pair(
false,
"")));
243 removedParameters_.insert(std::make_pair(
"Reg/VarianceNormalized", std::make_pair(
false,
"")));
246 removedParameters_.insert(std::make_pair(
"Icp/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
250 removedParameters_.insert(std::make_pair(
"Rtabmap/VhStrategy", std::make_pair(
true, Parameters::kVhEpEnabled())));
253 removedParameters_.insert(std::make_pair(
"Grid/FullUpdate", std::make_pair(
true, Parameters::kGridGlobalFullUpdate())));
256 removedParameters_.insert(std::make_pair(
"Grid/3DGroundIsObstacle", std::make_pair(
true, Parameters::kGridGroundIsObstacle())));
259 removedParameters_.insert(std::make_pair(
"Optimizer/Slam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
260 removedParameters_.insert(std::make_pair(
"OdomF2M/FixedMapPath", std::make_pair(
false,
"")));
263 removedParameters_.insert(std::make_pair(
"Grid/FlatObstaclesDetected", std::make_pair(
true, Parameters::kGridFlatObstacleDetected())));
266 removedParameters_.insert(std::make_pair(
"Reg/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
267 removedParameters_.insert(std::make_pair(
"OdomF2M/ScanSubstractRadius", std::make_pair(
true, Parameters::kOdomF2MScanSubtractRadius())));
270 removedParameters_.insert(std::make_pair(
"RGBD/ProximityPathScansMerged", std::make_pair(
false,
"")));
273 removedParameters_.insert(std::make_pair(
"Mem/ImageDecimation", std::make_pair(
true, Parameters::kMemImagePostDecimation())));
276 removedParameters_.insert(std::make_pair(
"OdomLocalMap/HistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
277 removedParameters_.insert(std::make_pair(
"OdomLocalMap/FixedMapPath", std::make_pair(
false,
"")));
278 removedParameters_.insert(std::make_pair(
"OdomF2F/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
279 removedParameters_.insert(std::make_pair(
"OdomF2F/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
282 removedParameters_.insert(std::make_pair(
"OdomBow/LocalHistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
283 removedParameters_.insert(std::make_pair(
"OdomBow/FixedLocalMapPath", std::make_pair(
false,
"")));
284 removedParameters_.insert(std::make_pair(
"OdomFlow/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
285 removedParameters_.insert(std::make_pair(
"OdomFlow/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
287 removedParameters_.insert(std::make_pair(
"Kp/WordsPerImage", std::make_pair(
true, Parameters::kKpMaxFeatures())));
289 removedParameters_.insert(std::make_pair(
"Mem/LocalSpaceLinksKeptInWM", std::make_pair(
false,
"")));
291 removedParameters_.insert(std::make_pair(
"RGBD/PoseScanMatching", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
293 removedParameters_.insert(std::make_pair(
"Odom/ParticleFiltering", std::make_pair(
false, Parameters::kOdomFilteringStrategy())));
294 removedParameters_.insert(std::make_pair(
"Odom/FeatureType", std::make_pair(
true, Parameters::kVisFeatureType())));
295 removedParameters_.insert(std::make_pair(
"Odom/EstimationType", std::make_pair(
true, Parameters::kVisEstimationType())));
296 removedParameters_.insert(std::make_pair(
"Odom/MaxFeatures", std::make_pair(
true, Parameters::kVisMaxFeatures())));
297 removedParameters_.insert(std::make_pair(
"Odom/InlierDistance", std::make_pair(
true, Parameters::kVisInlierDistance())));
298 removedParameters_.insert(std::make_pair(
"Odom/MinInliers", std::make_pair(
true, Parameters::kVisMinInliers())));
299 removedParameters_.insert(std::make_pair(
"Odom/Iterations", std::make_pair(
true, Parameters::kVisIterations())));
300 removedParameters_.insert(std::make_pair(
"Odom/RefineIterations", std::make_pair(
true, Parameters::kVisRefineIterations())));
301 removedParameters_.insert(std::make_pair(
"Odom/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
302 removedParameters_.insert(std::make_pair(
"Odom/RoiRatios", std::make_pair(
true, Parameters::kVisRoiRatios())));
303 removedParameters_.insert(std::make_pair(
"Odom/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
304 removedParameters_.insert(std::make_pair(
"Odom/VarianceFromInliersCount", std::make_pair(
false,
"")));
305 removedParameters_.insert(std::make_pair(
"Odom/PnPReprojError", std::make_pair(
true, Parameters::kVisPnPReprojError())));
306 removedParameters_.insert(std::make_pair(
"Odom/PnPFlags", std::make_pair(
true, Parameters::kVisPnPFlags())));
308 removedParameters_.insert(std::make_pair(
"OdomBow/NNType", std::make_pair(
true, Parameters::kVisCorNNType())));
309 removedParameters_.insert(std::make_pair(
"OdomBow/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
311 removedParameters_.insert(std::make_pair(
"OdomFlow/WinSize", std::make_pair(
true, Parameters::kVisCorFlowWinSize())));
312 removedParameters_.insert(std::make_pair(
"OdomFlow/Iterations", std::make_pair(
true, Parameters::kVisCorFlowIterations())));
313 removedParameters_.insert(std::make_pair(
"OdomFlow/Eps", std::make_pair(
true, Parameters::kVisCorFlowEps())));
314 removedParameters_.insert(std::make_pair(
"OdomFlow/MaxLevel", std::make_pair(
true, Parameters::kVisCorFlowMaxLevel())));
316 removedParameters_.insert(std::make_pair(
"OdomSubPix/WinSize", std::make_pair(
true, Parameters::kVisSubPixWinSize())));
317 removedParameters_.insert(std::make_pair(
"OdomSubPix/Iterations", std::make_pair(
true, Parameters::kVisSubPixIterations())));
318 removedParameters_.insert(std::make_pair(
"OdomSubPix/Eps", std::make_pair(
true, Parameters::kVisSubPixEps())));
320 removedParameters_.insert(std::make_pair(
"LccReextract/Activated", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
321 removedParameters_.insert(std::make_pair(
"LccReextract/FeatureType", std::make_pair(
false, Parameters::kVisFeatureType())));
322 removedParameters_.insert(std::make_pair(
"LccReextract/MaxWords", std::make_pair(
false, Parameters::kVisMaxFeatures())));
323 removedParameters_.insert(std::make_pair(
"LccReextract/MaxDepth", std::make_pair(
false, Parameters::kVisMaxDepth())));
324 removedParameters_.insert(std::make_pair(
"LccReextract/RoiRatios", std::make_pair(
false, Parameters::kVisRoiRatios())));
325 removedParameters_.insert(std::make_pair(
"LccReextract/NNType", std::make_pair(
false, Parameters::kVisCorNNType())));
326 removedParameters_.insert(std::make_pair(
"LccReextract/NNDR", std::make_pair(
false, Parameters::kVisCorNNDR())));
328 removedParameters_.insert(std::make_pair(
"LccBow/EstimationType", std::make_pair(
false, Parameters::kVisEstimationType())));
329 removedParameters_.insert(std::make_pair(
"LccBow/InlierDistance", std::make_pair(
false, Parameters::kVisInlierDistance())));
330 removedParameters_.insert(std::make_pair(
"LccBow/MinInliers", std::make_pair(
false, Parameters::kVisMinInliers())));
331 removedParameters_.insert(std::make_pair(
"LccBow/Iterations", std::make_pair(
false, Parameters::kVisIterations())));
332 removedParameters_.insert(std::make_pair(
"LccBow/RefineIterations", std::make_pair(
false, Parameters::kVisRefineIterations())));
333 removedParameters_.insert(std::make_pair(
"LccBow/Force2D", std::make_pair(
false, Parameters::kRegForce3DoF())));
334 removedParameters_.insert(std::make_pair(
"LccBow/VarianceFromInliersCount", std::make_pair(
false,
"")));
335 removedParameters_.insert(std::make_pair(
"LccBow/PnPReprojError", std::make_pair(
false, Parameters::kVisPnPReprojError())));
336 removedParameters_.insert(std::make_pair(
"LccBow/PnPFlags", std::make_pair(
false, Parameters::kVisPnPFlags())));
337 removedParameters_.insert(std::make_pair(
"LccBow/EpipolarGeometryVar", std::make_pair(
true, Parameters::kVisEpipolarGeometryVar())));
339 removedParameters_.insert(std::make_pair(
"LccIcp/Type", std::make_pair(
false, Parameters::kRegStrategy())));
341 removedParameters_.insert(std::make_pair(
"LccIcp3/Decimation", std::make_pair(
false,
"")));
342 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxDepth", std::make_pair(
false,
"")));
343 removedParameters_.insert(std::make_pair(
"LccIcp3/VoxelSize", std::make_pair(
false, Parameters::kIcpVoxelSize())));
344 removedParameters_.insert(std::make_pair(
"LccIcp3/Samples", std::make_pair(
false, Parameters::kIcpDownsamplingStep())));
345 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxCorrespondenceDistance", std::make_pair(
false, Parameters::kIcpMaxCorrespondenceDistance())));
346 removedParameters_.insert(std::make_pair(
"LccIcp3/Iterations", std::make_pair(
false, Parameters::kIcpIterations())));
347 removedParameters_.insert(std::make_pair(
"LccIcp3/CorrespondenceRatio", std::make_pair(
false, Parameters::kIcpCorrespondenceRatio())));
348 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlane", std::make_pair(
true, Parameters::kIcpPointToPlane())));
349 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
351 removedParameters_.insert(std::make_pair(
"LccIcp2/MaxCorrespondenceDistance", std::make_pair(
true, Parameters::kIcpMaxCorrespondenceDistance())));
352 removedParameters_.insert(std::make_pair(
"LccIcp2/Iterations", std::make_pair(
true, Parameters::kIcpIterations())));
353 removedParameters_.insert(std::make_pair(
"LccIcp2/CorrespondenceRatio", std::make_pair(
true, Parameters::kIcpCorrespondenceRatio())));
354 removedParameters_.insert(std::make_pair(
"LccIcp2/VoxelSize", std::make_pair(
true, Parameters::kIcpVoxelSize())));
356 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionByTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
357 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionBySpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
358 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
359 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionSpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
360 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(
false,
"")));
361 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
362 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(
true, Parameters::kRGBDProximityPathFilteringRadius())));
363 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(
true, Parameters::kRGBDProximityPathRawPosesUsed())));
365 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeStrategy", std::make_pair(
true, Parameters::kOptimizerStrategy())));
366 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeEpsilon", std::make_pair(
true, Parameters::kOptimizerEpsilon())));
367 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
368 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeRobust", std::make_pair(
true, Parameters::kOptimizerRobust())));
369 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
370 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2d", std::make_pair(
true, Parameters::kRegForce3DoF())));
371 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeVarianceIgnored", std::make_pair(
true, Parameters::kOptimizerVarianceIgnored())));
373 removedParameters_.insert(std::make_pair(
"Stereo/WinSize", std::make_pair(
true, Parameters::kStereoWinWidth())));
376 removedParameters_.insert(std::make_pair(
"GFTT/MaxCorners", std::make_pair(
true, Parameters::kVisMaxFeatures())));
377 removedParameters_.insert(std::make_pair(
"LccBow/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
378 removedParameters_.insert(std::make_pair(
"LccReextract/LoopClosureFeatures", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
379 removedParameters_.insert(std::make_pair(
"Rtabmap/DetectorStrategy", std::make_pair(
true, Parameters::kKpDetectorStrategy())));
380 removedParameters_.insert(std::make_pair(
"RGBD/ScanMatchingSize", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
381 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionRadius", std::make_pair(
true, Parameters::kRGBDLocalRadius())));
382 removedParameters_.insert(std::make_pair(
"RGBD/ToroIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
383 removedParameters_.insert(std::make_pair(
"Mem/RehearsedNodesKept", std::make_pair(
true, Parameters::kMemNotLinkedNodesKept())));
384 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
385 removedParameters_.insert(std::make_pair(
"RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(
false,
"")));
386 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
false,
"")));
387 removedParameters_.insert(std::make_pair(
"Odom/Type", std::make_pair(
true, Parameters::kVisFeatureType())));
388 removedParameters_.insert(std::make_pair(
"Odom/MaxWords", std::make_pair(
true, Parameters::kVisMaxFeatures())));
389 removedParameters_.insert(std::make_pair(
"Odom/LocalHistory", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
390 removedParameters_.insert(std::make_pair(
"Odom/NearestNeighbor", std::make_pair(
true, Parameters::kVisCorNNType())));
391 removedParameters_.insert(std::make_pair(
"Odom/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
403 for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=
removedParameters_.begin();
407 if(iter->second.first)
426 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.c_str());
437 description = iter->second;
441 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.c_str());
448 ParametersMap::const_iterator iter = parameters.find(key);
449 if(iter != parameters.end())
458 ParametersMap::const_iterator iter = parameters.find(key);
459 if(iter != parameters.end())
461 value =
uStr2Int(iter->second.c_str());
468 ParametersMap::const_iterator iter = parameters.find(key);
469 if(iter != parameters.end())
471 value =
uStr2Int(iter->second.c_str());
478 ParametersMap::const_iterator iter = parameters.find(key);
479 if(iter != parameters.end())
488 ParametersMap::const_iterator iter = parameters.find(key);
489 if(iter != parameters.end())
498 ParametersMap::const_iterator iter = parameters.find(key);
499 if(iter != parameters.end())
501 value = iter->second;
508 for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
510 ParametersMap::const_iterator jter = parameters.find(iter->first);
511 if(jter != parameters.end())
513 iter->second = jter->second;
520 return "RTAB-Map options:\n" 521 " --help Show usage.\n" 522 " --version Show version of rtabmap and its dependencies.\n" 523 " --params Show all parameters with their default value and description\n" 524 " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n" 525 " --SURF/HessianThreshold 150\n" 526 " For parameters in table format, add ',' between values :\n" 527 " --Kp/RoiRatios 0,0,0.1,0\n" 529 " --nolog Disable logger\n" 530 " --logconsole Set logger console type\n" 531 " --logfile \"path\" Set logger file type\n" 532 " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n" 533 " --udebug Set logger level to debug\n" 534 " --uinfo Set logger level to info\n" 535 " --uwarn Set logger level to warn\n" 536 " --uerror Set logger level to error\n" 537 " --logtime \"bool\" Print time when logging\n" 538 " --logwhere \"bool\" Print where when logging\n" 539 " --logthread \"bool\" Print thread id when logging\n" 547 const std::map<std::string, std::pair<bool, std::string> > & removedParams =
getRemovedParameters();
548 for(
int i=0;i<argc;++i)
550 bool checkParameters = onlyParameters;
553 if(strcmp(argv[i],
"--help") == 0)
558 else if(strcmp(argv[i],
"--version") == 0)
560 std::string str =
"RTAB-Map:";
563 std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
565 #ifdef RTABMAP_OPENCV3 566 std::cout << str << std::setw(spacing - str.size()) <<
"3" << std::endl;
568 std::cout << str << std::setw(spacing - str.size()) <<
"2" << std::endl;
570 str =
"With OpenCV nonfree:";
571 #ifdef RTABMAP_NONFREE 572 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
574 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
578 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
580 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
584 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
586 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
590 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
592 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
594 str =
"With Vertigo:";
595 #ifdef RTABMAP_VERTIGO 596 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
598 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
602 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
604 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
606 str =
"With OpenNI2:";
607 #ifdef RTABMAP_OPENNI2 608 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
610 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
612 str =
"With Freenect:";
613 #ifdef RTABMAP_FREENECT 614 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
616 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
618 str =
"With Freenect2:";
619 #ifdef RTABMAP_FREENECT2 620 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
622 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
626 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
628 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
630 str =
"With DC1394:";
631 #ifdef RTABMAP_DC1394 632 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
634 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
636 str =
"With FlyCapture2:";
637 #ifdef RTABMAP_FLYCAPTURE2 638 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
640 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
644 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
646 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
648 str =
"With RealSense:";
649 #ifdef RTABMAP_REALSENSE 650 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
652 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
654 str =
"With RealSense SLAM:";
655 #ifdef RTABMAP_REALSENSE_SLAM 656 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
658 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
660 str =
"With RealSense2:";
661 #ifdef RTABMAP_REALSENSE2 662 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
664 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
666 str =
"With libpointmatcher:";
667 #ifdef RTABMAP_POINTMATCHER 668 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
670 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
672 str =
"With octomap:";
673 #ifdef RTABMAP_OCTOMAP 674 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
676 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
678 str =
"With cpu-tsdf:";
679 #ifdef RTABMAP_CPUTSDF 680 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
682 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
684 str =
"With open chisel:";
685 #ifdef RTABMAP_OPENCHISEL 686 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
688 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
692 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
694 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
698 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
700 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
704 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
706 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
710 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
712 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
714 str =
"With ORB_SLAM2:";
715 #ifdef RTABMAP_ORB_SLAM2 716 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
718 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
722 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
724 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
726 str =
"With MSCKF_VIO:";
727 #ifdef RTABMAP_MSCKF_VIO 728 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
730 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
734 else if(strcmp(argv[i],
"--nolog") == 0)
738 else if(strcmp(argv[i],
"--logconsole") == 0)
742 else if(strcmp(argv[i],
"--logfile") == 0)
751 UERROR(
"\"--logfile\" argument requires following file path");
754 else if(strcmp(argv[i],
"--logfilea") == 0)
763 UERROR(
"\"--logfilea\" argument requires following file path");
766 else if(strcmp(argv[i],
"--udebug") == 0)
770 else if(strcmp(argv[i],
"--uinfo") == 0)
774 else if(strcmp(argv[i],
"--uwarn") == 0)
778 else if(strcmp(argv[i],
"--uerror") == 0)
782 else if(strcmp(argv[i],
"--ulogtime") == 0)
791 UERROR(
"\"--ulogtime\" argument requires a following boolean value");
794 else if(strcmp(argv[i],
"--ulogwhere") == 0)
803 UERROR(
"\"--ulogwhere\" argument requires a following boolean value");
806 else if(strcmp(argv[i],
"--ulogthread") == 0)
815 UERROR(
"\"--ulogthread\" argument requires a following boolean value");
820 checkParameters =
true;
826 if(strcmp(argv[i],
"--params") == 0)
828 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
832 std::string group =
uSplit(iter->first,
'/').front();
833 #ifndef RTABMAP_GTSAM 834 if(group.compare(
"GTSAM") == 0)
840 if(group.compare(
"g2o") == 0)
845 #ifndef RTABMAP_FOVIS 846 if(group.compare(
"OdomFovis") == 0)
851 #ifndef RTABMAP_VISO2 852 if(group.compare(
"OdomViso2") == 0)
857 #ifndef RTABMAP_ORBSLAM2 858 if(group.compare(
"OdomORBSLAM2") == 0)
863 #ifndef RTABMAP_OKVIS 864 if(group.compare(
"OdomOKVIS") == 0)
870 if(group.compare(
"OdomLOAM") == 0)
875 #ifndef RTABMAP_MSCKF_VIO 876 if(group.compare(
"OdomMSCKF") == 0)
883 std::string str =
"Param: " + iter->first +
" = \"" + iter->second +
"\"";
886 std::setw(60 - str.size()) <<
893 UWARN(
"App will now exit after showing default RTAB-Map parameters because " 894 "argument \"--params\" is detected!");
900 ParametersMap::const_iterator iter = parameters.find(key);
901 if(iter != parameters.end())
907 UINFO(
"Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
913 std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
914 if(jter!=removedParams.end())
916 if(jter->second.first)
921 std::string value = argv[i];
925 key = jter->second.second;
926 UWARN(
"Parameter migration from \"%s\" to \"%s\" (value=%s).",
927 jter->first.c_str(), jter->second.second.c_str(), value.c_str());
933 UERROR(
"Value missing for argument \"%s\"", argv[i-1]);
936 else if(jter->second.second.empty())
938 UERROR(
"Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
942 UERROR(
"Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
960 for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
962 std::string key = (*iter).first.pItem;
963 if(key.compare(
"Version") == 0)
967 if(version.size() == 3)
969 if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
971 if(configFile.find(
".rtabmap") != std::string::npos)
973 UWARN(
"Version in the config file \"%s\" is more recent (\"%s\") than " 974 "current RTAB-Map version used (\"%s\"). The config file will be upgraded " 982 UERROR(
"Version in the config file \"%s\" is more recent (\"%s\") than " 983 "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will " 1000 if(oldIter->second.first)
1002 if(parameters.find(oldIter->second.second) == parameters.end())
1004 key = oldIter->second.second;
1005 UINFO(
"Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1009 else if(oldIter->second.second.empty())
1011 UWARN(
"Parameter \"%s\" doesn't exist anymore.",
1012 oldIter->first.c_str());
1014 else if(parameters.find(oldIter->second.second) == parameters.end())
1016 UWARN(
"Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1034 ULOGGER_WARN(
"Section \"Core\" in %s doesn't exist... " 1035 "Ignore this warning if the ini file does not exist yet. " 1036 "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
1046 ini.
SetValue(
"Core",
"Version", RTABMAP_VERSION,
NULL,
true);
1048 for(ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
1050 std::string key = (*i).first;
1053 std::string value = (*i).second.c_str();
1056 ini.
SetValue(
"Core", key.c_str(), value.c_str(),
NULL,
true);
static bool isFeatureParameter(const std::string ¶m)
static void setPrintThreadId(bool printThreadId)
int UTILITE_EXP uStr2Int(const std::string &str)
static std::string homeDir()
static ParametersMap filterParameters(const ParametersMap ¶meters, const std::string &group)
static bool parse(const ParametersMap ¶meters, const std::string &key, bool &value)
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
static bool makeDir(const std::string &dirPath)
static std::string getDescription(const std::string ¶mKey)
double UTILITE_EXP uStr2Double(const std::string &str)
std::multimap< Entry, const SI_CHAR *, typename Entry::KeyOrder > TKeyVal
static const char * showUsage()
SI_Error SaveFile(const char *a_pszFile, bool a_bAddSignature=true) const
std::pair< std::string, std::string > ParametersPair
bool UTILITE_EXP uStr2Bool(const char *str)
static std::string getVersion()
static std::string separator()
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
float UTILITE_EXP uStr2Float(const std::string &str)
std::map< std::string, std::string > ParametersMap
static ParametersMap descriptions_
static void writeINI(const std::string &configFile, const ParametersMap ¶meters)
static ParametersMap backwardCompatibilityMap_
Some conversion functions.
static ParametersMap getDefaultOdometryParameters(bool stereo=false, bool vis=true, bool icp=false)
static void setLevel(ULogger::Level level)
bool uStrContains(const std::string &string, const std::string &substring)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
const TKeyVal * GetSection(const SI_CHAR *a_pSection) const
#define UASSERT(condition)
Wrappers of STL for convenient functions.
static std::string serialize(const ParametersMap ¶meters)
static void setPrintTime(bool printTime)
static Parameters instance_
static const ParametersMap & getBackwardCompatibilityMap()
static ParametersMap deserialize(const std::string ¶meters)
#define UASSERT_MSG(condition, msg_str)
Transform RTABMAP_EXP icp(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZ > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
static ParametersMap parameters_
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
static void setPrintWhere(bool printWhere)
static std::string getType(const std::string ¶mKey)
SI_Error LoadFile(const char *a_pszFile)
std::vector< V > uListToVector(const std::list< V > &list)
static const ParametersMap & getDefaultParameters()
#define ULOGGER_WARN(...)
ULogger class and convenient macros.
static ParametersMap parametersType_
SI_Error SetValue(const SI_CHAR *a_pSection, const SI_CHAR *a_pKey, const SI_CHAR *a_pValue, const SI_CHAR *a_pComment=NULL, bool a_bForceReplace=false)
static std::string getDefaultDatabaseName()
static void readINI(const std::string &configFile, ParametersMap ¶meters, bool modifiedOnly=false)
std::string UTILITE_EXP uFormat(const char *fmt,...)
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
static std::string createDefaultWorkingDirectory()
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)