41 #include <opencv2/core/version.hpp> 42 #include <pcl/pcl_config.h> 43 #include <opencv2/opencv_modules.hpp> 45 #include <vtkVersion.h> 77 UFATAL(
"Can't get the HOME variable environment!");
84 return RTABMAP_VERSION;
95 std::stringstream output;
96 for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
98 if(iter != parameters.begin())
103 output << iter->first <<
":" <<
uReplaceChar(iter->second,
',',
'.');
105 UDEBUG(
"output=%s", output.str().c_str());
111 UDEBUG(
"parameters=%s", parameters.c_str());
113 std::list<std::string> tuplets =
uSplit(parameters,
';');
114 for(std::list<std::string>::iterator iter=tuplets.begin(); iter!=tuplets.end(); ++iter)
116 std::list<std::string> p =
uSplit(*iter,
':');
119 std::string key = p.front();
120 std::string value = p.back();
123 bool addParameter =
true;
127 addParameter = oldIter->second.first;
130 key = oldIter->second.second;
131 UWARN(
"Parameter migration from \"%s\" to \"%s\" (value=%s).",
132 oldIter->first.c_str(), oldIter->second.second.c_str(), value.c_str());
134 else if(oldIter->second.second.empty())
136 UWARN(
"Parameter \"%s\" doesn't exist anymore.",
137 oldIter->first.c_str());
141 UWARN(
"Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
150 UWARN(
"Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
160 std::string group =
uSplit(parameter,
'/').front();
161 return group.compare(
"SURF") == 0 ||
162 group.compare(
"SIFT") == 0 ||
163 group.compare(
"ORB") == 0 ||
164 group.compare(
"FAST") == 0 ||
165 group.compare(
"FREAK") == 0 ||
166 group.compare(
"BRIEF") == 0 ||
167 group.compare(
"GFTT") == 0 ||
168 group.compare(
"BRISK") == 0 ||
169 group.compare(
"KAZE") == 0 ||
170 group.compare(
"SuperPoint") == 0;
177 for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
179 std::string group =
uSplit(iter->first,
'/').front();
181 (stereo && group.compare(
"Stereo") == 0) ||
182 (icp && group.compare(
"Icp") == 0) ||
184 group.compare(
"Reg") == 0 ||
185 group.compare(
"Optimizer") == 0 ||
186 group.compare(
"g2o") == 0 ||
187 group.compare(
"GTSAM") == 0 ||
188 (vis && (group.compare(
"Vis") == 0 || group.compare(
"PyMatcher") == 0 || group.compare(
"GMS") == 0)) ||
189 iter->first.compare(kRtabmapPublishRAMUsage())==0)
191 odomParameters.insert(*iter);
194 return odomParameters;
201 for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
204 std::string group =
uSplit(iter->first,
'/').front();
205 if(group.compare(groupIn) == 0)
207 parameters.insert(*iter);
210 UASSERT_MSG(parameters.size(),
uFormat(
"No parameters found for group %s!", groupIn.c_str()).c_str());
217 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
220 std::string group =
uSplit(iter->first,
'/').front();
221 if(group.compare(groupIn) == 0)
223 output.insert(*iter);
236 removedParameters_.insert(std::make_pair(
"SuperGlue/Path", std::make_pair(
true, Parameters::kPyMatcherPath())));
237 removedParameters_.insert(std::make_pair(
"SuperGlue/Iterations", std::make_pair(
true, Parameters::kPyMatcherIterations())));
238 removedParameters_.insert(std::make_pair(
"SuperGlue/MatchThreshold", std::make_pair(
true, Parameters::kPyMatcherThreshold())));
239 removedParameters_.insert(std::make_pair(
"SuperGlue/Cuda", std::make_pair(
true, Parameters::kPyMatcherCuda())));
240 removedParameters_.insert(std::make_pair(
"SuperGlue/Indoor", std::make_pair(
false, Parameters::kPyMatcherModel())));
242 removedParameters_.insert(std::make_pair(
"Vis/CorCrossCheck", std::make_pair(
false, Parameters::kVisCorNNType())));
243 removedParameters_.insert(std::make_pair(
"SPTorch/ModelPath", std::make_pair(
true, Parameters::kSuperPointModelPath())));
244 removedParameters_.insert(std::make_pair(
"SPTorch/Threshold", std::make_pair(
true, Parameters::kSuperPointThreshold())));
245 removedParameters_.insert(std::make_pair(
"SPTorch/NMS", std::make_pair(
true, Parameters::kSuperPointNMS())));
246 removedParameters_.insert(std::make_pair(
"SPTorch/MinDistance", std::make_pair(
true, Parameters::kSuperPointNMSRadius())));
247 removedParameters_.insert(std::make_pair(
"SPTorch/Cuda", std::make_pair(
true, Parameters::kSuperPointCuda())));
250 removedParameters_.insert(std::make_pair(
"RGBD/MaxLocalizationDistance", std::make_pair(
true, Parameters::kRGBDMaxLoopClosureDistance())));
253 removedParameters_.insert(std::make_pair(
"Aruco/Dictionary", std::make_pair(
true, Parameters::kMarkerDictionary())));
254 removedParameters_.insert(std::make_pair(
"Aruco/MarkerLength", std::make_pair(
true, Parameters::kMarkerLength())));
255 removedParameters_.insert(std::make_pair(
"Aruco/MaxDepthError", std::make_pair(
true, Parameters::kMarkerMaxDepthError())));
256 removedParameters_.insert(std::make_pair(
"Aruco/VarianceLinear", std::make_pair(
true, Parameters::kMarkerVarianceLinear())));
257 removedParameters_.insert(std::make_pair(
"Aruco/VarianceAngular", std::make_pair(
true, Parameters::kMarkerVarianceAngular())));
258 removedParameters_.insert(std::make_pair(
"Aruco/CornerRefinementMethod", std::make_pair(
true, Parameters::kMarkerCornerRefinementMethod())));
261 removedParameters_.insert(std::make_pair(
"Grid/OctoMapOccupancyThr", std::make_pair(
true, Parameters::kGridGlobalOccupancyThr())));
264 removedParameters_.insert(std::make_pair(
"Grid/Scan2dMaxFilledRange", std::make_pair(
false, Parameters::kGridRangeMax())));
267 removedParameters_.insert(std::make_pair(
"Grid/ProjRayTracing", std::make_pair(
true, Parameters::kGridRayTracing())));
268 removedParameters_.insert(std::make_pair(
"Grid/DepthMin", std::make_pair(
true, Parameters::kGridRangeMin())));
269 removedParameters_.insert(std::make_pair(
"Grid/DepthMax", std::make_pair(
true, Parameters::kGridRangeMax())));
272 removedParameters_.insert(std::make_pair(
"Reg/VarianceFromInliersCount", std::make_pair(
false,
"")));
273 removedParameters_.insert(std::make_pair(
"Reg/VarianceNormalized", std::make_pair(
false,
"")));
276 removedParameters_.insert(std::make_pair(
"Icp/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
280 removedParameters_.insert(std::make_pair(
"Rtabmap/VhStrategy", std::make_pair(
true, Parameters::kVhEpEnabled())));
283 removedParameters_.insert(std::make_pair(
"Grid/FullUpdate", std::make_pair(
true, Parameters::kGridGlobalFullUpdate())));
286 removedParameters_.insert(std::make_pair(
"Grid/3DGroundIsObstacle", std::make_pair(
true, Parameters::kGridGroundIsObstacle())));
289 removedParameters_.insert(std::make_pair(
"Optimizer/Slam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
290 removedParameters_.insert(std::make_pair(
"OdomF2M/FixedMapPath", std::make_pair(
false,
"")));
293 removedParameters_.insert(std::make_pair(
"Grid/FlatObstaclesDetected", std::make_pair(
true, Parameters::kGridFlatObstacleDetected())));
296 removedParameters_.insert(std::make_pair(
"Reg/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
297 removedParameters_.insert(std::make_pair(
"OdomF2M/ScanSubstractRadius", std::make_pair(
true, Parameters::kOdomF2MScanSubtractRadius())));
300 removedParameters_.insert(std::make_pair(
"RGBD/ProximityPathScansMerged", std::make_pair(
false,
"")));
303 removedParameters_.insert(std::make_pair(
"Mem/ImageDecimation", std::make_pair(
true, Parameters::kMemImagePostDecimation())));
306 removedParameters_.insert(std::make_pair(
"OdomLocalMap/HistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
307 removedParameters_.insert(std::make_pair(
"OdomLocalMap/FixedMapPath", std::make_pair(
false,
"")));
308 removedParameters_.insert(std::make_pair(
"OdomF2F/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
309 removedParameters_.insert(std::make_pair(
"OdomF2F/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
312 removedParameters_.insert(std::make_pair(
"OdomBow/LocalHistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
313 removedParameters_.insert(std::make_pair(
"OdomBow/FixedLocalMapPath", std::make_pair(
false,
"")));
314 removedParameters_.insert(std::make_pair(
"OdomFlow/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
315 removedParameters_.insert(std::make_pair(
"OdomFlow/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
317 removedParameters_.insert(std::make_pair(
"Kp/WordsPerImage", std::make_pair(
true, Parameters::kKpMaxFeatures())));
319 removedParameters_.insert(std::make_pair(
"Mem/LocalSpaceLinksKeptInWM", std::make_pair(
false,
"")));
321 removedParameters_.insert(std::make_pair(
"RGBD/PoseScanMatching", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
323 removedParameters_.insert(std::make_pair(
"Odom/ParticleFiltering", std::make_pair(
false, Parameters::kOdomFilteringStrategy())));
324 removedParameters_.insert(std::make_pair(
"Odom/FeatureType", std::make_pair(
true, Parameters::kVisFeatureType())));
325 removedParameters_.insert(std::make_pair(
"Odom/EstimationType", std::make_pair(
true, Parameters::kVisEstimationType())));
326 removedParameters_.insert(std::make_pair(
"Odom/MaxFeatures", std::make_pair(
true, Parameters::kVisMaxFeatures())));
327 removedParameters_.insert(std::make_pair(
"Odom/InlierDistance", std::make_pair(
true, Parameters::kVisInlierDistance())));
328 removedParameters_.insert(std::make_pair(
"Odom/MinInliers", std::make_pair(
true, Parameters::kVisMinInliers())));
329 removedParameters_.insert(std::make_pair(
"Odom/Iterations", std::make_pair(
true, Parameters::kVisIterations())));
330 removedParameters_.insert(std::make_pair(
"Odom/RefineIterations", std::make_pair(
true, Parameters::kVisRefineIterations())));
331 removedParameters_.insert(std::make_pair(
"Odom/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
332 removedParameters_.insert(std::make_pair(
"Odom/RoiRatios", std::make_pair(
true, Parameters::kVisRoiRatios())));
333 removedParameters_.insert(std::make_pair(
"Odom/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
334 removedParameters_.insert(std::make_pair(
"Odom/VarianceFromInliersCount", std::make_pair(
false,
"")));
335 removedParameters_.insert(std::make_pair(
"Odom/PnPReprojError", std::make_pair(
true, Parameters::kVisPnPReprojError())));
336 removedParameters_.insert(std::make_pair(
"Odom/PnPFlags", std::make_pair(
true, Parameters::kVisPnPFlags())));
338 removedParameters_.insert(std::make_pair(
"OdomBow/NNType", std::make_pair(
true, Parameters::kVisCorNNType())));
339 removedParameters_.insert(std::make_pair(
"OdomBow/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
341 removedParameters_.insert(std::make_pair(
"OdomFlow/WinSize", std::make_pair(
true, Parameters::kVisCorFlowWinSize())));
342 removedParameters_.insert(std::make_pair(
"OdomFlow/Iterations", std::make_pair(
true, Parameters::kVisCorFlowIterations())));
343 removedParameters_.insert(std::make_pair(
"OdomFlow/Eps", std::make_pair(
true, Parameters::kVisCorFlowEps())));
344 removedParameters_.insert(std::make_pair(
"OdomFlow/MaxLevel", std::make_pair(
true, Parameters::kVisCorFlowMaxLevel())));
346 removedParameters_.insert(std::make_pair(
"OdomSubPix/WinSize", std::make_pair(
true, Parameters::kVisSubPixWinSize())));
347 removedParameters_.insert(std::make_pair(
"OdomSubPix/Iterations", std::make_pair(
true, Parameters::kVisSubPixIterations())));
348 removedParameters_.insert(std::make_pair(
"OdomSubPix/Eps", std::make_pair(
true, Parameters::kVisSubPixEps())));
350 removedParameters_.insert(std::make_pair(
"LccReextract/Activated", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
351 removedParameters_.insert(std::make_pair(
"LccReextract/FeatureType", std::make_pair(
false, Parameters::kVisFeatureType())));
352 removedParameters_.insert(std::make_pair(
"LccReextract/MaxWords", std::make_pair(
false, Parameters::kVisMaxFeatures())));
353 removedParameters_.insert(std::make_pair(
"LccReextract/MaxDepth", std::make_pair(
false, Parameters::kVisMaxDepth())));
354 removedParameters_.insert(std::make_pair(
"LccReextract/RoiRatios", std::make_pair(
false, Parameters::kVisRoiRatios())));
355 removedParameters_.insert(std::make_pair(
"LccReextract/NNType", std::make_pair(
false, Parameters::kVisCorNNType())));
356 removedParameters_.insert(std::make_pair(
"LccReextract/NNDR", std::make_pair(
false, Parameters::kVisCorNNDR())));
358 removedParameters_.insert(std::make_pair(
"LccBow/EstimationType", std::make_pair(
false, Parameters::kVisEstimationType())));
359 removedParameters_.insert(std::make_pair(
"LccBow/InlierDistance", std::make_pair(
false, Parameters::kVisInlierDistance())));
360 removedParameters_.insert(std::make_pair(
"LccBow/MinInliers", std::make_pair(
false, Parameters::kVisMinInliers())));
361 removedParameters_.insert(std::make_pair(
"LccBow/Iterations", std::make_pair(
false, Parameters::kVisIterations())));
362 removedParameters_.insert(std::make_pair(
"LccBow/RefineIterations", std::make_pair(
false, Parameters::kVisRefineIterations())));
363 removedParameters_.insert(std::make_pair(
"LccBow/Force2D", std::make_pair(
false, Parameters::kRegForce3DoF())));
364 removedParameters_.insert(std::make_pair(
"LccBow/VarianceFromInliersCount", std::make_pair(
false,
"")));
365 removedParameters_.insert(std::make_pair(
"LccBow/PnPReprojError", std::make_pair(
false, Parameters::kVisPnPReprojError())));
366 removedParameters_.insert(std::make_pair(
"LccBow/PnPFlags", std::make_pair(
false, Parameters::kVisPnPFlags())));
367 removedParameters_.insert(std::make_pair(
"LccBow/EpipolarGeometryVar", std::make_pair(
true, Parameters::kVisEpipolarGeometryVar())));
369 removedParameters_.insert(std::make_pair(
"LccIcp/Type", std::make_pair(
false, Parameters::kRegStrategy())));
371 removedParameters_.insert(std::make_pair(
"LccIcp3/Decimation", std::make_pair(
false,
"")));
372 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxDepth", std::make_pair(
false,
"")));
373 removedParameters_.insert(std::make_pair(
"LccIcp3/VoxelSize", std::make_pair(
false, Parameters::kIcpVoxelSize())));
374 removedParameters_.insert(std::make_pair(
"LccIcp3/Samples", std::make_pair(
false, Parameters::kIcpDownsamplingStep())));
375 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxCorrespondenceDistance", std::make_pair(
false, Parameters::kIcpMaxCorrespondenceDistance())));
376 removedParameters_.insert(std::make_pair(
"LccIcp3/Iterations", std::make_pair(
false, Parameters::kIcpIterations())));
377 removedParameters_.insert(std::make_pair(
"LccIcp3/CorrespondenceRatio", std::make_pair(
false, Parameters::kIcpCorrespondenceRatio())));
378 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlane", std::make_pair(
true, Parameters::kIcpPointToPlane())));
379 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
381 removedParameters_.insert(std::make_pair(
"LccIcp2/MaxCorrespondenceDistance", std::make_pair(
true, Parameters::kIcpMaxCorrespondenceDistance())));
382 removedParameters_.insert(std::make_pair(
"LccIcp2/Iterations", std::make_pair(
true, Parameters::kIcpIterations())));
383 removedParameters_.insert(std::make_pair(
"LccIcp2/CorrespondenceRatio", std::make_pair(
true, Parameters::kIcpCorrespondenceRatio())));
384 removedParameters_.insert(std::make_pair(
"LccIcp2/VoxelSize", std::make_pair(
true, Parameters::kIcpVoxelSize())));
386 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionByTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
387 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionBySpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
388 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
389 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionSpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
390 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(
false,
"")));
391 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
392 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(
true, Parameters::kRGBDProximityPathFilteringRadius())));
393 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(
true, Parameters::kRGBDProximityPathRawPosesUsed())));
395 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeStrategy", std::make_pair(
true, Parameters::kOptimizerStrategy())));
396 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeEpsilon", std::make_pair(
true, Parameters::kOptimizerEpsilon())));
397 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
398 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeRobust", std::make_pair(
true, Parameters::kOptimizerRobust())));
399 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
400 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2d", std::make_pair(
true, Parameters::kRegForce3DoF())));
401 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeVarianceIgnored", std::make_pair(
true, Parameters::kOptimizerVarianceIgnored())));
403 removedParameters_.insert(std::make_pair(
"Stereo/WinSize", std::make_pair(
true, Parameters::kStereoWinWidth())));
406 removedParameters_.insert(std::make_pair(
"GFTT/MaxCorners", std::make_pair(
true, Parameters::kVisMaxFeatures())));
407 removedParameters_.insert(std::make_pair(
"LccBow/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
408 removedParameters_.insert(std::make_pair(
"LccReextract/LoopClosureFeatures", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
409 removedParameters_.insert(std::make_pair(
"Rtabmap/DetectorStrategy", std::make_pair(
true, Parameters::kKpDetectorStrategy())));
410 removedParameters_.insert(std::make_pair(
"RGBD/ScanMatchingSize", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
411 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionRadius", std::make_pair(
true, Parameters::kRGBDLocalRadius())));
412 removedParameters_.insert(std::make_pair(
"RGBD/ToroIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
413 removedParameters_.insert(std::make_pair(
"Mem/RehearsedNodesKept", std::make_pair(
true, Parameters::kMemNotLinkedNodesKept())));
414 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
415 removedParameters_.insert(std::make_pair(
"RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(
false,
"")));
416 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
false,
"")));
417 removedParameters_.insert(std::make_pair(
"Odom/Type", std::make_pair(
true, Parameters::kVisFeatureType())));
418 removedParameters_.insert(std::make_pair(
"Odom/MaxWords", std::make_pair(
true, Parameters::kVisMaxFeatures())));
419 removedParameters_.insert(std::make_pair(
"Odom/LocalHistory", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
420 removedParameters_.insert(std::make_pair(
"Odom/NearestNeighbor", std::make_pair(
true, Parameters::kVisCorNNType())));
421 removedParameters_.insert(std::make_pair(
"Odom/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
433 for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=
removedParameters_.begin();
437 if(iter->second.first)
456 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.c_str());
467 description = iter->second;
471 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.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())
491 value =
uStr2Int(iter->second.c_str());
498 ParametersMap::const_iterator iter = parameters.find(key);
499 if(iter != parameters.end())
501 value =
uStr2Int(iter->second.c_str());
508 ParametersMap::const_iterator iter = parameters.find(key);
509 if(iter != parameters.end())
518 ParametersMap::const_iterator iter = parameters.find(key);
519 if(iter != parameters.end())
528 ParametersMap::const_iterator iter = parameters.find(key);
529 if(iter != parameters.end())
531 value = iter->second;
538 for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
540 ParametersMap::const_iterator jter = parameters.find(iter->first);
541 if(jter != parameters.end())
543 iter->second = jter->second;
550 return "RTAB-Map options:\n" 551 " --help Show usage.\n" 552 " --version Show version of rtabmap and its dependencies.\n" 553 " --params Show all parameters with their default value and description. \n" 554 " If a database path is set as last argument, the parameters in the \n" 555 " database will be shown in INI format.\n" 556 " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n" 557 " --SURF/HessianThreshold 150\n" 558 " For parameters in table format, add ',' between values :\n" 559 " --Kp/RoiRatios 0,0,0.1,0\n" 561 " --nolog Disable logger\n" 562 " --logconsole Set logger console type\n" 563 " --logfile \"path\" Set logger file type\n" 564 " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n" 565 " --udebug Set logger level to debug\n" 566 " --uinfo Set logger level to info\n" 567 " --uwarn Set logger level to warn\n" 568 " --uerror Set logger level to error\n" 569 " --logtime \"bool\" Print time when logging\n" 570 " --logwhere \"bool\" Print where when logging\n" 571 " --logthread \"bool\" Print thread id when logging\n" 579 const std::map<std::string, std::pair<bool, std::string> > & removedParams =
getRemovedParameters();
580 for(
int i=0;i<argc;++i)
582 bool checkParameters = onlyParameters;
585 if(strcmp(argv[i],
"--help") == 0)
590 else if(strcmp(argv[i],
"--version") == 0)
592 std::string str =
"RTAB-Map:";
595 std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
597 std::cout << str << std::setw(spacing - str.size()) << PCL_VERSION_PRETTY << std::endl;
600 std::cout << str << std::setw(spacing - str.size()) << vtkVersion::GetVTKVersion() << std::endl;
602 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
605 std::cout << str << std::setw(spacing - str.size()) << CV_VERSION << std::endl;
606 #if CV_MAJOR_VERSION >= 3 607 str =
"With OpenCV xfeatures2d:";
608 #ifdef HAVE_OPENCV_XFEATURES2D 609 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
611 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
614 str =
"With OpenCV nonfree:";
615 #ifdef RTABMAP_NONFREE 616 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
618 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
620 str =
"With ORB OcTree:";
621 #ifdef RTABMAP_ORB_OCTREE 622 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
624 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
626 str =
"With SuperPoint Torch:";
627 #ifdef RTABMAP_SUPERPOINT_TORCH 628 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
630 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
632 str =
"With Python3:";
633 #ifdef RTABMAP_PYMATCHER 634 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
636 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
638 str =
"With FastCV:";
639 #ifdef RTABMAP_FASTCV 640 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
642 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
644 str =
"With Madgwick:";
645 #ifdef RTABMAP_MADGWICK 646 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
648 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
652 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
654 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
658 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
660 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
664 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
666 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
668 str =
"With Vertigo:";
669 #ifdef RTABMAP_VERTIGO 670 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
672 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
676 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
678 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
682 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
684 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
686 str =
"With OpenNI2:";
687 #ifdef RTABMAP_OPENNI2 688 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
690 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
692 str =
"With Freenect:";
693 #ifdef RTABMAP_FREENECT 694 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
696 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
698 str =
"With Freenect2:";
699 #ifdef RTABMAP_FREENECT2 700 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
702 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
706 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
708 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
712 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
714 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
716 str =
"With DC1394:";
717 #ifdef RTABMAP_DC1394 718 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
720 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
722 str =
"With FlyCapture2:";
723 #ifdef RTABMAP_FLYCAPTURE2 724 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
726 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
730 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
732 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
734 str =
"With RealSense:";
735 #ifdef RTABMAP_REALSENSE 736 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
738 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
740 str =
"With RealSense SLAM:";
741 #ifdef RTABMAP_REALSENSE_SLAM 742 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
744 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
746 str =
"With RealSense2:";
747 #ifdef RTABMAP_REALSENSE2 748 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
750 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
752 str =
"With MYNT EYE S:";
753 #ifdef RTABMAP_MYNTEYE 754 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
756 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
758 str =
"With libpointmatcher:";
759 #ifdef RTABMAP_POINTMATCHER 760 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
762 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
764 str =
"With octomap:";
765 #ifdef RTABMAP_OCTOMAP 766 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
768 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
770 str =
"With cpu-tsdf:";
771 #ifdef RTABMAP_CPUTSDF 772 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
774 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
776 str =
"With open chisel:";
777 #ifdef RTABMAP_OPENCHISEL 778 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
780 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
782 str =
"With Alice Vision:";
783 #ifdef RTABMAP_ALICE_VISION 784 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
786 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
790 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
792 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
796 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
798 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
802 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
804 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
808 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
810 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
812 str =
"With ORB_SLAM2:";
813 #ifdef RTABMAP_ORB_SLAM2 814 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
816 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
820 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
822 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
824 str =
"With MSCKF_VIO:";
825 #ifdef RTABMAP_MSCKF_VIO 826 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
828 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
830 str =
"With VINS-Fusion:";
832 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
834 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
838 else if(strcmp(argv[i],
"--nolog") == 0)
842 else if(strcmp(argv[i],
"--logconsole") == 0)
846 else if(strcmp(argv[i],
"--logfile") == 0)
855 UERROR(
"\"--logfile\" argument requires following file path");
858 else if(strcmp(argv[i],
"--logfilea") == 0)
867 UERROR(
"\"--logfilea\" argument requires following file path");
870 else if(strcmp(argv[i],
"--udebug") == 0)
874 else if(strcmp(argv[i],
"--uinfo") == 0)
878 else if(strcmp(argv[i],
"--uwarn") == 0)
882 else if(strcmp(argv[i],
"--uerror") == 0)
886 else if(strcmp(argv[i],
"--ulogtime") == 0)
895 UERROR(
"\"--ulogtime\" argument requires a following boolean value");
898 else if(strcmp(argv[i],
"--ulogwhere") == 0)
907 UERROR(
"\"--ulogwhere\" argument requires a following boolean value");
910 else if(strcmp(argv[i],
"--ulogthread") == 0)
919 UERROR(
"\"--ulogthread\" argument requires a following boolean value");
924 checkParameters =
true;
930 if(strcmp(argv[i],
"--params") == 0)
935 std::string dbName = argv[argc - 1];
943 if (!dbParameters.empty())
945 std::cout <<
"[Core]" << std::endl;
946 std::cout <<
"Version = " << RTABMAP_VERSION << std::endl;
947 for (ParametersMap::const_iterator iter = dbParameters.begin(); iter != dbParameters.end(); ++iter)
949 std::string key = iter->first;
952 std::string value = iter->second.c_str();
955 std::cout << key <<
" = " << value << std::endl;
969 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
973 std::string group =
uSplit(iter->first,
'/').front();
974 #ifndef RTABMAP_GTSAM 975 if(group.compare(
"GTSAM") == 0)
981 if(group.compare(
"g2o") == 0)
986 #ifndef RTABMAP_FOVIS 987 if(group.compare(
"OdomFovis") == 0)
992 #ifndef RTABMAP_VISO2 993 if(group.compare(
"OdomViso2") == 0)
998 #ifndef RTABMAP_ORBSLAM2 999 if(group.compare(
"OdomORBSLAM2") == 0)
1004 #ifndef RTABMAP_OKVIS 1005 if(group.compare(
"OdomOKVIS") == 0)
1010 #ifndef RTABMAP_LOAM 1011 if(group.compare(
"OdomLOAM") == 0)
1016 #ifndef RTABMAP_MSCKF_VIO 1017 if(group.compare(
"OdomMSCKF") == 0)
1024 std::string str =
"Param: " + iter->first +
" = \"" + iter->second +
"\"";
1027 std::setw(60 - str.size()) <<
1039 ParametersMap::const_iterator iter = parameters.find(key);
1040 if(iter != parameters.end())
1046 UINFO(
"Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
1052 std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
1053 if(jter!=removedParams.end())
1055 if(jter->second.first)
1060 std::string value = argv[i];
1064 key = jter->second.second;
1065 UWARN(
"Parameter migration from \"%s\" to \"%s\" (value=%s).",
1066 jter->first.c_str(), jter->second.second.c_str(), value.c_str());
1072 UERROR(
"Value missing for argument \"%s\"", argv[i-1]);
1075 else if(jter->second.second.empty())
1077 UERROR(
"Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
1081 UERROR(
"Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
1099 for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
1101 std::string key = (*iter).first.pItem;
1102 if(key.compare(
"Version") == 0)
1106 if(version.size() == 3)
1108 if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
1110 if(configFile.find(
".rtabmap") != std::string::npos)
1112 UWARN(
"Version in the config file \"%s\" is more recent (\"%s\") than " 1113 "current RTAB-Map version used (\"%s\"). The config file will be upgraded " 1121 UERROR(
"Version in the config file \"%s\" is more recent (\"%s\") than " 1122 "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will " 1139 if(oldIter->second.first)
1141 if(parameters.find(oldIter->second.second) == parameters.end())
1143 key = oldIter->second.second;
1144 UINFO(
"Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1148 else if(oldIter->second.second.empty())
1150 UWARN(
"Parameter \"%s\" doesn't exist anymore.",
1151 oldIter->first.c_str());
1153 else if(parameters.find(oldIter->second.second) == parameters.end())
1155 UWARN(
"Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1173 ULOGGER_WARN(
"Section \"Core\" in %s doesn't exist... " 1174 "Ignore this warning if the ini file does not exist yet. " 1175 "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
1185 ini.
SetValue(
"Core",
"Version", RTABMAP_VERSION,
NULL,
true);
1187 for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1189 std::string key = iter->first;
1192 std::string value = iter->second.c_str();
1195 ini.
SetValue(
"Core", key.c_str(), value.c_str(),
NULL,
true);
1201 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter =
removedParameters_.begin();
1205 std::string key = iter->first;
1208 std::string value = ini.
GetValue(
"Core", key.c_str(),
"");
1210 if(ini.
Delete(
"Core", key.c_str(),
true))
1212 if(iter->second.first && parameters.find(iter->second.second) != parameters.end())
1214 UWARN(
"Removed deprecated parameter %s=%s (replaced by %s=%s) from \"%s\".", iter->first.c_str(), value.c_str(), iter->second.second.c_str(), parameters.at(iter->second.second).c_str(), configFile.c_str());
1218 UWARN(
"Removed deprecated parameter %s=%s from \"%s\".", iter->first.c_str(), value.c_str(), configFile.c_str());
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()
bool Delete(const SI_CHAR *a_pSection, const SI_CHAR *a_pKey, bool a_bRemoveEmpty=false)
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)
std::string getExtension()
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
bool openConnection(const std::string &url, bool overwritten=false)
#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)
void closeConnection(bool save=true, const std::string &outputUrl="")
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)
const SI_CHAR * GetValue(const SI_CHAR *a_pSection, const SI_CHAR *a_pKey, const SI_CHAR *a_pDefault=NULL, bool *a_pHasMultiple=NULL) const
static ParametersMap parameters_
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
static void setPrintWhere(bool printWhere)
static DBDriver * create(const ParametersMap ¶meters=ParametersMap())
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()
ParametersMap getLastParameters() const
#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)