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 ||
171 group.compare(
"PyDetector") == 0;
178 for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
180 std::string group =
uSplit(iter->first,
'/').front();
182 (stereo && group.compare(
"Stereo") == 0) ||
183 (icp && group.compare(
"Icp") == 0) ||
185 group.compare(
"Reg") == 0 ||
186 group.compare(
"Optimizer") == 0 ||
187 group.compare(
"g2o") == 0 ||
188 group.compare(
"GTSAM") == 0 ||
189 (vis && (group.compare(
"Vis") == 0 || group.compare(
"PyMatcher") == 0 || group.compare(
"GMS") == 0)) ||
190 iter->first.compare(kRtabmapPublishRAMUsage())==0 ||
191 iter->first.compare(kRtabmapImagesAlreadyRectified())==0 ||
192 iter->first.compare(kKpByteToFloat())==0)
194 odomParameters.insert(*iter);
197 return odomParameters;
204 for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
207 std::string group =
uSplit(iter->first,
'/').front();
208 if(group.compare(groupIn) == 0)
210 parameters.insert(*iter);
213 UASSERT_MSG(parameters.size(),
uFormat(
"No parameters found for group %s!", groupIn.c_str()).c_str());
220 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
223 std::string group =
uSplit(iter->first,
'/').front();
224 bool sameGroup = group.compare(group) == 0;
225 if((!
remove && sameGroup) || (
remove && !sameGroup))
227 output.insert(*iter);
240 removedParameters_.insert(std::make_pair(
"Grid/FromDepth", std::make_pair(
true, Parameters::kGridSensor())));
243 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/VocPath", std::make_pair(
true, Parameters::kOdomORBSLAMVocPath())));
244 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/Bf", std::make_pair(
true, Parameters::kOdomORBSLAMBf())));
245 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/ThDepth", std::make_pair(
true, Parameters::kOdomORBSLAMThDepth())));
246 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/Fps", std::make_pair(
true, Parameters::kOdomORBSLAMFps())));
247 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/MaxFeatures", std::make_pair(
true, Parameters::kOdomORBSLAMMaxFeatures())));
248 removedParameters_.insert(std::make_pair(
"OdomORBSLAM2/MapSize", std::make_pair(
true, Parameters::kOdomORBSLAMMapSize())));
250 removedParameters_.insert(std::make_pair(
"RGBD/SavedLocalizationIgnored", std::make_pair(
true, Parameters::kRGBDStartAtOrigin())));
252 removedParameters_.insert(std::make_pair(
"Icp/PMForce4DoF", std::make_pair(
true, Parameters::kIcpForce4DoF())));
253 removedParameters_.insert(std::make_pair(
"Icp/PM", std::make_pair(
true, Parameters::kIcpStrategy())));
254 removedParameters_.insert(std::make_pair(
"Icp/PMOutlierRatio", std::make_pair(
true, Parameters::kIcpOutlierRatio())));
257 removedParameters_.insert(std::make_pair(
"SuperGlue/Path", std::make_pair(
true, Parameters::kPyMatcherPath())));
258 removedParameters_.insert(std::make_pair(
"SuperGlue/Iterations", std::make_pair(
true, Parameters::kPyMatcherIterations())));
259 removedParameters_.insert(std::make_pair(
"SuperGlue/MatchThreshold", std::make_pair(
true, Parameters::kPyMatcherThreshold())));
260 removedParameters_.insert(std::make_pair(
"SuperGlue/Cuda", std::make_pair(
true, Parameters::kPyMatcherCuda())));
261 removedParameters_.insert(std::make_pair(
"SuperGlue/Indoor", std::make_pair(
false, Parameters::kPyMatcherModel())));
263 removedParameters_.insert(std::make_pair(
"Vis/CorCrossCheck", std::make_pair(
false, Parameters::kVisCorNNType())));
264 removedParameters_.insert(std::make_pair(
"SPTorch/ModelPath", std::make_pair(
true, Parameters::kSuperPointModelPath())));
265 removedParameters_.insert(std::make_pair(
"SPTorch/Threshold", std::make_pair(
true, Parameters::kSuperPointThreshold())));
266 removedParameters_.insert(std::make_pair(
"SPTorch/NMS", std::make_pair(
true, Parameters::kSuperPointNMS())));
267 removedParameters_.insert(std::make_pair(
"SPTorch/MinDistance", std::make_pair(
true, Parameters::kSuperPointNMSRadius())));
268 removedParameters_.insert(std::make_pair(
"SPTorch/Cuda", std::make_pair(
true, Parameters::kSuperPointCuda())));
271 removedParameters_.insert(std::make_pair(
"RGBD/MaxLocalizationDistance", std::make_pair(
true, Parameters::kRGBDMaxLoopClosureDistance())));
274 removedParameters_.insert(std::make_pair(
"Aruco/Dictionary", std::make_pair(
true, Parameters::kMarkerDictionary())));
275 removedParameters_.insert(std::make_pair(
"Aruco/MarkerLength", std::make_pair(
true, Parameters::kMarkerLength())));
276 removedParameters_.insert(std::make_pair(
"Aruco/MaxDepthError", std::make_pair(
true, Parameters::kMarkerMaxDepthError())));
277 removedParameters_.insert(std::make_pair(
"Aruco/VarianceLinear", std::make_pair(
true, Parameters::kMarkerVarianceLinear())));
278 removedParameters_.insert(std::make_pair(
"Aruco/VarianceAngular", std::make_pair(
true, Parameters::kMarkerVarianceAngular())));
279 removedParameters_.insert(std::make_pair(
"Aruco/CornerRefinementMethod", std::make_pair(
true, Parameters::kMarkerCornerRefinementMethod())));
282 removedParameters_.insert(std::make_pair(
"Grid/OctoMapOccupancyThr", std::make_pair(
true, Parameters::kGridGlobalOccupancyThr())));
285 removedParameters_.insert(std::make_pair(
"Grid/Scan2dMaxFilledRange", std::make_pair(
false, Parameters::kGridRangeMax())));
288 removedParameters_.insert(std::make_pair(
"Grid/ProjRayTracing", std::make_pair(
true, Parameters::kGridRayTracing())));
289 removedParameters_.insert(std::make_pair(
"Grid/DepthMin", std::make_pair(
true, Parameters::kGridRangeMin())));
290 removedParameters_.insert(std::make_pair(
"Grid/DepthMax", std::make_pair(
true, Parameters::kGridRangeMax())));
293 removedParameters_.insert(std::make_pair(
"Reg/VarianceFromInliersCount", std::make_pair(
false,
"")));
294 removedParameters_.insert(std::make_pair(
"Reg/VarianceNormalized", std::make_pair(
false,
"")));
297 removedParameters_.insert(std::make_pair(
"Icp/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
301 removedParameters_.insert(std::make_pair(
"Rtabmap/VhStrategy", std::make_pair(
true, Parameters::kVhEpEnabled())));
304 removedParameters_.insert(std::make_pair(
"Grid/FullUpdate", std::make_pair(
true, Parameters::kGridGlobalFullUpdate())));
307 removedParameters_.insert(std::make_pair(
"Grid/3DGroundIsObstacle", std::make_pair(
true, Parameters::kGridGroundIsObstacle())));
310 removedParameters_.insert(std::make_pair(
"Optimizer/Slam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
311 removedParameters_.insert(std::make_pair(
"OdomF2M/FixedMapPath", std::make_pair(
false,
"")));
314 removedParameters_.insert(std::make_pair(
"Grid/FlatObstaclesDetected", std::make_pair(
true, Parameters::kGridFlatObstacleDetected())));
317 removedParameters_.insert(std::make_pair(
"Reg/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
318 removedParameters_.insert(std::make_pair(
"OdomF2M/ScanSubstractRadius", std::make_pair(
true, Parameters::kOdomF2MScanSubtractRadius())));
321 removedParameters_.insert(std::make_pair(
"RGBD/ProximityPathScansMerged", std::make_pair(
false,
"")));
324 removedParameters_.insert(std::make_pair(
"Mem/ImageDecimation", std::make_pair(
true, Parameters::kMemImagePostDecimation())));
327 removedParameters_.insert(std::make_pair(
"OdomLocalMap/HistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
328 removedParameters_.insert(std::make_pair(
"OdomLocalMap/FixedMapPath", std::make_pair(
false,
"")));
329 removedParameters_.insert(std::make_pair(
"OdomF2F/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
330 removedParameters_.insert(std::make_pair(
"OdomF2F/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
333 removedParameters_.insert(std::make_pair(
"OdomBow/LocalHistorySize", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
334 removedParameters_.insert(std::make_pair(
"OdomBow/FixedLocalMapPath", std::make_pair(
false,
"")));
335 removedParameters_.insert(std::make_pair(
"OdomFlow/KeyFrameThr", std::make_pair(
false, Parameters::kOdomKeyFrameThr())));
336 removedParameters_.insert(std::make_pair(
"OdomFlow/GuessMotion", std::make_pair(
true, Parameters::kOdomGuessMotion())));
338 removedParameters_.insert(std::make_pair(
"Kp/WordsPerImage", std::make_pair(
true, Parameters::kKpMaxFeatures())));
340 removedParameters_.insert(std::make_pair(
"Mem/LocalSpaceLinksKeptInWM", std::make_pair(
false,
"")));
342 removedParameters_.insert(std::make_pair(
"RGBD/PoseScanMatching", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
344 removedParameters_.insert(std::make_pair(
"Odom/ParticleFiltering", std::make_pair(
false, Parameters::kOdomFilteringStrategy())));
345 removedParameters_.insert(std::make_pair(
"Odom/FeatureType", std::make_pair(
true, Parameters::kVisFeatureType())));
346 removedParameters_.insert(std::make_pair(
"Odom/EstimationType", std::make_pair(
true, Parameters::kVisEstimationType())));
347 removedParameters_.insert(std::make_pair(
"Odom/MaxFeatures", std::make_pair(
true, Parameters::kVisMaxFeatures())));
348 removedParameters_.insert(std::make_pair(
"Odom/InlierDistance", std::make_pair(
true, Parameters::kVisInlierDistance())));
349 removedParameters_.insert(std::make_pair(
"Odom/MinInliers", std::make_pair(
true, Parameters::kVisMinInliers())));
350 removedParameters_.insert(std::make_pair(
"Odom/Iterations", std::make_pair(
true, Parameters::kVisIterations())));
351 removedParameters_.insert(std::make_pair(
"Odom/RefineIterations", std::make_pair(
true, Parameters::kVisRefineIterations())));
352 removedParameters_.insert(std::make_pair(
"Odom/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
353 removedParameters_.insert(std::make_pair(
"Odom/RoiRatios", std::make_pair(
true, Parameters::kVisRoiRatios())));
354 removedParameters_.insert(std::make_pair(
"Odom/Force2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
355 removedParameters_.insert(std::make_pair(
"Odom/VarianceFromInliersCount", std::make_pair(
false,
"")));
356 removedParameters_.insert(std::make_pair(
"Odom/PnPReprojError", std::make_pair(
true, Parameters::kVisPnPReprojError())));
357 removedParameters_.insert(std::make_pair(
"Odom/PnPFlags", std::make_pair(
true, Parameters::kVisPnPFlags())));
359 removedParameters_.insert(std::make_pair(
"OdomBow/NNType", std::make_pair(
true, Parameters::kVisCorNNType())));
360 removedParameters_.insert(std::make_pair(
"OdomBow/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
362 removedParameters_.insert(std::make_pair(
"OdomFlow/WinSize", std::make_pair(
true, Parameters::kVisCorFlowWinSize())));
363 removedParameters_.insert(std::make_pair(
"OdomFlow/Iterations", std::make_pair(
true, Parameters::kVisCorFlowIterations())));
364 removedParameters_.insert(std::make_pair(
"OdomFlow/Eps", std::make_pair(
true, Parameters::kVisCorFlowEps())));
365 removedParameters_.insert(std::make_pair(
"OdomFlow/MaxLevel", std::make_pair(
true, Parameters::kVisCorFlowMaxLevel())));
367 removedParameters_.insert(std::make_pair(
"OdomSubPix/WinSize", std::make_pair(
true, Parameters::kVisSubPixWinSize())));
368 removedParameters_.insert(std::make_pair(
"OdomSubPix/Iterations", std::make_pair(
true, Parameters::kVisSubPixIterations())));
369 removedParameters_.insert(std::make_pair(
"OdomSubPix/Eps", std::make_pair(
true, Parameters::kVisSubPixEps())));
371 removedParameters_.insert(std::make_pair(
"LccReextract/Activated", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
372 removedParameters_.insert(std::make_pair(
"LccReextract/FeatureType", std::make_pair(
false, Parameters::kVisFeatureType())));
373 removedParameters_.insert(std::make_pair(
"LccReextract/MaxWords", std::make_pair(
false, Parameters::kVisMaxFeatures())));
374 removedParameters_.insert(std::make_pair(
"LccReextract/MaxDepth", std::make_pair(
false, Parameters::kVisMaxDepth())));
375 removedParameters_.insert(std::make_pair(
"LccReextract/RoiRatios", std::make_pair(
false, Parameters::kVisRoiRatios())));
376 removedParameters_.insert(std::make_pair(
"LccReextract/NNType", std::make_pair(
false, Parameters::kVisCorNNType())));
377 removedParameters_.insert(std::make_pair(
"LccReextract/NNDR", std::make_pair(
false, Parameters::kVisCorNNDR())));
379 removedParameters_.insert(std::make_pair(
"LccBow/EstimationType", std::make_pair(
false, Parameters::kVisEstimationType())));
380 removedParameters_.insert(std::make_pair(
"LccBow/InlierDistance", std::make_pair(
false, Parameters::kVisInlierDistance())));
381 removedParameters_.insert(std::make_pair(
"LccBow/MinInliers", std::make_pair(
false, Parameters::kVisMinInliers())));
382 removedParameters_.insert(std::make_pair(
"LccBow/Iterations", std::make_pair(
false, Parameters::kVisIterations())));
383 removedParameters_.insert(std::make_pair(
"LccBow/RefineIterations", std::make_pair(
false, Parameters::kVisRefineIterations())));
384 removedParameters_.insert(std::make_pair(
"LccBow/Force2D", std::make_pair(
false, Parameters::kRegForce3DoF())));
385 removedParameters_.insert(std::make_pair(
"LccBow/VarianceFromInliersCount", std::make_pair(
false,
"")));
386 removedParameters_.insert(std::make_pair(
"LccBow/PnPReprojError", std::make_pair(
false, Parameters::kVisPnPReprojError())));
387 removedParameters_.insert(std::make_pair(
"LccBow/PnPFlags", std::make_pair(
false, Parameters::kVisPnPFlags())));
388 removedParameters_.insert(std::make_pair(
"LccBow/EpipolarGeometryVar", std::make_pair(
true, Parameters::kVisEpipolarGeometryVar())));
390 removedParameters_.insert(std::make_pair(
"LccIcp/Type", std::make_pair(
false, Parameters::kRegStrategy())));
392 removedParameters_.insert(std::make_pair(
"LccIcp3/Decimation", std::make_pair(
false,
"")));
393 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxDepth", std::make_pair(
false,
"")));
394 removedParameters_.insert(std::make_pair(
"LccIcp3/VoxelSize", std::make_pair(
false, Parameters::kIcpVoxelSize())));
395 removedParameters_.insert(std::make_pair(
"LccIcp3/Samples", std::make_pair(
false, Parameters::kIcpDownsamplingStep())));
396 removedParameters_.insert(std::make_pair(
"LccIcp3/MaxCorrespondenceDistance", std::make_pair(
false, Parameters::kIcpMaxCorrespondenceDistance())));
397 removedParameters_.insert(std::make_pair(
"LccIcp3/Iterations", std::make_pair(
false, Parameters::kIcpIterations())));
398 removedParameters_.insert(std::make_pair(
"LccIcp3/CorrespondenceRatio", std::make_pair(
false, Parameters::kIcpCorrespondenceRatio())));
399 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlane", std::make_pair(
true, Parameters::kIcpPointToPlane())));
400 removedParameters_.insert(std::make_pair(
"LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(
true, Parameters::kIcpPointToPlaneK())));
402 removedParameters_.insert(std::make_pair(
"LccIcp2/MaxCorrespondenceDistance", std::make_pair(
true, Parameters::kIcpMaxCorrespondenceDistance())));
403 removedParameters_.insert(std::make_pair(
"LccIcp2/Iterations", std::make_pair(
true, Parameters::kIcpIterations())));
404 removedParameters_.insert(std::make_pair(
"LccIcp2/CorrespondenceRatio", std::make_pair(
true, Parameters::kIcpCorrespondenceRatio())));
405 removedParameters_.insert(std::make_pair(
"LccIcp2/VoxelSize", std::make_pair(
true, Parameters::kIcpVoxelSize())));
407 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionByTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
408 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionBySpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
409 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionTime", std::make_pair(
true, Parameters::kRGBDProximityByTime())));
410 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionSpace", std::make_pair(
true, Parameters::kRGBDProximityBySpace())));
411 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(
false,
"")));
412 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
413 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(
true, Parameters::kRGBDProximityPathFilteringRadius())));
414 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(
true, Parameters::kRGBDProximityPathRawPosesUsed())));
416 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeStrategy", std::make_pair(
true, Parameters::kOptimizerStrategy())));
417 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeEpsilon", std::make_pair(
true, Parameters::kOptimizerEpsilon())));
418 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
419 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeRobust", std::make_pair(
true, Parameters::kOptimizerRobust())));
420 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2D", std::make_pair(
true, Parameters::kRegForce3DoF())));
421 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeSlam2d", std::make_pair(
true, Parameters::kRegForce3DoF())));
422 removedParameters_.insert(std::make_pair(
"RGBD/OptimizeVarianceIgnored", std::make_pair(
true, Parameters::kOptimizerVarianceIgnored())));
424 removedParameters_.insert(std::make_pair(
"Stereo/WinSize", std::make_pair(
true, Parameters::kStereoWinWidth())));
427 removedParameters_.insert(std::make_pair(
"GFTT/MaxCorners", std::make_pair(
true, Parameters::kVisMaxFeatures())));
428 removedParameters_.insert(std::make_pair(
"LccBow/MaxDepth", std::make_pair(
true, Parameters::kVisMaxDepth())));
429 removedParameters_.insert(std::make_pair(
"LccReextract/LoopClosureFeatures", std::make_pair(
true, Parameters::kRGBDLoopClosureReextractFeatures())));
430 removedParameters_.insert(std::make_pair(
"Rtabmap/DetectorStrategy", std::make_pair(
true, Parameters::kKpDetectorStrategy())));
431 removedParameters_.insert(std::make_pair(
"RGBD/ScanMatchingSize", std::make_pair(
true, Parameters::kRGBDNeighborLinkRefining())));
432 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionRadius", std::make_pair(
true, Parameters::kRGBDLocalRadius())));
433 removedParameters_.insert(std::make_pair(
"RGBD/ToroIterations", std::make_pair(
true, Parameters::kOptimizerIterations())));
434 removedParameters_.insert(std::make_pair(
"Mem/RehearsedNodesKept", std::make_pair(
true, Parameters::kMemNotLinkedNodesKept())));
435 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
true, Parameters::kRGBDProximityMaxGraphDepth())));
436 removedParameters_.insert(std::make_pair(
"RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(
false,
"")));
437 removedParameters_.insert(std::make_pair(
"RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(
false,
"")));
438 removedParameters_.insert(std::make_pair(
"Odom/Type", std::make_pair(
true, Parameters::kVisFeatureType())));
439 removedParameters_.insert(std::make_pair(
"Odom/MaxWords", std::make_pair(
true, Parameters::kVisMaxFeatures())));
440 removedParameters_.insert(std::make_pair(
"Odom/LocalHistory", std::make_pair(
true, Parameters::kOdomF2MMaxSize())));
441 removedParameters_.insert(std::make_pair(
"Odom/NearestNeighbor", std::make_pair(
true, Parameters::kVisCorNNType())));
442 removedParameters_.insert(std::make_pair(
"Odom/NNDR", std::make_pair(
true, Parameters::kVisCorNNDR())));
454 for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=
removedParameters_.begin();
458 if(iter->second.first)
477 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.c_str());
488 description = iter->second;
492 UERROR(
"Parameters \"%s\" doesn't exist!", paramKey.c_str());
499 ParametersMap::const_iterator iter = parameters.find(key);
500 if(iter != parameters.end())
509 ParametersMap::const_iterator iter = parameters.find(key);
510 if(iter != parameters.end())
512 value =
uStr2Int(iter->second.c_str());
519 ParametersMap::const_iterator iter = parameters.find(key);
520 if(iter != parameters.end())
522 value =
uStr2Int(iter->second.c_str());
529 ParametersMap::const_iterator iter = parameters.find(key);
530 if(iter != parameters.end())
539 ParametersMap::const_iterator iter = parameters.find(key);
540 if(iter != parameters.end())
549 ParametersMap::const_iterator iter = parameters.find(key);
550 if(iter != parameters.end())
552 value = iter->second;
559 for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
561 ParametersMap::const_iterator jter = parameters.find(iter->first);
562 if(jter != parameters.end())
564 iter->second = jter->second;
571 return "RTAB-Map options:\n" 572 " --help Show usage.\n" 573 " --version Show version of rtabmap and its dependencies.\n" 574 " --params Show all parameters with their default value and description. \n" 575 " If a database path is set as last argument, the parameters in the \n" 576 " database will be shown in INI format.\n" 577 " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n" 578 " --SURF/HessianThreshold 150\n" 579 " For parameters in table format, add ',' between values :\n" 580 " --Kp/RoiRatios 0,0,0.1,0\n" 582 " --nolog Disable logger\n" 583 " --logconsole Set logger console type\n" 584 " --logfile \"path\" Set logger file type\n" 585 " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n" 586 " --udebug Set logger level to debug\n" 587 " --uinfo Set logger level to info\n" 588 " --uwarn Set logger level to warn\n" 589 " --uerror Set logger level to error\n" 590 " --logtime \"bool\" Print time when logging\n" 591 " --logwhere \"bool\" Print where when logging\n" 592 " --logthread \"bool\" Print thread id when logging\n" 600 const std::map<std::string, std::pair<bool, std::string> > & removedParams =
getRemovedParameters();
601 for(
int i=0;i<argc;++i)
603 bool checkParameters = onlyParameters;
606 if(strcmp(argv[i],
"--help") == 0)
611 else if(strcmp(argv[i],
"--version") == 0)
613 std::string str =
"RTAB-Map:";
616 std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
618 std::cout << str << std::setw(spacing - str.size()) << PCL_VERSION_PRETTY << std::endl;
621 std::cout << str << std::setw(spacing - str.size()) << vtkVersion::GetVTKVersion() << std::endl;
623 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
626 std::cout << str << std::setw(spacing - str.size()) << CV_VERSION << std::endl;
627 #if CV_MAJOR_VERSION >= 3 628 str =
"With OpenCV xfeatures2d:";
629 #ifdef HAVE_OPENCV_XFEATURES2D 630 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
632 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
635 str =
"With OpenCV nonfree:";
636 #ifdef RTABMAP_NONFREE 637 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
639 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
641 str =
"With ORB OcTree:";
642 #ifdef RTABMAP_ORB_OCTREE 643 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
645 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
647 str =
"With SuperPoint Torch:";
649 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
651 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
653 str =
"With Python3:";
654 #ifdef RTABMAP_PYTHON 655 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
657 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
659 str =
"With FastCV:";
660 #ifdef RTABMAP_FASTCV 661 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
663 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
665 str =
"With OpenGV:";
666 #ifdef RTABMAP_OPENGV 667 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
669 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
671 str =
"With Madgwick:";
672 #ifdef RTABMAP_MADGWICK 673 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
675 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
679 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
681 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
685 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
687 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
691 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
693 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
697 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
699 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
701 str =
"With Vertigo:";
702 #ifdef RTABMAP_VERTIGO 703 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
705 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
709 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
711 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
715 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
717 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
719 str =
"With OpenNI2:";
720 #ifdef RTABMAP_OPENNI2 721 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
723 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
725 str =
"With Freenect:";
726 #ifdef RTABMAP_FREENECT 727 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
729 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
731 str =
"With Freenect2:";
732 #ifdef RTABMAP_FREENECT2 733 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
735 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
739 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
741 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
745 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
747 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
749 str =
"With DC1394:";
750 #ifdef RTABMAP_DC1394 751 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
753 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
755 str =
"With FlyCapture2:";
756 #ifdef RTABMAP_FLYCAPTURE2 757 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
759 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
763 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
765 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
767 str =
"With ZED Open Capture:";
769 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
771 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
773 str =
"With RealSense:";
774 #ifdef RTABMAP_REALSENSE 775 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
777 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
779 str =
"With RealSense SLAM:";
780 #ifdef RTABMAP_REALSENSE_SLAM 781 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
783 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
785 str =
"With RealSense2:";
786 #ifdef RTABMAP_REALSENSE2 787 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
789 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
791 str =
"With MYNT EYE S:";
792 #ifdef RTABMAP_MYNTEYE 793 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
795 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
797 str =
"With DepthAI:";
798 #ifdef RTABMAP_DEPTHAI 799 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
801 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
803 str =
"With libpointmatcher:";
804 #ifdef RTABMAP_POINTMATCHER 805 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
807 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
809 str =
"With CCCoreLib:";
810 #ifdef RTABMAP_CCCORELIB 811 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
813 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
815 str =
"With octomap:";
816 #ifdef RTABMAP_OCTOMAP 817 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
819 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
821 str =
"With cpu-tsdf:";
822 #ifdef RTABMAP_CPUTSDF 823 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
825 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
827 str =
"With open chisel:";
828 #ifdef RTABMAP_OPENCHISEL 829 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
831 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
833 str =
"With Alice Vision:";
834 #ifdef RTABMAP_ALICE_VISION 835 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
837 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
841 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
843 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
847 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
849 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
853 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
855 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
859 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
861 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
865 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
867 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
869 #if RTABMAP_ORB_SLAM == 3 870 str =
"With ORB_SLAM3:";
871 #elif RTABMAP_ORB_SLAM == 2 872 str =
"With ORB_SLAM2:";
874 str =
"With ORB_SLAM:";
876 #ifdef RTABMAP_ORB_SLAM 877 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
879 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
883 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
885 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
887 str =
"With MSCKF_VIO:";
888 #ifdef RTABMAP_MSCKF_VIO 889 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
891 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
893 str =
"With VINS-Fusion:";
895 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
897 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
899 str =
"With OpenVINS:";
900 #ifdef RTABMAP_OPENVINS 901 std::cout << str << std::setw(spacing - str.size()) <<
"true" << std::endl;
903 std::cout << str << std::setw(spacing - str.size()) <<
"false" << std::endl;
907 else if(strcmp(argv[i],
"--nolog") == 0)
911 else if(strcmp(argv[i],
"--logconsole") == 0)
915 else if(strcmp(argv[i],
"--logfile") == 0)
924 UERROR(
"\"--logfile\" argument requires following file path");
927 else if(strcmp(argv[i],
"--logfilea") == 0)
936 UERROR(
"\"--logfilea\" argument requires following file path");
939 else if(strcmp(argv[i],
"--udebug") == 0)
943 else if(strcmp(argv[i],
"--uinfo") == 0)
947 else if(strcmp(argv[i],
"--uwarn") == 0)
951 else if(strcmp(argv[i],
"--uerror") == 0)
955 else if(strcmp(argv[i],
"--ulogtime") == 0)
964 UERROR(
"\"--ulogtime\" argument requires a following boolean value");
967 else if(strcmp(argv[i],
"--ulogwhere") == 0)
976 UERROR(
"\"--ulogwhere\" argument requires a following boolean value");
979 else if(strcmp(argv[i],
"--ulogthread") == 0)
988 UERROR(
"\"--ulogthread\" argument requires a following boolean value");
993 checkParameters =
true;
999 if(strcmp(argv[i],
"--params") == 0)
1004 std::string dbName = argv[argc - 1];
1012 if (!dbParameters.empty())
1014 std::cout <<
"[Core]" << std::endl;
1015 std::cout <<
"Version = " << RTABMAP_VERSION << std::endl;
1016 for (ParametersMap::const_iterator iter = dbParameters.begin(); iter != dbParameters.end(); ++iter)
1018 std::string key = iter->first;
1021 std::string value = iter->second.c_str();
1024 std::cout << key <<
" = " << value << std::endl;
1038 for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1040 bool ignore =
false;
1042 std::string group =
uSplit(iter->first,
'/').front();
1043 #ifndef RTABMAP_GTSAM 1044 if(group.compare(
"GTSAM") == 0)
1050 if(group.compare(
"g2o") == 0)
1055 #ifndef RTABMAP_FOVIS 1056 if(group.compare(
"OdomFovis") == 0)
1061 #ifndef RTABMAP_VISO2 1062 if(group.compare(
"OdomViso2") == 0)
1067 #ifndef RTABMAP_ORBSLAM2 1068 if(group.compare(
"OdomORBSLAM2") == 0)
1073 #ifndef RTABMAP_OKVIS 1074 if(group.compare(
"OdomOKVIS") == 0)
1079 #if not defined(RTABMAP_LOAM) and not defined(RTABMAP_FLOAM) 1080 if(group.compare(
"OdomLOAM") == 0)
1085 #ifndef RTABMAP_MSCKF_VIO 1086 if(group.compare(
"OdomMSCKF") == 0)
1093 std::string str =
"Param: " + iter->first +
" = \"" + iter->second +
"\"";
1096 std::setw(60 - str.size()) <<
1108 ParametersMap::const_iterator iter = parameters.find(key);
1109 if(iter != parameters.end())
1115 UINFO(
"Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
1121 std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
1122 if(jter!=removedParams.end())
1124 if(jter->second.first)
1129 std::string value = argv[i];
1133 key = jter->second.second;
1134 UWARN(
"Parameter migration from \"%s\" to \"%s\" (value=%s).",
1135 jter->first.c_str(), jter->second.second.c_str(), value.c_str());
1141 UERROR(
"Value missing for argument \"%s\"", argv[i-1]);
1144 else if(jter->second.second.empty())
1146 UERROR(
"Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
1150 UERROR(
"Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
1168 for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
1170 std::string key = (*iter).first.pItem;
1171 if(key.compare(
"Version") == 0)
1175 if(version.size() == 3)
1177 if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
1179 if(configFile.find(
".rtabmap") != std::string::npos)
1181 UWARN(
"Version in the config file \"%s\" is more recent (\"%s\") than " 1182 "current RTAB-Map version used (\"%s\"). The config file will be upgraded " 1190 UERROR(
"Version in the config file \"%s\" is more recent (\"%s\") than " 1191 "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will " 1208 if(oldIter->second.first)
1210 if(parameters.find(oldIter->second.second) == parameters.end())
1212 key = oldIter->second.second;
1213 UINFO(
"Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1217 else if(oldIter->second.second.empty())
1219 UWARN(
"Parameter \"%s\" doesn't exist anymore.",
1220 oldIter->first.c_str());
1222 else if(parameters.find(oldIter->second.second) == parameters.end())
1224 UWARN(
"Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1242 ULOGGER_WARN(
"Section \"Core\" in %s doesn't exist... " 1243 "Ignore this warning if the ini file does not exist yet. " 1244 "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
1254 ini.
SetValue(
"Core",
"Version", RTABMAP_VERSION,
NULL,
true);
1256 for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1258 std::string key = iter->first;
1261 std::string value = iter->second.c_str();
1264 ini.
SetValue(
"Core", key.c_str(), value.c_str(),
NULL,
true);
1270 for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter =
removedParameters_.begin();
1274 std::string key = iter->first;
1277 std::string value = ini.
GetValue(
"Core", key.c_str(),
"");
1279 if(ini.
Delete(
"Core", key.c_str(),
true))
1281 if(iter->second.first && parameters.find(iter->second.second) != parameters.end())
1283 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());
1287 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 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)
const TKeyVal * GetSection(const SI_CHAR *a_pSection) const
double UTILITE_EXP uStr2Double(const std::string &str)
std::multimap< Entry, const SI_CHAR *, typename Entry::KeyOrder > TKeyVal
static const char * showUsage()
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)
SI_Error SaveFile(const char *a_pszFile, bool a_bAddSignature=true) const
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)
bool openConnection(const std::string &url, bool overwritten=false)
#define UASSERT(condition)
Wrappers of STL for convenient functions.
std::list< std::string > uSplit(const std::string &str, char separator=' ')
static ParametersMap filterParameters(const ParametersMap ¶meters, const std::string &group, bool remove=false)
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="")
PM::Parameters Parameters
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 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()
#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)
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
ParametersMap getLastParameters() const
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)