Parameters.cpp
Go to the documentation of this file.
1 /*
2 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
3 All rights reserved.
4 
5 Redistribution and use in source and binary forms, with or without
6 modification, are permitted provided that the following conditions are met:
7  * Redistributions of source code must retain the above copyright
8  notice, this list of conditions and the following disclaimer.
9  * Redistributions in binary form must reproduce the above copyright
10  notice, this list of conditions and the following disclaimer in the
11  documentation and/or other materials provided with the distribution.
12  * Neither the name of the Universite de Sherbrooke nor the
13  names of its contributors may be used to endorse or promote products
14  derived from this software without specific prior written permission.
15 
16 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
17 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
18 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
19 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
20 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
21 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
22 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
23 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
24 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 */
27 
29 #include "rtabmap/core/DBDriver.h"
33 #include <rtabmap/utilite/UStl.h>
34 #include <rtabmap/utilite/UFile.h>
35 #include <cmath>
36 #include <stdlib.h>
37 #include <sstream>
38 #include <iostream>
39 #include <iomanip>
40 #include "SimpleIni.h"
41 #include <opencv2/core/version.hpp>
42 #include <pcl/pcl_config.h>
43 #include <opencv2/opencv_modules.hpp>
44 #ifndef DISABLE_VTK
45 #include <vtkVersion.h>
46 #endif
47 
48 namespace rtabmap
49 {
50 
55 std::map<std::string, std::pair<bool, std::string> > Parameters::removedParameters_;
57 
59 {
60 }
61 
63 {
64 }
65 
67 {
68  std::string path = UDirectory::homeDir();
69  if(!path.empty())
70  {
73 
74  }
75  else
76  {
77  UFATAL("Can't get the HOME variable environment!");
78  }
79  return path;
80 }
81 
83 {
84  return RTABMAP_VERSION;
85  return ""; // Second return only to avoid compiler warning with RTABMAP_VERSION not yet set.
86 }
87 
89 {
90  return "rtabmap.db";
91 }
92 
93 std::string Parameters::serialize(const ParametersMap & parameters)
94 {
95  std::stringstream output;
96  for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
97  {
98  if(iter != parameters.begin())
99  {
100  output << ";";
101  }
102  // make sure there are no commas instead of dots
103  output << iter->first << ":" << uReplaceChar(iter->second, ',', '.');
104  }
105  UDEBUG("output=%s", output.str().c_str());
106  return output.str();
107 }
108 
109 ParametersMap Parameters::deserialize(const std::string & parameters)
110 {
111  UDEBUG("parameters=%s", parameters.c_str());
112  ParametersMap output;
113  std::list<std::string> tuplets = uSplit(parameters, ';');
114  for(std::list<std::string>::iterator iter=tuplets.begin(); iter!=tuplets.end(); ++iter)
115  {
116  std::list<std::string> p = uSplit(*iter, ':');
117  if(p.size() == 2)
118  {
119  std::string key = p.front();
120  std::string value = p.back();
121 
122  // look for old parameter name
123  bool addParameter = true;
124  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
125  if(oldIter!=Parameters::getRemovedParameters().end())
126  {
127  addParameter = oldIter->second.first;
128  if(addParameter)
129  {
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());
133  }
134  else if(oldIter->second.second.empty())
135  {
136  UWARN("Parameter \"%s\" doesn't exist anymore.",
137  oldIter->first.c_str());
138  }
139  else
140  {
141  UWARN("Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
142  oldIter->first.c_str(), oldIter->second.second.c_str(), Parameters::getDescription(oldIter->second.second).c_str());
143  }
144 
145  }
146 
147  if(oldIter==Parameters::getRemovedParameters().end() &&
149  {
150  UWARN("Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
151  }
152  uInsert(output, ParametersPair(key, value));
153  }
154  }
155  return output;
156 }
157 
158 bool Parameters::isFeatureParameter(const std::string & parameter)
159 {
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;
172 }
173 
175 {
176  rtabmap::ParametersMap odomParameters;
178  for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
179  {
180  std::string group = uSplit(iter->first, '/').front();
181  if(uStrContains(group, "Odom") ||
182  (stereo && group.compare("Stereo") == 0) ||
183  (icp && group.compare("Icp") == 0) ||
184  (vis && Parameters::isFeatureParameter(iter->first)) ||
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)
193  {
194  odomParameters.insert(*iter);
195  }
196  }
197  return odomParameters;
198 }
199 
201 {
202  rtabmap::ParametersMap parameters;
204  for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
205  {
206  UASSERT(uSplit(iter->first, '/').size() == 2);
207  std::string group = uSplit(iter->first, '/').front();
208  if(group.compare(groupIn) == 0)
209  {
210  parameters.insert(*iter);
211  }
212  }
213  UASSERT_MSG(parameters.size(), uFormat("No parameters found for group %s!", groupIn.c_str()).c_str());
214  return parameters;
215 }
216 
217 ParametersMap Parameters::filterParameters(const ParametersMap & parameters, const std::string & groupIn, bool remove)
218 {
219  ParametersMap output;
220  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
221  {
222  UASSERT(uSplit(iter->first, '/').size() == 2);
223  std::string group = uSplit(iter->first, '/').front();
224  bool sameGroup = group.compare(groupIn) == 0;
225  if((!remove && sameGroup) || (remove && !sameGroup))
226  {
227  output.insert(*iter);
228  }
229  }
230  return output;
231 }
232 
233 const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemovedParameters()
234 {
235  if(removedParameters_.empty())
236  {
237  // removed parameters
238 
239  // 0.21.13
240  removedParameters_.insert(std::make_pair("Vis/ForwardEstOnly", std::make_pair(false, "")));
241 
242  // 0.21.7
243  removedParameters_.insert(std::make_pair("SIFT/NFeatures", std::make_pair(false, "")));
244 
245  // 0.21.3
246  removedParameters_.insert(std::make_pair("GridGlobal/FullUpdate", std::make_pair(false, "")));
247 
248  // 0.20.15
249  removedParameters_.insert(std::make_pair("Grid/FromDepth", std::make_pair(true, Parameters::kGridSensor())));
250 
251  // 0.20.9
252  removedParameters_.insert(std::make_pair("OdomORBSLAM2/VocPath", std::make_pair(true, Parameters::kOdomORBSLAMVocPath())));
253  removedParameters_.insert(std::make_pair("OdomORBSLAM2/Bf", std::make_pair(true, Parameters::kOdomORBSLAMBf())));
254  removedParameters_.insert(std::make_pair("OdomORBSLAM2/ThDepth", std::make_pair(true, Parameters::kOdomORBSLAMThDepth())));
255  removedParameters_.insert(std::make_pair("OdomORBSLAM2/Fps", std::make_pair(true, Parameters::kOdomORBSLAMFps())));
256  removedParameters_.insert(std::make_pair("OdomORBSLAM2/MaxFeatures", std::make_pair(true, Parameters::kOdomORBSLAMMaxFeatures())));
257  removedParameters_.insert(std::make_pair("OdomORBSLAM2/MapSize", std::make_pair(true, Parameters::kOdomORBSLAMMapSize())));
258 
259  removedParameters_.insert(std::make_pair("RGBD/SavedLocalizationIgnored", std::make_pair(true, Parameters::kRGBDStartAtOrigin())));
260 
261  removedParameters_.insert(std::make_pair("Icp/PMForce4DoF", std::make_pair(true, Parameters::kIcpForce4DoF())));
262  removedParameters_.insert(std::make_pair("Icp/PM", std::make_pair(true, Parameters::kIcpStrategy()))); // convert "true" to "1"
263  removedParameters_.insert(std::make_pair("Icp/PMOutlierRatio", std::make_pair(true, Parameters::kIcpOutlierRatio())));
264 
265  // 0.20.
266  removedParameters_.insert(std::make_pair("SuperGlue/Path", std::make_pair(true, Parameters::kPyMatcherPath())));
267  removedParameters_.insert(std::make_pair("SuperGlue/Iterations", std::make_pair(true, Parameters::kPyMatcherIterations())));
268  removedParameters_.insert(std::make_pair("SuperGlue/MatchThreshold", std::make_pair(true, Parameters::kPyMatcherThreshold())));
269  removedParameters_.insert(std::make_pair("SuperGlue/Cuda", std::make_pair(true, Parameters::kPyMatcherCuda())));
270  removedParameters_.insert(std::make_pair("SuperGlue/Indoor", std::make_pair(false, Parameters::kPyMatcherModel())));
271 
272  removedParameters_.insert(std::make_pair("Vis/CorCrossCheck", std::make_pair(false, Parameters::kVisCorNNType())));
273  removedParameters_.insert(std::make_pair("SPTorch/ModelPath", std::make_pair(true, Parameters::kSuperPointModelPath())));
274  removedParameters_.insert(std::make_pair("SPTorch/Threshold", std::make_pair(true, Parameters::kSuperPointThreshold())));
275  removedParameters_.insert(std::make_pair("SPTorch/NMS", std::make_pair(true, Parameters::kSuperPointNMS())));
276  removedParameters_.insert(std::make_pair("SPTorch/MinDistance", std::make_pair(true, Parameters::kSuperPointNMSRadius())));
277  removedParameters_.insert(std::make_pair("SPTorch/Cuda", std::make_pair(true, Parameters::kSuperPointCuda())));
278 
279  // 0.19.4
280  removedParameters_.insert(std::make_pair("RGBD/MaxLocalizationDistance", std::make_pair(true, Parameters::kRGBDMaxLoopClosureDistance())));
281 
282  // 0.19.3
283  removedParameters_.insert(std::make_pair("Aruco/Dictionary", std::make_pair(true, Parameters::kMarkerDictionary())));
284  removedParameters_.insert(std::make_pair("Aruco/MarkerLength", std::make_pair(true, Parameters::kMarkerLength())));
285  removedParameters_.insert(std::make_pair("Aruco/MaxDepthError", std::make_pair(true, Parameters::kMarkerMaxDepthError())));
286  removedParameters_.insert(std::make_pair("Aruco/VarianceLinear", std::make_pair(true, Parameters::kMarkerVarianceLinear())));
287  removedParameters_.insert(std::make_pair("Aruco/VarianceAngular", std::make_pair(true, Parameters::kMarkerVarianceAngular())));
288  removedParameters_.insert(std::make_pair("Aruco/CornerRefinementMethod", std::make_pair(true, Parameters::kMarkerCornerRefinementMethod())));
289 
290  // 0.17.5
291  removedParameters_.insert(std::make_pair("Grid/OctoMapOccupancyThr", std::make_pair(true, Parameters::kGridGlobalOccupancyThr())));
292 
293  // 0.17.0
294  removedParameters_.insert(std::make_pair("Grid/Scan2dMaxFilledRange", std::make_pair(false, Parameters::kGridRangeMax())));
295 
296  // 0.16.0
297  removedParameters_.insert(std::make_pair("Grid/ProjRayTracing", std::make_pair(true, Parameters::kGridRayTracing())));
298  removedParameters_.insert(std::make_pair("Grid/DepthMin", std::make_pair(true, Parameters::kGridRangeMin())));
299  removedParameters_.insert(std::make_pair("Grid/DepthMax", std::make_pair(true, Parameters::kGridRangeMax())));
300 
301  // 0.15.1
302  removedParameters_.insert(std::make_pair("Reg/VarianceFromInliersCount", std::make_pair(false, "")));
303  removedParameters_.insert(std::make_pair("Reg/VarianceNormalized", std::make_pair(false, "")));
304 
305  // 0.13.3
306  removedParameters_.insert(std::make_pair("Icp/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
307 
308 
309  // 0.13.1
310  removedParameters_.insert(std::make_pair("Rtabmap/VhStrategy", std::make_pair(true, Parameters::kVhEpEnabled())));
311 
312  // 0.12.5
313  removedParameters_.insert(std::make_pair("Grid/FullUpdate", std::make_pair(false, "")));
314 
315  // 0.12.1
316  removedParameters_.insert(std::make_pair("Grid/3DGroundIsObstacle", std::make_pair(true, Parameters::kGridGroundIsObstacle())));
317 
318  // 0.11.12
319  removedParameters_.insert(std::make_pair("Optimizer/Slam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
320  removedParameters_.insert(std::make_pair("OdomF2M/FixedMapPath", std::make_pair(false, "")));
321 
322  // 0.11.10 typos
323  removedParameters_.insert(std::make_pair("Grid/FlatObstaclesDetected", std::make_pair(true, Parameters::kGridFlatObstacleDetected())));
324 
325  // 0.11.8
326  removedParameters_.insert(std::make_pair("Reg/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
327  removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius", std::make_pair(true, Parameters::kOdomF2MScanSubtractRadius())));
328 
329  // 0.11.6
330  removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false, "")));
331 
332  // 0.11.3
333  removedParameters_.insert(std::make_pair("Mem/ImageDecimation", std::make_pair(true, Parameters::kMemImagePostDecimation())));
334 
335  // 0.11.2
336  removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
337  removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath", std::make_pair(false, "")));
338  removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
339  removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
340 
341  // 0.11.0
342  removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
343  removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath", std::make_pair(false, "")));
344  removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
345  removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
346 
347  removedParameters_.insert(std::make_pair("Kp/WordsPerImage", std::make_pair(true, Parameters::kKpMaxFeatures())));
348 
349  removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM", std::make_pair(false, "")));
350 
351  removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
352 
353  removedParameters_.insert(std::make_pair("Odom/ParticleFiltering", std::make_pair(false, Parameters::kOdomFilteringStrategy())));
354  removedParameters_.insert(std::make_pair("Odom/FeatureType", std::make_pair(true, Parameters::kVisFeatureType())));
355  removedParameters_.insert(std::make_pair("Odom/EstimationType", std::make_pair(true, Parameters::kVisEstimationType())));
356  removedParameters_.insert(std::make_pair("Odom/MaxFeatures", std::make_pair(true, Parameters::kVisMaxFeatures())));
357  removedParameters_.insert(std::make_pair("Odom/InlierDistance", std::make_pair(true, Parameters::kVisInlierDistance())));
358  removedParameters_.insert(std::make_pair("Odom/MinInliers", std::make_pair(true, Parameters::kVisMinInliers())));
359  removedParameters_.insert(std::make_pair("Odom/Iterations", std::make_pair(true, Parameters::kVisIterations())));
360  removedParameters_.insert(std::make_pair("Odom/RefineIterations", std::make_pair(true, Parameters::kVisRefineIterations())));
361  removedParameters_.insert(std::make_pair("Odom/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
362  removedParameters_.insert(std::make_pair("Odom/RoiRatios", std::make_pair(true, Parameters::kVisRoiRatios())));
363  removedParameters_.insert(std::make_pair("Odom/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
364  removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(false, "")));
365  removedParameters_.insert(std::make_pair("Odom/PnPReprojError", std::make_pair(true, Parameters::kVisPnPReprojError())));
366  removedParameters_.insert(std::make_pair("Odom/PnPFlags", std::make_pair(true, Parameters::kVisPnPFlags())));
367 
368  removedParameters_.insert(std::make_pair("OdomBow/NNType", std::make_pair(true, Parameters::kVisCorNNType())));
369  removedParameters_.insert(std::make_pair("OdomBow/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
370 
371  removedParameters_.insert(std::make_pair("OdomFlow/WinSize", std::make_pair(true, Parameters::kVisCorFlowWinSize())));
372  removedParameters_.insert(std::make_pair("OdomFlow/Iterations", std::make_pair(true, Parameters::kVisCorFlowIterations())));
373  removedParameters_.insert(std::make_pair("OdomFlow/Eps", std::make_pair(true, Parameters::kVisCorFlowEps())));
374  removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel", std::make_pair(true, Parameters::kVisCorFlowMaxLevel())));
375 
376  removedParameters_.insert(std::make_pair("OdomSubPix/WinSize", std::make_pair(true, Parameters::kVisSubPixWinSize())));
377  removedParameters_.insert(std::make_pair("OdomSubPix/Iterations", std::make_pair(true, Parameters::kVisSubPixIterations())));
378  removedParameters_.insert(std::make_pair("OdomSubPix/Eps", std::make_pair(true, Parameters::kVisSubPixEps())));
379 
380  removedParameters_.insert(std::make_pair("LccReextract/Activated", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
381  removedParameters_.insert(std::make_pair("LccReextract/FeatureType", std::make_pair(false, Parameters::kVisFeatureType())));
382  removedParameters_.insert(std::make_pair("LccReextract/MaxWords", std::make_pair(false, Parameters::kVisMaxFeatures())));
383  removedParameters_.insert(std::make_pair("LccReextract/MaxDepth", std::make_pair(false, Parameters::kVisMaxDepth())));
384  removedParameters_.insert(std::make_pair("LccReextract/RoiRatios", std::make_pair(false, Parameters::kVisRoiRatios())));
385  removedParameters_.insert(std::make_pair("LccReextract/NNType", std::make_pair(false, Parameters::kVisCorNNType())));
386  removedParameters_.insert(std::make_pair("LccReextract/NNDR", std::make_pair(false, Parameters::kVisCorNNDR())));
387 
388  removedParameters_.insert(std::make_pair("LccBow/EstimationType", std::make_pair(false, Parameters::kVisEstimationType())));
389  removedParameters_.insert(std::make_pair("LccBow/InlierDistance", std::make_pair(false, Parameters::kVisInlierDistance())));
390  removedParameters_.insert(std::make_pair("LccBow/MinInliers", std::make_pair(false, Parameters::kVisMinInliers())));
391  removedParameters_.insert(std::make_pair("LccBow/Iterations", std::make_pair(false, Parameters::kVisIterations())));
392  removedParameters_.insert(std::make_pair("LccBow/RefineIterations", std::make_pair(false, Parameters::kVisRefineIterations())));
393  removedParameters_.insert(std::make_pair("LccBow/Force2D", std::make_pair(false, Parameters::kRegForce3DoF())));
394  removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false, "")));
395  removedParameters_.insert(std::make_pair("LccBow/PnPReprojError", std::make_pair(false, Parameters::kVisPnPReprojError())));
396  removedParameters_.insert(std::make_pair("LccBow/PnPFlags", std::make_pair(false, Parameters::kVisPnPFlags())));
397  removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar", std::make_pair(true, Parameters::kVisEpipolarGeometryVar())));
398 
399  removedParameters_.insert(std::make_pair("LccIcp/Type", std::make_pair(false, Parameters::kRegStrategy())));
400 
401  removedParameters_.insert(std::make_pair("LccIcp3/Decimation", std::make_pair(false, "")));
402  removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth", std::make_pair(false, "")));
403  removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize", std::make_pair(false, Parameters::kIcpVoxelSize())));
404  removedParameters_.insert(std::make_pair("LccIcp3/Samples", std::make_pair(false, Parameters::kIcpDownsamplingStep())));
405  removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance", std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
406  removedParameters_.insert(std::make_pair("LccIcp3/Iterations", std::make_pair(false, Parameters::kIcpIterations())));
407  removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio", std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
408  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane", std::make_pair(true, Parameters::kIcpPointToPlane())));
409  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
410 
411  removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance", std::make_pair(true, Parameters::kIcpMaxCorrespondenceDistance())));
412  removedParameters_.insert(std::make_pair("LccIcp2/Iterations", std::make_pair(true, Parameters::kIcpIterations())));
413  removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio", std::make_pair(true, Parameters::kIcpCorrespondenceRatio())));
414  removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize", std::make_pair(true, Parameters::kIcpVoxelSize())));
415 
416  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
417  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
418  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
419  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
420  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(false, "")));
421  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
422  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true, Parameters::kRGBDProximityPathFilteringRadius())));
423  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(true, Parameters::kRGBDProximityPathRawPosesUsed())));
424 
425  removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy", std::make_pair(true, Parameters::kOptimizerStrategy())));
426  removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon", std::make_pair(true, Parameters::kOptimizerEpsilon())));
427  removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
428  removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust", std::make_pair(true, Parameters::kOptimizerRobust())));
429  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
430  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d", std::make_pair(true, Parameters::kRegForce3DoF())));
431  removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored", std::make_pair(true, Parameters::kOptimizerVarianceIgnored())));
432 
433  removedParameters_.insert(std::make_pair("Stereo/WinSize", std::make_pair(true, Parameters::kStereoWinWidth())));
434 
435  // before 0.11.0
436  removedParameters_.insert(std::make_pair("GFTT/MaxCorners", std::make_pair(true, Parameters::kVisMaxFeatures())));
437  removedParameters_.insert(std::make_pair("LccBow/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
438  removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
439  removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy", std::make_pair(true, Parameters::kKpDetectorStrategy())));
440  removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
441  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius", std::make_pair(true, Parameters::kRGBDLocalRadius())));
442  removedParameters_.insert(std::make_pair("RGBD/ToroIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
443  removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept", std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
444  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
445  removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(false, "")));
446  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
447  removedParameters_.insert(std::make_pair("Odom/Type", std::make_pair(true, Parameters::kVisFeatureType())));
448  removedParameters_.insert(std::make_pair("Odom/MaxWords", std::make_pair(true, Parameters::kVisMaxFeatures())));
449  removedParameters_.insert(std::make_pair("Odom/LocalHistory", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
450  removedParameters_.insert(std::make_pair("Odom/NearestNeighbor", std::make_pair(true, Parameters::kVisCorNNType())));
451  removedParameters_.insert(std::make_pair("Odom/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
452  }
453  return removedParameters_;
454 }
455 
457 {
458  if(backwardCompatibilityMap_.empty())
459  {
460  getRemovedParameters(); // make sure removedParameters is filled
461 
462  // compatibility
463  for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
464  iter!=removedParameters_.end();
465  ++iter)
466  {
467  if(iter->second.first)
468  {
469  backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
470  }
471  }
472  }
474 }
475 
476 std::string Parameters::getType(const std::string & paramKey)
477 {
478  std::string type;
479  ParametersMap::iterator iter = parametersType_.find(paramKey);
480  if(iter != parametersType_.end())
481  {
482  type = iter->second;
483  }
484  else
485  {
486  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
487  }
488  return type;
489 }
490 
491 std::string Parameters::getDescription(const std::string & paramKey)
492 {
493  std::string description;
494  ParametersMap::iterator iter = descriptions_.find(paramKey);
495  if(iter != descriptions_.end())
496  {
497  description = iter->second;
498  }
499  else
500  {
501  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
502  }
503  return description;
504 }
505 
506 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
507 {
508  ParametersMap::const_iterator iter = parameters.find(key);
509  if(iter != parameters.end())
510  {
511  value = uStr2Bool(iter->second.c_str());
512  return true;
513  }
514  return false;
515 }
516 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
517 {
518  ParametersMap::const_iterator iter = parameters.find(key);
519  if(iter != parameters.end())
520  {
521  value = uStr2Int(iter->second.c_str());
522  return true;
523  }
524  return false;
525 }
526 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
527 {
528  ParametersMap::const_iterator iter = parameters.find(key);
529  if(iter != parameters.end())
530  {
531  value = uStr2Int(iter->second.c_str());
532  return true;
533  }
534  return false;
535 }
536 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
537 {
538  ParametersMap::const_iterator iter = parameters.find(key);
539  if(iter != parameters.end())
540  {
541  value = uStr2Float(iter->second);
542  return true;
543  }
544  return false;
545 }
546 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
547 {
548  ParametersMap::const_iterator iter = parameters.find(key);
549  if(iter != parameters.end())
550  {
551  value = uStr2Double(iter->second);
552  return true;
553  }
554  return false;
555 }
556 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
557 {
558  ParametersMap::const_iterator iter = parameters.find(key);
559  if(iter != parameters.end())
560  {
561  value = iter->second;
562  return true;
563  }
564  return false;
565 }
566 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
567 {
568  for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
569  {
570  ParametersMap::const_iterator jter = parameters.find(iter->first);
571  if(jter != parameters.end())
572  {
573  iter->second = jter->second;
574  }
575  }
576 }
577 
578 const char * Parameters::showUsage()
579 {
580  return "RTAB-Map options:\n"
581  " --help Show usage.\n"
582  " --version Show version of rtabmap and its dependencies.\n"
583  " --params Show all parameters with their default value and description. \n"
584  " If a database path is set as last argument, the parameters in the \n"
585  " database will be shown in INI format.\n"
586  " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n"
587  " --SURF/HessianThreshold 150\n"
588  " For parameters in table format, add ',' between values :\n"
589  " --Kp/RoiRatios 0,0,0.1,0\n"
590  "Logger options:\n"
591  " --nolog Disable logger\n"
592  " --logconsole Set logger console type\n"
593  " --logfile \"path\" Set logger file type\n"
594  " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n"
595  " --udebug Set logger level to debug\n"
596  " --uinfo Set logger level to info\n"
597  " --uwarn Set logger level to warn\n"
598  " --uerror Set logger level to error\n"
599  " --logtime \"bool\" Print time when logging\n"
600  " --logwhere \"bool\" Print where when logging\n"
601  " --logthread \"bool\" Print thread id when logging\n"
602  ;
603 }
604 
605 ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParameters)
606 {
608  const ParametersMap & parameters = getDefaultParameters();
609  const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
610  for(int i=0;i<argc;++i)
611  {
612  bool checkParameters = onlyParameters;
613  if(!checkParameters)
614  {
615  if(strcmp(argv[i], "--help") == 0)
616  {
617  std::cout << showUsage() << std::endl;
618  exit(0);
619  }
620  else if(strcmp(argv[i], "--version") == 0)
621  {
622  std::string str = "RTAB-Map:";
623 
624  int spacing = 30;
625  std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
626  str = "PCL:";
627  std::cout << str << std::setw(spacing - str.size()) << PCL_VERSION_PRETTY << std::endl;
628  str = "With VTK:";
629 #ifndef DISABLE_VTK
630  std::cout << str << std::setw(spacing - str.size()) << vtkVersion::GetVTKVersion() << std::endl;
631 #else
632  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
633 #endif
634  str = "OpenCV:";
635  std::cout << str << std::setw(spacing - str.size()) << CV_VERSION << std::endl;
636 #if CV_MAJOR_VERSION >= 3
637  str = "With OpenCV xfeatures2d:";
638 #ifdef HAVE_OPENCV_XFEATURES2D
639  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
640 #else
641  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
642 #endif
643 #endif
644  str = "With OpenCV nonfree:";
645 #ifdef RTABMAP_NONFREE
646  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
647 #else
648  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
649 #endif
650  str = "With ORB OcTree:";
651 #ifdef RTABMAP_ORB_OCTREE
652  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
653 #else
654  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
655 #endif
656  str = "With SuperPoint Torch:";
657 #ifdef RTABMAP_TORCH
658  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
659 #else
660  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
661 #endif
662  str = "With Python3:";
663 #ifdef RTABMAP_PYTHON
664  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
665 #else
666  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
667 #endif
668  str = "With FastCV:";
669 #ifdef RTABMAP_FASTCV
670  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
671 #else
672  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
673 #endif
674  str = "With OpenGV:";
675 #ifdef RTABMAP_OPENGV
676  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
677 #else
678  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
679 #endif
680  str = "With Madgwick:";
681 #ifdef RTABMAP_MADGWICK
682  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
683 #else
684  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
685 #endif
686  str = "With PDAL:";
687 #ifdef RTABMAP_PDAL
688  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
689 #else
690  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
691 #endif
692  str = "With libLAS:";
693 #ifdef RTABMAP_LIBLAS
694  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
695 #else
696  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
697 #endif
698  str = "With CudaSift:";
699 #ifdef RTABMAP_CUDASIFT
700  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
701 #else
702  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
703 #endif
704  str = "With TORO:";
705 #ifdef RTABMAP_TORO
706  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
707 #else
708  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
709 #endif
710  str = "With g2o:";
711 #ifdef RTABMAP_G2O
712  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
713 #else
714  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
715 #endif
716  str = "With GTSAM:";
717 #ifdef RTABMAP_GTSAM
718  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
719 #else
720  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
721 #endif
722  str = "With Vertigo:";
723 #ifdef RTABMAP_VERTIGO
724  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
725 #else
726  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
727 #endif
728  str = "With CVSBA:";
729 #ifdef RTABMAP_CVSBA
730  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
731 #else
732  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
733 #endif
734  str = "With Ceres:";
735 #ifdef RTABMAP_CERES
736  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
737 #else
738  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
739 #endif
740  str = "With OpenNI:";
741 #ifdef RTABMAP_OPENNI
742  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
743 #else
744  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
745 #endif
746  str = "With OpenNI2:";
747 #ifdef RTABMAP_OPENNI2
748  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
749 #else
750  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
751 #endif
752  str = "With Freenect:";
753 #ifdef RTABMAP_FREENECT
754  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
755 #else
756  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
757 #endif
758  str = "With Freenect2:";
759 #ifdef RTABMAP_FREENECT2
760  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
761 #else
762  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
763 #endif
764  str = "With K4W2:";
765 #ifdef RTABMAP_K4W2
766  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
767 #else
768  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
769 #endif
770  str = "With K4A:";
771 #ifdef RTABMAP_K4A
772  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
773 #else
774  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
775 #endif
776  str = "With DC1394:";
777 #ifdef RTABMAP_DC1394
778  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
779 #else
780  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
781 #endif
782  str = "With FlyCapture2:";
783 #ifdef RTABMAP_FLYCAPTURE2
784  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
785 #else
786  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
787 #endif
788  str = "With ZED:";
789 #ifdef RTABMAP_ZED
790  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
791 #else
792  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
793 #endif
794  str = "With ZED Open Capture:";
795 #ifdef RTABMAP_ZEDOC
796  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
797 #else
798  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
799 #endif
800  str = "With RealSense:";
801 #ifdef RTABMAP_REALSENSE
802  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
803 #else
804  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
805 #endif
806  str = "With RealSense SLAM:";
807 #ifdef RTABMAP_REALSENSE_SLAM
808  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
809 #else
810  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
811 #endif
812  str = "With RealSense2:";
813 #ifdef RTABMAP_REALSENSE2
814  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
815 #else
816  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
817 #endif
818  str = "With MYNT EYE S:";
819 #ifdef RTABMAP_MYNTEYE
820  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
821 #else
822  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
823 #endif
824  str = "With DepthAI:";
825 #ifdef RTABMAP_DEPTHAI
826  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
827 #else
828  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
829 #endif
830  str = "With XVisio SDK:";
831 #ifdef RTABMAP_XVSDK
832  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
833 #else
834  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
835 #endif
836  str = "With libpointmatcher:";
837 #ifdef RTABMAP_POINTMATCHER
838  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
839 #else
840  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
841 #endif
842  str = "With CCCoreLib:";
843 #ifdef RTABMAP_CCCORELIB
844  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
845 #else
846  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
847 #endif
848  str = "With Open3D:";
849 #ifdef RTABMAP_OPEN3D
850  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
851 #else
852  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
853 #endif
854  str = "With OctoMap:";
855 #ifdef RTABMAP_OCTOMAP
856  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
857 #else
858  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
859 #endif
860  str = "With GridMap:";
861 #ifdef RTABMAP_GRIDMAP
862  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
863 #else
864  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
865 #endif
866  str = "With cpu-tsdf:";
867 #ifdef RTABMAP_CPUTSDF
868  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
869 #else
870  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
871 #endif
872  str = "With open chisel:";
873 #ifdef RTABMAP_OPENCHISEL
874  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
875 #else
876  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
877 #endif
878  str = "With Alice Vision:";
879 #ifdef RTABMAP_ALICE_VISION
880  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
881 #else
882  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
883 #endif
884  str = "With LOAM:";
885 #ifdef RTABMAP_LOAM
886  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
887 #else
888  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
889 #endif
890  str = "With FLOAM:";
891 #ifdef RTABMAP_FLOAM
892  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
893 #else
894  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
895 #endif
896  str = "With FOVIS:";
897 #ifdef RTABMAP_FOVIS
898  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
899 #else
900  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
901 #endif
902  str = "With Viso2:";
903 #ifdef RTABMAP_VISO2
904  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
905 #else
906  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
907 #endif
908  str = "With DVO:";
909 #ifdef RTABMAP_DVO
910  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
911 #else
912  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
913 #endif
914 #if RTABMAP_ORB_SLAM == 3
915  str = "With ORB_SLAM3:";
916 #elif RTABMAP_ORB_SLAM == 2
917  str = "With ORB_SLAM2:";
918 #else
919  str = "With ORB_SLAM:";
920 #endif
921 #ifdef RTABMAP_ORB_SLAM
922  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
923 #else
924  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
925 #endif
926  str = "With OKVIS:";
927 #ifdef RTABMAP_OKVIS
928  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
929 #else
930  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
931 #endif
932  str = "With MSCKF_VIO:";
933 #ifdef RTABMAP_MSCKF_VIO
934  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
935 #else
936  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
937 #endif
938  str = "With VINS-Fusion:";
939 #ifdef RTABMAP_VINS
940  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
941 #else
942  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
943 #endif
944  str = "With OpenVINS:";
945 #ifdef RTABMAP_OPENVINS
946  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
947 #else
948  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
949 #endif
950  exit(0);
951  }
952  else if(strcmp(argv[i], "--nolog") == 0)
953  {
955  }
956  else if(strcmp(argv[i], "--logconsole") == 0)
957  {
959  }
960  else if(strcmp(argv[i], "--logfile") == 0)
961  {
962  ++i;
963  if(i < argc)
964  {
966  }
967  else
968  {
969  UERROR("\"--logfile\" argument requires following file path");
970  }
971  }
972  else if(strcmp(argv[i], "--logfilea") == 0)
973  {
974  ++i;
975  if(i < argc)
976  {
978  }
979  else
980  {
981  UERROR("\"--logfilea\" argument requires following file path");
982  }
983  }
984  else if(strcmp(argv[i], "--udebug") == 0)
985  {
987  }
988  else if(strcmp(argv[i], "--uinfo") == 0)
989  {
991  }
992  else if(strcmp(argv[i], "--uwarn") == 0)
993  {
995  }
996  else if(strcmp(argv[i], "--uerror") == 0)
997  {
999  }
1000  else if(strcmp(argv[i], "--ulogtime") == 0)
1001  {
1002  ++i;
1003  if(i < argc)
1004  {
1006  }
1007  else
1008  {
1009  UERROR("\"--ulogtime\" argument requires a following boolean value");
1010  }
1011  }
1012  else if(strcmp(argv[i], "--ulogwhere") == 0)
1013  {
1014  ++i;
1015  if(i < argc)
1016  {
1018  }
1019  else
1020  {
1021  UERROR("\"--ulogwhere\" argument requires a following boolean value");
1022  }
1023  }
1024  else if(strcmp(argv[i], "--ulogthread") == 0)
1025  {
1026  ++i;
1027  if(i < argc)
1028  {
1030  }
1031  else
1032  {
1033  UERROR("\"--ulogthread\" argument requires a following boolean value");
1034  }
1035  }
1036  else
1037  {
1038  checkParameters = true;
1039  }
1040  }
1041 
1042  if(checkParameters) // check for parameters
1043  {
1044  if(strcmp(argv[i], "--params") == 0)
1045  {
1046  if (i < argc - 1)
1047  {
1048  // If the last argument is a database, dump the parameters in INI format
1049  std::string dbName = argv[argc - 1];
1050  if (UFile::exists(dbName) && UFile::getExtension(dbName).compare("db") == 0)
1051  {
1052  DBDriver * driver = DBDriver::create();
1053  bool read = false;
1054  if (driver->openConnection(dbName))
1055  {
1056  ParametersMap dbParameters = driver->getLastParameters();
1057  if (!dbParameters.empty())
1058  {
1059  std::cout << "[Core]" << std::endl;
1060  std::cout << "Version = " << RTABMAP_VERSION << std::endl;
1061  for (ParametersMap::const_iterator iter = dbParameters.begin(); iter != dbParameters.end(); ++iter)
1062  {
1063  std::string key = iter->first;
1064  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1065 
1066  std::string value = iter->second.c_str();
1067  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1068 
1069  std::cout << key << " = " << value << std::endl;
1070  }
1071  read = true;
1072  }
1073  driver->closeConnection(false);
1074  }
1075  delete driver;
1076  if (read)
1077  {
1078  exit(0);
1079  }
1080  }
1081  }
1082 
1083  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1084  {
1085  bool ignore = false;
1086  UASSERT(uSplit(iter->first, '/').size() == 2);
1087  std::string group = uSplit(iter->first, '/').front();
1088 #ifndef RTABMAP_GTSAM
1089  if(group.compare("GTSAM") == 0)
1090  {
1091  ignore = true;
1092  }
1093 #endif
1094 #ifndef RTABMAP_G2O
1095  if(group.compare("g2o") == 0)
1096  {
1097  ignore = true;
1098  }
1099 #endif
1100 #ifndef RTABMAP_FOVIS
1101  if(group.compare("OdomFovis") == 0)
1102  {
1103  ignore = true;
1104  }
1105 #endif
1106 #ifndef RTABMAP_VISO2
1107  if(group.compare("OdomViso2") == 0)
1108  {
1109  ignore = true;
1110  }
1111 #endif
1112 #ifndef RTABMAP_ORBSLAM2
1113  if(group.compare("OdomORBSLAM2") == 0)
1114  {
1115  ignore = true;
1116  }
1117 #endif
1118 #ifndef RTABMAP_OKVIS
1119  if(group.compare("OdomOKVIS") == 0)
1120  {
1121  ignore = true;
1122  }
1123 #endif
1124 #if not defined(RTABMAP_LOAM) and not defined(RTABMAP_FLOAM)
1125  if(group.compare("OdomLOAM") == 0)
1126  {
1127  ignore = true;
1128  }
1129 #endif
1130 #ifndef RTABMAP_MSCKF_VIO
1131  if(group.compare("OdomMSCKF") == 0)
1132  {
1133  ignore = true;
1134  }
1135 #endif
1136  if(!ignore)
1137  {
1138  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
1139  std::cout <<
1140  str <<
1141  std::setw(60 - str.size()) <<
1142  " [" <<
1143  rtabmap::Parameters::getDescription(iter->first).c_str() <<
1144  "]" <<
1145  std::endl;
1146  }
1147  }
1148  exit(0);
1149  }
1150  else
1151  {
1152  std::string key = uReplaceChar(argv[i], '-', "");
1153  ParametersMap::const_iterator iter = parameters.find(key);
1154  if(iter != parameters.end())
1155  {
1156  ++i;
1157  if(i < argc)
1158  {
1159  uInsert(out, ParametersPair(iter->first, argv[i]));
1160  UINFO("Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
1161  }
1162  }
1163  else
1164  {
1165  // backward compatibility
1166  std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
1167  if(jter!=removedParams.end())
1168  {
1169  if(jter->second.first)
1170  {
1171  ++i;
1172  if(i < argc)
1173  {
1174  std::string value = argv[i];
1175  if(!value.empty())
1176  {
1177  value = uReplaceChar(value, ',', ' '); // for table
1178  key = jter->second.second;
1179  UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
1180  jter->first.c_str(), jter->second.second.c_str(), value.c_str());
1182  }
1183  }
1184  else
1185  {
1186  UERROR("Value missing for argument \"%s\"", argv[i-1]);
1187  }
1188  }
1189  else if(jter->second.second.empty())
1190  {
1191  UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
1192  }
1193  else
1194  {
1195  UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
1196  }
1197  }
1198  }
1199  }
1200  }
1201  }
1202  return out;
1203 }
1204 
1205 void readINIImpl(const CSimpleIniA & ini, const std::string & configFilePath, ParametersMap & parameters, bool modifiedOnly)
1206 {
1207  const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
1208  if(keyValMap)
1209  {
1210  for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
1211  {
1212  std::string key = (*iter).first.pItem;
1213  if(key.compare("Version") == 0)
1214  {
1215  // Compare version in ini with the current RTAB-Map version
1216  std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
1217  if(version.size() == 3)
1218  {
1219  if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
1220  {
1221  if(configFilePath.find(".rtabmap") != std::string::npos)
1222  {
1223  UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
1224  "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
1225  "to new version.",
1226  configFilePath.c_str(),
1227  (*iter).second,
1228  RTABMAP_VERSION);
1229  }
1230  else
1231  {
1232  UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
1233  "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
1234  "be ignored.",
1235  configFilePath.c_str(),
1236  (*iter).second,
1237  RTABMAP_VERSION);
1238  }
1239  }
1240  }
1241  }
1242  else
1243  {
1244  key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
1245 
1246  // look for old parameter name
1247  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
1248  if(oldIter!=Parameters::getRemovedParameters().end())
1249  {
1250  if(oldIter->second.first)
1251  {
1252  if(parameters.find(oldIter->second.second) == parameters.end())
1253  {
1254  key = oldIter->second.second;
1255  UINFO("Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1256  oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second, Parameters::getDefaultParameters().at(oldIter->second.second).c_str());
1257  }
1258  }
1259  else if(oldIter->second.second.empty())
1260  {
1261  UWARN("Parameter \"%s\" doesn't exist anymore.",
1262  oldIter->first.c_str());
1263  }
1264  else if(parameters.find(oldIter->second.second) == parameters.end())
1265  {
1266  UWARN("Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1267  oldIter->first.c_str(), iter->second, oldIter->second.second.c_str(), Parameters::getDefaultParameters().at(oldIter->second.second).c_str(), Parameters::getDescription(oldIter->second.second).c_str());
1268  }
1269 
1270  }
1271 
1273  {
1274  if(!modifiedOnly || std::string(iter->second).compare(Parameters::getDefaultParameters().find(key)->second) != 0)
1275  {
1276  uInsert(parameters, ParametersPair(key, iter->second));
1277  }
1278  }
1279  }
1280  }
1281  }
1282  else
1283  {
1284  ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
1285  "Ignore this warning if the ini file does not exist yet. "
1286  "The ini file will be automatically created when rtabmap will close.", configFilePath.c_str());
1287  }
1288 }
1289 
1290 
1291 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly)
1292 {
1293  CSimpleIniA ini;
1294  ini.LoadFile(configFile.c_str());
1295  readINIImpl(ini, configFile, parameters, modifiedOnly);
1296 }
1297 
1298 void Parameters::readINIStr(const std::string & configContent, ParametersMap & parameters, bool modifiedOnly)
1299 {
1300  CSimpleIniA ini;
1301  ini.LoadData(configContent);
1302  readINIImpl(ini, "", parameters, modifiedOnly);
1303 }
1304 
1305 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
1306 {
1307  CSimpleIniA ini;
1308  ini.LoadFile(configFile.c_str());
1309 
1310  // Save current version
1311  ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
1312 
1313  for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1314  {
1315  std::string key = iter->first;
1316  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1317 
1318  std::string value = iter->second.c_str();
1319  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1320 
1321  ini.SetValue("Core", key.c_str(), value.c_str(), NULL, true);
1322  }
1323 
1324  // Delete removed parameters
1325  if(parameters.size() == getDefaultParameters().size())
1326  {
1327  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter = removedParameters_.begin();
1328  iter!=removedParameters_.end();
1329  ++iter)
1330  {
1331  std::string key = iter->first;
1332  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1333 
1334  std::string value = ini.GetValue("Core", key.c_str(), "");
1335 
1336  if(ini.Delete("Core", key.c_str(), true))
1337  {
1338  if(iter->second.first && parameters.find(iter->second.second) != parameters.end())
1339  {
1340  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());
1341  }
1342  else
1343  {
1344  UWARN("Removed deprecated parameter %s=%s from \"%s\".", iter->first.c_str(), value.c_str(), configFile.c_str());
1345  }
1346  }
1347  }
1348  }
1349 
1350  ini.SaveFile(configFile.c_str());
1351 }
1352 
1353 }
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
compare
bool compare
SimpleIni.h
UINFO
#define UINFO(...)
rtabmap::DBDriver::getLastParameters
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
rtabmap::Parameters::parameters_
static ParametersMap parameters_
Definition: Parameters.h:974
rtabmap::Parameters::readINIStr
static void readINIStr(const std::string &configContent, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1298
ULogger::kError
@ kError
Definition: ULogger.h:252
UDirectory::makeDir
static bool makeDir(const std::string &dirPath)
Definition: UDirectory.cpp:333
rtabmap::DBDriver::openConnection
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
rtabmap::Parameters::parseArguments
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
Definition: Parameters.cpp:605
ULogger::kTypeFile
@ kTypeFile
Definition: ULogger.h:244
UDirectory.h
ULogger::kTypeConsole
@ kTypeConsole
Definition: ULogger.h:244
size
Index size
uStr2Bool
bool UTILITE_EXPORT uStr2Bool(const char *str)
Definition: UConversion.cpp:170
Parameters
PM::Parameters Parameters
ULogger::setLevel
static void setLevel(ULogger::Level level)
Definition: ULogger.h:339
description
description
CSimpleIniTempl
Definition: SimpleIni.h:293
end
end
ULogger::kDebug
@ kDebug
Definition: ULogger.h:252
UDirectory::separator
static std::string separator()
Definition: UDirectory.cpp:391
type
ULogger::kTypeNoLog
@ kTypeNoLog
Definition: ULogger.h:244
rtabmap::Parameters::~Parameters
virtual ~Parameters()
Definition: Parameters.cpp:62
uStr2Double
double UTILITE_EXPORT uStr2Double(const std::string &str)
Definition: UConversion.cpp:147
iterator
rtabmap::Parameters::parametersType_
static ParametersMap parametersType_
Definition: Parameters.h:975
uListToVector
std::vector< V > uListToVector(const std::list< V > &list)
Definition: UStl.h:473
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::Parameters::getDefaultDatabaseName
static std::string getDefaultDatabaseName()
Definition: Parameters.cpp:88
rtabmap::Parameters::getVersion
static std::string getVersion()
Definition: Parameters.cpp:82
rtabmap::Parameters::parse
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:506
CSimpleIniTempl::SaveFile
SI_Error SaveFile(const char *a_pszFile, bool a_bAddSignature=true) const
Definition: SimpleIni.h:2311
Parameters.h
UDirectory::homeDir
static std::string homeDir()
Definition: UDirectory.cpp:355
rtabmap::Parameters::getDefaultOdometryParameters
static ParametersMap getDefaultOdometryParameters(bool stereo=false, bool vis=true, bool icp=false)
Definition: Parameters.cpp:174
uInsert
void uInsert(std::map< K, V > &map, const std::pair< K, V > &pair)
Definition: UStl.h:441
rtabmap::Parameters::filterParameters
static ParametersMap filterParameters(const ParametersMap &parameters, const std::string &group, bool remove=false)
Definition: Parameters.cpp:217
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:910
UFATAL
#define UFATAL(...)
ULogger::setPrintTime
static void setPrintTime(bool printTime)
Definition: ULogger.h:273
UConversion.h
Some conversion functions.
UFile::getExtension
std::string getExtension()
Definition: UFile.h:140
ULogger::kWarning
@ kWarning
Definition: ULogger.h:252
rtabmap::Parameters::isFeatureParameter
static bool isFeatureParameter(const std::string &param)
Definition: Parameters.cpp:158
ULogger::kInfo
@ kInfo
Definition: ULogger.h:252
rtabmap::Parameters::getRemovedParameters
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
Definition: Parameters.cpp:233
CSimpleIniTempl::SetValue
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)
Definition: SimpleIni.h:968
version
version
UASSERT
#define UASSERT(condition)
rtabmap_netvlad.argv
argv
Definition: rtabmap_netvlad.py:15
CSimpleIniTempl::LoadFile
SI_Error LoadFile(const char *a_pszFile)
Definition: SimpleIni.h:1301
rtabmap::Parameters::Parameters
Parameters()
Definition: Parameters.cpp:58
CSimpleIniTempl::TKeyVal
std::multimap< Entry, const SI_CHAR *, typename Entry::KeyOrder > TKeyVal
Definition: SimpleIni.h:352
rtabmap::Parameters::serialize
static std::string serialize(const ParametersMap &parameters)
Definition: Parameters.cpp:93
p
Point3_ p(2)
ULogger::setType
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
DBDriver.h
uStrContains
bool uStrContains(const std::string &string, const std::string &substring)
Definition: UStl.h:785
rtabmap::Parameters::getBackwardCompatibilityMap
static const ParametersMap & getBackwardCompatibilityMap()
Definition: Parameters.cpp:456
CSimpleIniTempl::Delete
bool Delete(const SI_CHAR *a_pSection, const SI_CHAR *a_pKey, bool a_bRemoveEmpty=false)
Definition: SimpleIni.h:2524
out
std::ofstream out("Result.txt")
path
path
str
UASSERT_MSG
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
key
const gtsam::Symbol key( 'X', 0)
UWARN
#define UWARN(...)
CSimpleIniTempl::GetSection
const TKeyVal * GetSection(const SI_CHAR *a_pSection) const
Definition: SimpleIni.h:2252
rtabmap::Parameters::showUsage
static const char * showUsage()
Definition: Parameters.cpp:578
rtabmap::DBDriver
Definition: DBDriver.h:62
ULogger::setPrintWhere
static void setPrintWhere(bool printWhere)
Definition: ULogger.h:302
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
uReplaceChar
std::string UTILITE_EXPORT uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:33
ULogger.h
ULogger class and convenient macros.
CSimpleIniTempl::GetValue
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
Definition: SimpleIni.h:1951
uSplit
std::list< std::string > uSplit(const std::string &str, char separator=' ')
Definition: UStl.h:564
uStr2Int
int UTILITE_EXPORT uStr2Int(const std::string &str)
Definition: UConversion.cpp:125
rtabmap::Parameters::readINI
static void readINI(const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1291
iter
iterator iter(handle obj)
CSimpleIniTempl::LoadData
SI_Error LoadData(const std::string &a_strData)
Definition: SimpleIni.h:604
rtabmap::Parameters::descriptions_
static ParametersMap descriptions_
Definition: Parameters.h:976
c_str
const char * c_str(Args &&...args)
UStl.h
Wrappers of STL for convenient functions.
rtabmap::Parameters::backwardCompatibilityMap_
static ParametersMap backwardCompatibilityMap_
Definition: Parameters.h:980
UDEBUG
#define UDEBUG(...)
rtabmap::Parameters::getType
static std::string getType(const std::string &paramKey)
Definition: Parameters.cpp:476
icp
rtabmap::Parameters::removedParameters_
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
Definition: Parameters.h:979
NULL
#define NULL
ULogger::setPrintThreadId
static void setPrintThreadId(bool printThreadId)
Definition: ULogger.h:309
uStr2Float
float UTILITE_EXPORT uStr2Float(const std::string &str)
Definition: UConversion.cpp:138
rtabmap::Parameters::createDefaultWorkingDirectory
static std::string createDefaultWorkingDirectory()
Definition: Parameters.cpp:66
UFile.h
rtabmap
Definition: CameraARCore.cpp:35
UFile::exists
bool exists()
Definition: UFile.h:104
rtabmap::readINIImpl
void readINIImpl(const CSimpleIniA &ini, const std::string &configFilePath, ParametersMap &parameters, bool modifiedOnly)
Definition: Parameters.cpp:1205
UERROR
#define UERROR(...)
value
value
i
int i
ULOGGER_WARN
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
rtabmap::Parameters::writeINI
static void writeINI(const std::string &configFile, const ParametersMap &parameters)
Definition: Parameters.cpp:1305
rtabmap::Parameters::getDescription
static std::string getDescription(const std::string &paramKey)
Definition: Parameters.cpp:491
rtabmap::DBDriver::closeConnection
void closeConnection(bool save=true, const std::string &outputUrl="")
Definition: DBDriver.cpp:64
rtabmap::Parameters::deserialize
static ParametersMap deserialize(const std::string &parameters)
Definition: Parameters.cpp:109
rtabmap::Parameters::instance_
static Parameters instance_
Definition: Parameters.h:977
rtabmap::DBDriver::create
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Apr 28 2025 02:45:58