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.7
240  removedParameters_.insert(std::make_pair("SIFT/NFeatures", std::make_pair(false, "")));
241 
242  // 0.21.3
243  removedParameters_.insert(std::make_pair("GridGlobal/FullUpdate", std::make_pair(false, "")));
244 
245  // 0.20.15
246  removedParameters_.insert(std::make_pair("Grid/FromDepth", std::make_pair(true, Parameters::kGridSensor())));
247 
248  // 0.20.9
249  removedParameters_.insert(std::make_pair("OdomORBSLAM2/VocPath", std::make_pair(true, Parameters::kOdomORBSLAMVocPath())));
250  removedParameters_.insert(std::make_pair("OdomORBSLAM2/Bf", std::make_pair(true, Parameters::kOdomORBSLAMBf())));
251  removedParameters_.insert(std::make_pair("OdomORBSLAM2/ThDepth", std::make_pair(true, Parameters::kOdomORBSLAMThDepth())));
252  removedParameters_.insert(std::make_pair("OdomORBSLAM2/Fps", std::make_pair(true, Parameters::kOdomORBSLAMFps())));
253  removedParameters_.insert(std::make_pair("OdomORBSLAM2/MaxFeatures", std::make_pair(true, Parameters::kOdomORBSLAMMaxFeatures())));
254  removedParameters_.insert(std::make_pair("OdomORBSLAM2/MapSize", std::make_pair(true, Parameters::kOdomORBSLAMMapSize())));
255 
256  removedParameters_.insert(std::make_pair("RGBD/SavedLocalizationIgnored", std::make_pair(true, Parameters::kRGBDStartAtOrigin())));
257 
258  removedParameters_.insert(std::make_pair("Icp/PMForce4DoF", std::make_pair(true, Parameters::kIcpForce4DoF())));
259  removedParameters_.insert(std::make_pair("Icp/PM", std::make_pair(true, Parameters::kIcpStrategy()))); // convert "true" to "1"
260  removedParameters_.insert(std::make_pair("Icp/PMOutlierRatio", std::make_pair(true, Parameters::kIcpOutlierRatio())));
261 
262  // 0.20.
263  removedParameters_.insert(std::make_pair("SuperGlue/Path", std::make_pair(true, Parameters::kPyMatcherPath())));
264  removedParameters_.insert(std::make_pair("SuperGlue/Iterations", std::make_pair(true, Parameters::kPyMatcherIterations())));
265  removedParameters_.insert(std::make_pair("SuperGlue/MatchThreshold", std::make_pair(true, Parameters::kPyMatcherThreshold())));
266  removedParameters_.insert(std::make_pair("SuperGlue/Cuda", std::make_pair(true, Parameters::kPyMatcherCuda())));
267  removedParameters_.insert(std::make_pair("SuperGlue/Indoor", std::make_pair(false, Parameters::kPyMatcherModel())));
268 
269  removedParameters_.insert(std::make_pair("Vis/CorCrossCheck", std::make_pair(false, Parameters::kVisCorNNType())));
270  removedParameters_.insert(std::make_pair("SPTorch/ModelPath", std::make_pair(true, Parameters::kSuperPointModelPath())));
271  removedParameters_.insert(std::make_pair("SPTorch/Threshold", std::make_pair(true, Parameters::kSuperPointThreshold())));
272  removedParameters_.insert(std::make_pair("SPTorch/NMS", std::make_pair(true, Parameters::kSuperPointNMS())));
273  removedParameters_.insert(std::make_pair("SPTorch/MinDistance", std::make_pair(true, Parameters::kSuperPointNMSRadius())));
274  removedParameters_.insert(std::make_pair("SPTorch/Cuda", std::make_pair(true, Parameters::kSuperPointCuda())));
275 
276  // 0.19.4
277  removedParameters_.insert(std::make_pair("RGBD/MaxLocalizationDistance", std::make_pair(true, Parameters::kRGBDMaxLoopClosureDistance())));
278 
279  // 0.19.3
280  removedParameters_.insert(std::make_pair("Aruco/Dictionary", std::make_pair(true, Parameters::kMarkerDictionary())));
281  removedParameters_.insert(std::make_pair("Aruco/MarkerLength", std::make_pair(true, Parameters::kMarkerLength())));
282  removedParameters_.insert(std::make_pair("Aruco/MaxDepthError", std::make_pair(true, Parameters::kMarkerMaxDepthError())));
283  removedParameters_.insert(std::make_pair("Aruco/VarianceLinear", std::make_pair(true, Parameters::kMarkerVarianceLinear())));
284  removedParameters_.insert(std::make_pair("Aruco/VarianceAngular", std::make_pair(true, Parameters::kMarkerVarianceAngular())));
285  removedParameters_.insert(std::make_pair("Aruco/CornerRefinementMethod", std::make_pair(true, Parameters::kMarkerCornerRefinementMethod())));
286 
287  // 0.17.5
288  removedParameters_.insert(std::make_pair("Grid/OctoMapOccupancyThr", std::make_pair(true, Parameters::kGridGlobalOccupancyThr())));
289 
290  // 0.17.0
291  removedParameters_.insert(std::make_pair("Grid/Scan2dMaxFilledRange", std::make_pair(false, Parameters::kGridRangeMax())));
292 
293  // 0.16.0
294  removedParameters_.insert(std::make_pair("Grid/ProjRayTracing", std::make_pair(true, Parameters::kGridRayTracing())));
295  removedParameters_.insert(std::make_pair("Grid/DepthMin", std::make_pair(true, Parameters::kGridRangeMin())));
296  removedParameters_.insert(std::make_pair("Grid/DepthMax", std::make_pair(true, Parameters::kGridRangeMax())));
297 
298  // 0.15.1
299  removedParameters_.insert(std::make_pair("Reg/VarianceFromInliersCount", std::make_pair(false, "")));
300  removedParameters_.insert(std::make_pair("Reg/VarianceNormalized", std::make_pair(false, "")));
301 
302  // 0.13.3
303  removedParameters_.insert(std::make_pair("Icp/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
304 
305 
306  // 0.13.1
307  removedParameters_.insert(std::make_pair("Rtabmap/VhStrategy", std::make_pair(true, Parameters::kVhEpEnabled())));
308 
309  // 0.12.5
310  removedParameters_.insert(std::make_pair("Grid/FullUpdate", std::make_pair(false, "")));
311 
312  // 0.12.1
313  removedParameters_.insert(std::make_pair("Grid/3DGroundIsObstacle", std::make_pair(true, Parameters::kGridGroundIsObstacle())));
314 
315  // 0.11.12
316  removedParameters_.insert(std::make_pair("Optimizer/Slam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
317  removedParameters_.insert(std::make_pair("OdomF2M/FixedMapPath", std::make_pair(false, "")));
318 
319  // 0.11.10 typos
320  removedParameters_.insert(std::make_pair("Grid/FlatObstaclesDetected", std::make_pair(true, Parameters::kGridFlatObstacleDetected())));
321 
322  // 0.11.8
323  removedParameters_.insert(std::make_pair("Reg/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
324  removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius", std::make_pair(true, Parameters::kOdomF2MScanSubtractRadius())));
325 
326  // 0.11.6
327  removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false, "")));
328 
329  // 0.11.3
330  removedParameters_.insert(std::make_pair("Mem/ImageDecimation", std::make_pair(true, Parameters::kMemImagePostDecimation())));
331 
332  // 0.11.2
333  removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
334  removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath", std::make_pair(false, "")));
335  removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
336  removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
337 
338  // 0.11.0
339  removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
340  removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath", std::make_pair(false, "")));
341  removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
342  removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
343 
344  removedParameters_.insert(std::make_pair("Kp/WordsPerImage", std::make_pair(true, Parameters::kKpMaxFeatures())));
345 
346  removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM", std::make_pair(false, "")));
347 
348  removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
349 
350  removedParameters_.insert(std::make_pair("Odom/ParticleFiltering", std::make_pair(false, Parameters::kOdomFilteringStrategy())));
351  removedParameters_.insert(std::make_pair("Odom/FeatureType", std::make_pair(true, Parameters::kVisFeatureType())));
352  removedParameters_.insert(std::make_pair("Odom/EstimationType", std::make_pair(true, Parameters::kVisEstimationType())));
353  removedParameters_.insert(std::make_pair("Odom/MaxFeatures", std::make_pair(true, Parameters::kVisMaxFeatures())));
354  removedParameters_.insert(std::make_pair("Odom/InlierDistance", std::make_pair(true, Parameters::kVisInlierDistance())));
355  removedParameters_.insert(std::make_pair("Odom/MinInliers", std::make_pair(true, Parameters::kVisMinInliers())));
356  removedParameters_.insert(std::make_pair("Odom/Iterations", std::make_pair(true, Parameters::kVisIterations())));
357  removedParameters_.insert(std::make_pair("Odom/RefineIterations", std::make_pair(true, Parameters::kVisRefineIterations())));
358  removedParameters_.insert(std::make_pair("Odom/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
359  removedParameters_.insert(std::make_pair("Odom/RoiRatios", std::make_pair(true, Parameters::kVisRoiRatios())));
360  removedParameters_.insert(std::make_pair("Odom/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
361  removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(false, "")));
362  removedParameters_.insert(std::make_pair("Odom/PnPReprojError", std::make_pair(true, Parameters::kVisPnPReprojError())));
363  removedParameters_.insert(std::make_pair("Odom/PnPFlags", std::make_pair(true, Parameters::kVisPnPFlags())));
364 
365  removedParameters_.insert(std::make_pair("OdomBow/NNType", std::make_pair(true, Parameters::kVisCorNNType())));
366  removedParameters_.insert(std::make_pair("OdomBow/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
367 
368  removedParameters_.insert(std::make_pair("OdomFlow/WinSize", std::make_pair(true, Parameters::kVisCorFlowWinSize())));
369  removedParameters_.insert(std::make_pair("OdomFlow/Iterations", std::make_pair(true, Parameters::kVisCorFlowIterations())));
370  removedParameters_.insert(std::make_pair("OdomFlow/Eps", std::make_pair(true, Parameters::kVisCorFlowEps())));
371  removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel", std::make_pair(true, Parameters::kVisCorFlowMaxLevel())));
372 
373  removedParameters_.insert(std::make_pair("OdomSubPix/WinSize", std::make_pair(true, Parameters::kVisSubPixWinSize())));
374  removedParameters_.insert(std::make_pair("OdomSubPix/Iterations", std::make_pair(true, Parameters::kVisSubPixIterations())));
375  removedParameters_.insert(std::make_pair("OdomSubPix/Eps", std::make_pair(true, Parameters::kVisSubPixEps())));
376 
377  removedParameters_.insert(std::make_pair("LccReextract/Activated", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
378  removedParameters_.insert(std::make_pair("LccReextract/FeatureType", std::make_pair(false, Parameters::kVisFeatureType())));
379  removedParameters_.insert(std::make_pair("LccReextract/MaxWords", std::make_pair(false, Parameters::kVisMaxFeatures())));
380  removedParameters_.insert(std::make_pair("LccReextract/MaxDepth", std::make_pair(false, Parameters::kVisMaxDepth())));
381  removedParameters_.insert(std::make_pair("LccReextract/RoiRatios", std::make_pair(false, Parameters::kVisRoiRatios())));
382  removedParameters_.insert(std::make_pair("LccReextract/NNType", std::make_pair(false, Parameters::kVisCorNNType())));
383  removedParameters_.insert(std::make_pair("LccReextract/NNDR", std::make_pair(false, Parameters::kVisCorNNDR())));
384 
385  removedParameters_.insert(std::make_pair("LccBow/EstimationType", std::make_pair(false, Parameters::kVisEstimationType())));
386  removedParameters_.insert(std::make_pair("LccBow/InlierDistance", std::make_pair(false, Parameters::kVisInlierDistance())));
387  removedParameters_.insert(std::make_pair("LccBow/MinInliers", std::make_pair(false, Parameters::kVisMinInliers())));
388  removedParameters_.insert(std::make_pair("LccBow/Iterations", std::make_pair(false, Parameters::kVisIterations())));
389  removedParameters_.insert(std::make_pair("LccBow/RefineIterations", std::make_pair(false, Parameters::kVisRefineIterations())));
390  removedParameters_.insert(std::make_pair("LccBow/Force2D", std::make_pair(false, Parameters::kRegForce3DoF())));
391  removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false, "")));
392  removedParameters_.insert(std::make_pair("LccBow/PnPReprojError", std::make_pair(false, Parameters::kVisPnPReprojError())));
393  removedParameters_.insert(std::make_pair("LccBow/PnPFlags", std::make_pair(false, Parameters::kVisPnPFlags())));
394  removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar", std::make_pair(true, Parameters::kVisEpipolarGeometryVar())));
395 
396  removedParameters_.insert(std::make_pair("LccIcp/Type", std::make_pair(false, Parameters::kRegStrategy())));
397 
398  removedParameters_.insert(std::make_pair("LccIcp3/Decimation", std::make_pair(false, "")));
399  removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth", std::make_pair(false, "")));
400  removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize", std::make_pair(false, Parameters::kIcpVoxelSize())));
401  removedParameters_.insert(std::make_pair("LccIcp3/Samples", std::make_pair(false, Parameters::kIcpDownsamplingStep())));
402  removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance", std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
403  removedParameters_.insert(std::make_pair("LccIcp3/Iterations", std::make_pair(false, Parameters::kIcpIterations())));
404  removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio", std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
405  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane", std::make_pair(true, Parameters::kIcpPointToPlane())));
406  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
407 
408  removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance", std::make_pair(true, Parameters::kIcpMaxCorrespondenceDistance())));
409  removedParameters_.insert(std::make_pair("LccIcp2/Iterations", std::make_pair(true, Parameters::kIcpIterations())));
410  removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio", std::make_pair(true, Parameters::kIcpCorrespondenceRatio())));
411  removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize", std::make_pair(true, Parameters::kIcpVoxelSize())));
412 
413  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
414  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
415  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
416  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
417  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(false, "")));
418  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
419  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true, Parameters::kRGBDProximityPathFilteringRadius())));
420  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(true, Parameters::kRGBDProximityPathRawPosesUsed())));
421 
422  removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy", std::make_pair(true, Parameters::kOptimizerStrategy())));
423  removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon", std::make_pair(true, Parameters::kOptimizerEpsilon())));
424  removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
425  removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust", std::make_pair(true, Parameters::kOptimizerRobust())));
426  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
427  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d", std::make_pair(true, Parameters::kRegForce3DoF())));
428  removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored", std::make_pair(true, Parameters::kOptimizerVarianceIgnored())));
429 
430  removedParameters_.insert(std::make_pair("Stereo/WinSize", std::make_pair(true, Parameters::kStereoWinWidth())));
431 
432  // before 0.11.0
433  removedParameters_.insert(std::make_pair("GFTT/MaxCorners", std::make_pair(true, Parameters::kVisMaxFeatures())));
434  removedParameters_.insert(std::make_pair("LccBow/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
435  removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
436  removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy", std::make_pair(true, Parameters::kKpDetectorStrategy())));
437  removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
438  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius", std::make_pair(true, Parameters::kRGBDLocalRadius())));
439  removedParameters_.insert(std::make_pair("RGBD/ToroIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
440  removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept", std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
441  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
442  removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(false, "")));
443  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
444  removedParameters_.insert(std::make_pair("Odom/Type", std::make_pair(true, Parameters::kVisFeatureType())));
445  removedParameters_.insert(std::make_pair("Odom/MaxWords", std::make_pair(true, Parameters::kVisMaxFeatures())));
446  removedParameters_.insert(std::make_pair("Odom/LocalHistory", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
447  removedParameters_.insert(std::make_pair("Odom/NearestNeighbor", std::make_pair(true, Parameters::kVisCorNNType())));
448  removedParameters_.insert(std::make_pair("Odom/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
449  }
450  return removedParameters_;
451 }
452 
454 {
455  if(backwardCompatibilityMap_.empty())
456  {
457  getRemovedParameters(); // make sure removedParameters is filled
458 
459  // compatibility
460  for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
461  iter!=removedParameters_.end();
462  ++iter)
463  {
464  if(iter->second.first)
465  {
466  backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
467  }
468  }
469  }
471 }
472 
473 std::string Parameters::getType(const std::string & paramKey)
474 {
475  std::string type;
476  ParametersMap::iterator iter = parametersType_.find(paramKey);
477  if(iter != parametersType_.end())
478  {
479  type = iter->second;
480  }
481  else
482  {
483  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
484  }
485  return type;
486 }
487 
488 std::string Parameters::getDescription(const std::string & paramKey)
489 {
490  std::string description;
491  ParametersMap::iterator iter = descriptions_.find(paramKey);
492  if(iter != descriptions_.end())
493  {
494  description = iter->second;
495  }
496  else
497  {
498  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
499  }
500  return description;
501 }
502 
503 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
504 {
505  ParametersMap::const_iterator iter = parameters.find(key);
506  if(iter != parameters.end())
507  {
508  value = uStr2Bool(iter->second.c_str());
509  return true;
510  }
511  return false;
512 }
513 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
514 {
515  ParametersMap::const_iterator iter = parameters.find(key);
516  if(iter != parameters.end())
517  {
518  value = uStr2Int(iter->second.c_str());
519  return true;
520  }
521  return false;
522 }
523 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
524 {
525  ParametersMap::const_iterator iter = parameters.find(key);
526  if(iter != parameters.end())
527  {
528  value = uStr2Int(iter->second.c_str());
529  return true;
530  }
531  return false;
532 }
533 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
534 {
535  ParametersMap::const_iterator iter = parameters.find(key);
536  if(iter != parameters.end())
537  {
538  value = uStr2Float(iter->second);
539  return true;
540  }
541  return false;
542 }
543 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
544 {
545  ParametersMap::const_iterator iter = parameters.find(key);
546  if(iter != parameters.end())
547  {
548  value = uStr2Double(iter->second);
549  return true;
550  }
551  return false;
552 }
553 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
554 {
555  ParametersMap::const_iterator iter = parameters.find(key);
556  if(iter != parameters.end())
557  {
558  value = iter->second;
559  return true;
560  }
561  return false;
562 }
563 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
564 {
565  for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
566  {
567  ParametersMap::const_iterator jter = parameters.find(iter->first);
568  if(jter != parameters.end())
569  {
570  iter->second = jter->second;
571  }
572  }
573 }
574 
575 const char * Parameters::showUsage()
576 {
577  return "RTAB-Map options:\n"
578  " --help Show usage.\n"
579  " --version Show version of rtabmap and its dependencies.\n"
580  " --params Show all parameters with their default value and description. \n"
581  " If a database path is set as last argument, the parameters in the \n"
582  " database will be shown in INI format.\n"
583  " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n"
584  " --SURF/HessianThreshold 150\n"
585  " For parameters in table format, add ',' between values :\n"
586  " --Kp/RoiRatios 0,0,0.1,0\n"
587  "Logger options:\n"
588  " --nolog Disable logger\n"
589  " --logconsole Set logger console type\n"
590  " --logfile \"path\" Set logger file type\n"
591  " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n"
592  " --udebug Set logger level to debug\n"
593  " --uinfo Set logger level to info\n"
594  " --uwarn Set logger level to warn\n"
595  " --uerror Set logger level to error\n"
596  " --logtime \"bool\" Print time when logging\n"
597  " --logwhere \"bool\" Print where when logging\n"
598  " --logthread \"bool\" Print thread id when logging\n"
599  ;
600 }
601 
602 ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParameters)
603 {
605  const ParametersMap & parameters = getDefaultParameters();
606  const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
607  for(int i=0;i<argc;++i)
608  {
609  bool checkParameters = onlyParameters;
610  if(!checkParameters)
611  {
612  if(strcmp(argv[i], "--help") == 0)
613  {
614  std::cout << showUsage() << std::endl;
615  exit(0);
616  }
617  else if(strcmp(argv[i], "--version") == 0)
618  {
619  std::string str = "RTAB-Map:";
620 
621  int spacing = 30;
622  std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
623  str = "PCL:";
624  std::cout << str << std::setw(spacing - str.size()) << PCL_VERSION_PRETTY << std::endl;
625  str = "With VTK:";
626 #ifndef DISABLE_VTK
627  std::cout << str << std::setw(spacing - str.size()) << vtkVersion::GetVTKVersion() << std::endl;
628 #else
629  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
630 #endif
631  str = "OpenCV:";
632  std::cout << str << std::setw(spacing - str.size()) << CV_VERSION << std::endl;
633 #if CV_MAJOR_VERSION >= 3
634  str = "With OpenCV xfeatures2d:";
635 #ifdef HAVE_OPENCV_XFEATURES2D
636  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
637 #else
638  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
639 #endif
640 #endif
641  str = "With OpenCV nonfree:";
642 #ifdef RTABMAP_NONFREE
643  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
644 #else
645  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
646 #endif
647  str = "With ORB OcTree:";
648 #ifdef RTABMAP_ORB_OCTREE
649  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
650 #else
651  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
652 #endif
653  str = "With SuperPoint Torch:";
654 #ifdef RTABMAP_TORCH
655  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
656 #else
657  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
658 #endif
659  str = "With Python3:";
660 #ifdef RTABMAP_PYTHON
661  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
662 #else
663  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
664 #endif
665  str = "With FastCV:";
666 #ifdef RTABMAP_FASTCV
667  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
668 #else
669  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
670 #endif
671  str = "With OpenGV:";
672 #ifdef RTABMAP_OPENGV
673  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
674 #else
675  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
676 #endif
677  str = "With Madgwick:";
678 #ifdef RTABMAP_MADGWICK
679  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
680 #else
681  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
682 #endif
683  str = "With PDAL:";
684 #ifdef RTABMAP_PDAL
685  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
686 #else
687  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
688 #endif
689  str = "With libLAS:";
690 #ifdef RTABMAP_LIBLAS
691  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
692 #else
693  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
694 #endif
695  str = "With CudaSift:";
696 #ifdef RTABMAP_CUDASIFT
697  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
698 #else
699  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
700 #endif
701  str = "With TORO:";
702 #ifdef RTABMAP_TORO
703  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
704 #else
705  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
706 #endif
707  str = "With g2o:";
708 #ifdef RTABMAP_G2O
709  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
710 #else
711  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
712 #endif
713  str = "With GTSAM:";
714 #ifdef RTABMAP_GTSAM
715  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
716 #else
717  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
718 #endif
719  str = "With Vertigo:";
720 #ifdef RTABMAP_VERTIGO
721  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
722 #else
723  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
724 #endif
725  str = "With CVSBA:";
726 #ifdef RTABMAP_CVSBA
727  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
728 #else
729  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
730 #endif
731  str = "With Ceres:";
732 #ifdef RTABMAP_CERES
733  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
734 #else
735  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
736 #endif
737  str = "With OpenNI:";
738 #ifdef RTABMAP_OPENNI
739  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
740 #else
741  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
742 #endif
743  str = "With OpenNI2:";
744 #ifdef RTABMAP_OPENNI2
745  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
746 #else
747  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
748 #endif
749  str = "With Freenect:";
750 #ifdef RTABMAP_FREENECT
751  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
752 #else
753  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
754 #endif
755  str = "With Freenect2:";
756 #ifdef RTABMAP_FREENECT2
757  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
758 #else
759  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
760 #endif
761  str = "With K4W2:";
762 #ifdef RTABMAP_K4W2
763  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
764 #else
765  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
766 #endif
767  str = "With K4A:";
768 #ifdef RTABMAP_K4A
769  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
770 #else
771  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
772 #endif
773  str = "With DC1394:";
774 #ifdef RTABMAP_DC1394
775  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
776 #else
777  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
778 #endif
779  str = "With FlyCapture2:";
780 #ifdef RTABMAP_FLYCAPTURE2
781  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
782 #else
783  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
784 #endif
785  str = "With ZED:";
786 #ifdef RTABMAP_ZED
787  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
788 #else
789  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
790 #endif
791  str = "With ZED Open Capture:";
792 #ifdef RTABMAP_ZEDOC
793  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
794 #else
795  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
796 #endif
797  str = "With RealSense:";
798 #ifdef RTABMAP_REALSENSE
799  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
800 #else
801  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
802 #endif
803  str = "With RealSense SLAM:";
804 #ifdef RTABMAP_REALSENSE_SLAM
805  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
806 #else
807  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
808 #endif
809  str = "With RealSense2:";
810 #ifdef RTABMAP_REALSENSE2
811  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
812 #else
813  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
814 #endif
815  str = "With MYNT EYE S:";
816 #ifdef RTABMAP_MYNTEYE
817  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
818 #else
819  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
820 #endif
821  str = "With DepthAI:";
822 #ifdef RTABMAP_DEPTHAI
823  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
824 #else
825  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
826 #endif
827  str = "With XVisio SDK:";
828 #ifdef RTABMAP_XVSDK
829  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
830 #else
831  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
832 #endif
833  str = "With libpointmatcher:";
834 #ifdef RTABMAP_POINTMATCHER
835  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
836 #else
837  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
838 #endif
839  str = "With CCCoreLib:";
840 #ifdef RTABMAP_CCCORELIB
841  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
842 #else
843  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
844 #endif
845  str = "With Open3D:";
846 #ifdef RTABMAP_OPEN3D
847  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
848 #else
849  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
850 #endif
851  str = "With OctoMap:";
852 #ifdef RTABMAP_OCTOMAP
853  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
854 #else
855  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
856 #endif
857  str = "With GridMap:";
858 #ifdef RTABMAP_GRIDMAP
859  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
860 #else
861  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
862 #endif
863  str = "With cpu-tsdf:";
864 #ifdef RTABMAP_CPUTSDF
865  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
866 #else
867  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
868 #endif
869  str = "With open chisel:";
870 #ifdef RTABMAP_OPENCHISEL
871  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
872 #else
873  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
874 #endif
875  str = "With Alice Vision:";
876 #ifdef RTABMAP_ALICE_VISION
877  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
878 #else
879  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
880 #endif
881  str = "With LOAM:";
882 #ifdef RTABMAP_LOAM
883  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
884 #else
885  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
886 #endif
887  str = "With FLOAM:";
888 #ifdef RTABMAP_FLOAM
889  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
890 #else
891  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
892 #endif
893  str = "With FOVIS:";
894 #ifdef RTABMAP_FOVIS
895  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
896 #else
897  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
898 #endif
899  str = "With Viso2:";
900 #ifdef RTABMAP_VISO2
901  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
902 #else
903  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
904 #endif
905  str = "With DVO:";
906 #ifdef RTABMAP_DVO
907  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
908 #else
909  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
910 #endif
911 #if RTABMAP_ORB_SLAM == 3
912  str = "With ORB_SLAM3:";
913 #elif RTABMAP_ORB_SLAM == 2
914  str = "With ORB_SLAM2:";
915 #else
916  str = "With ORB_SLAM:";
917 #endif
918 #ifdef RTABMAP_ORB_SLAM
919  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
920 #else
921  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
922 #endif
923  str = "With OKVIS:";
924 #ifdef RTABMAP_OKVIS
925  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
926 #else
927  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
928 #endif
929  str = "With MSCKF_VIO:";
930 #ifdef RTABMAP_MSCKF_VIO
931  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
932 #else
933  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
934 #endif
935  str = "With VINS-Fusion:";
936 #ifdef RTABMAP_VINS
937  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
938 #else
939  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
940 #endif
941  str = "With OpenVINS:";
942 #ifdef RTABMAP_OPENVINS
943  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
944 #else
945  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
946 #endif
947  exit(0);
948  }
949  else if(strcmp(argv[i], "--nolog") == 0)
950  {
952  }
953  else if(strcmp(argv[i], "--logconsole") == 0)
954  {
956  }
957  else if(strcmp(argv[i], "--logfile") == 0)
958  {
959  ++i;
960  if(i < argc)
961  {
963  }
964  else
965  {
966  UERROR("\"--logfile\" argument requires following file path");
967  }
968  }
969  else if(strcmp(argv[i], "--logfilea") == 0)
970  {
971  ++i;
972  if(i < argc)
973  {
975  }
976  else
977  {
978  UERROR("\"--logfilea\" argument requires following file path");
979  }
980  }
981  else if(strcmp(argv[i], "--udebug") == 0)
982  {
984  }
985  else if(strcmp(argv[i], "--uinfo") == 0)
986  {
988  }
989  else if(strcmp(argv[i], "--uwarn") == 0)
990  {
992  }
993  else if(strcmp(argv[i], "--uerror") == 0)
994  {
996  }
997  else if(strcmp(argv[i], "--ulogtime") == 0)
998  {
999  ++i;
1000  if(i < argc)
1001  {
1003  }
1004  else
1005  {
1006  UERROR("\"--ulogtime\" argument requires a following boolean value");
1007  }
1008  }
1009  else if(strcmp(argv[i], "--ulogwhere") == 0)
1010  {
1011  ++i;
1012  if(i < argc)
1013  {
1015  }
1016  else
1017  {
1018  UERROR("\"--ulogwhere\" argument requires a following boolean value");
1019  }
1020  }
1021  else if(strcmp(argv[i], "--ulogthread") == 0)
1022  {
1023  ++i;
1024  if(i < argc)
1025  {
1027  }
1028  else
1029  {
1030  UERROR("\"--ulogthread\" argument requires a following boolean value");
1031  }
1032  }
1033  else
1034  {
1035  checkParameters = true;
1036  }
1037  }
1038 
1039  if(checkParameters) // check for parameters
1040  {
1041  if(strcmp(argv[i], "--params") == 0)
1042  {
1043  if (i < argc - 1)
1044  {
1045  // If the last argument is a database, dump the parameters in INI format
1046  std::string dbName = argv[argc - 1];
1047  if (UFile::exists(dbName) && UFile::getExtension(dbName).compare("db") == 0)
1048  {
1049  DBDriver * driver = DBDriver::create();
1050  bool read = false;
1051  if (driver->openConnection(dbName))
1052  {
1053  ParametersMap dbParameters = driver->getLastParameters();
1054  if (!dbParameters.empty())
1055  {
1056  std::cout << "[Core]" << std::endl;
1057  std::cout << "Version = " << RTABMAP_VERSION << std::endl;
1058  for (ParametersMap::const_iterator iter = dbParameters.begin(); iter != dbParameters.end(); ++iter)
1059  {
1060  std::string key = iter->first;
1061  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1062 
1063  std::string value = iter->second.c_str();
1064  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1065 
1066  std::cout << key << " = " << value << std::endl;
1067  }
1068  read = true;
1069  }
1070  driver->closeConnection(false);
1071  }
1072  delete driver;
1073  if (read)
1074  {
1075  exit(0);
1076  }
1077  }
1078  }
1079 
1080  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1081  {
1082  bool ignore = false;
1083  UASSERT(uSplit(iter->first, '/').size() == 2);
1084  std::string group = uSplit(iter->first, '/').front();
1085 #ifndef RTABMAP_GTSAM
1086  if(group.compare("GTSAM") == 0)
1087  {
1088  ignore = true;
1089  }
1090 #endif
1091 #ifndef RTABMAP_G2O
1092  if(group.compare("g2o") == 0)
1093  {
1094  ignore = true;
1095  }
1096 #endif
1097 #ifndef RTABMAP_FOVIS
1098  if(group.compare("OdomFovis") == 0)
1099  {
1100  ignore = true;
1101  }
1102 #endif
1103 #ifndef RTABMAP_VISO2
1104  if(group.compare("OdomViso2") == 0)
1105  {
1106  ignore = true;
1107  }
1108 #endif
1109 #ifndef RTABMAP_ORBSLAM2
1110  if(group.compare("OdomORBSLAM2") == 0)
1111  {
1112  ignore = true;
1113  }
1114 #endif
1115 #ifndef RTABMAP_OKVIS
1116  if(group.compare("OdomOKVIS") == 0)
1117  {
1118  ignore = true;
1119  }
1120 #endif
1121 #if not defined(RTABMAP_LOAM) and not defined(RTABMAP_FLOAM)
1122  if(group.compare("OdomLOAM") == 0)
1123  {
1124  ignore = true;
1125  }
1126 #endif
1127 #ifndef RTABMAP_MSCKF_VIO
1128  if(group.compare("OdomMSCKF") == 0)
1129  {
1130  ignore = true;
1131  }
1132 #endif
1133  if(!ignore)
1134  {
1135  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
1136  std::cout <<
1137  str <<
1138  std::setw(60 - str.size()) <<
1139  " [" <<
1140  rtabmap::Parameters::getDescription(iter->first).c_str() <<
1141  "]" <<
1142  std::endl;
1143  }
1144  }
1145  exit(0);
1146  }
1147  else
1148  {
1149  std::string key = uReplaceChar(argv[i], '-', "");
1150  ParametersMap::const_iterator iter = parameters.find(key);
1151  if(iter != parameters.end())
1152  {
1153  ++i;
1154  if(i < argc)
1155  {
1156  uInsert(out, ParametersPair(iter->first, argv[i]));
1157  UINFO("Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
1158  }
1159  }
1160  else
1161  {
1162  // backward compatibility
1163  std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
1164  if(jter!=removedParams.end())
1165  {
1166  if(jter->second.first)
1167  {
1168  ++i;
1169  if(i < argc)
1170  {
1171  std::string value = argv[i];
1172  if(!value.empty())
1173  {
1174  value = uReplaceChar(value, ',', ' '); // for table
1175  key = jter->second.second;
1176  UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
1177  jter->first.c_str(), jter->second.second.c_str(), value.c_str());
1179  }
1180  }
1181  else
1182  {
1183  UERROR("Value missing for argument \"%s\"", argv[i-1]);
1184  }
1185  }
1186  else if(jter->second.second.empty())
1187  {
1188  UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
1189  }
1190  else
1191  {
1192  UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
1193  }
1194  }
1195  }
1196  }
1197  }
1198  }
1199  return out;
1200 }
1201 
1202 void readINIImpl(const CSimpleIniA & ini, const std::string & configFilePath, ParametersMap & parameters, bool modifiedOnly)
1203 {
1204  const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
1205  if(keyValMap)
1206  {
1207  for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
1208  {
1209  std::string key = (*iter).first.pItem;
1210  if(key.compare("Version") == 0)
1211  {
1212  // Compare version in ini with the current RTAB-Map version
1213  std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
1214  if(version.size() == 3)
1215  {
1216  if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
1217  {
1218  if(configFilePath.find(".rtabmap") != std::string::npos)
1219  {
1220  UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
1221  "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
1222  "to new version.",
1223  configFilePath.c_str(),
1224  (*iter).second,
1225  RTABMAP_VERSION);
1226  }
1227  else
1228  {
1229  UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
1230  "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
1231  "be ignored.",
1232  configFilePath.c_str(),
1233  (*iter).second,
1234  RTABMAP_VERSION);
1235  }
1236  }
1237  }
1238  }
1239  else
1240  {
1241  key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
1242 
1243  // look for old parameter name
1244  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
1245  if(oldIter!=Parameters::getRemovedParameters().end())
1246  {
1247  if(oldIter->second.first)
1248  {
1249  if(parameters.find(oldIter->second.second) == parameters.end())
1250  {
1251  key = oldIter->second.second;
1252  UINFO("Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1253  oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second, Parameters::getDefaultParameters().at(oldIter->second.second).c_str());
1254  }
1255  }
1256  else if(oldIter->second.second.empty())
1257  {
1258  UWARN("Parameter \"%s\" doesn't exist anymore.",
1259  oldIter->first.c_str());
1260  }
1261  else if(parameters.find(oldIter->second.second) == parameters.end())
1262  {
1263  UWARN("Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1264  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());
1265  }
1266 
1267  }
1268 
1270  {
1271  if(!modifiedOnly || std::string(iter->second).compare(Parameters::getDefaultParameters().find(key)->second) != 0)
1272  {
1273  uInsert(parameters, ParametersPair(key, iter->second));
1274  }
1275  }
1276  }
1277  }
1278  }
1279  else
1280  {
1281  ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
1282  "Ignore this warning if the ini file does not exist yet. "
1283  "The ini file will be automatically created when rtabmap will close.", configFilePath.c_str());
1284  }
1285 }
1286 
1287 
1288 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly)
1289 {
1290  CSimpleIniA ini;
1291  ini.LoadFile(configFile.c_str());
1292  readINIImpl(ini, configFile, parameters, modifiedOnly);
1293 }
1294 
1295 void Parameters::readINIStr(const std::string & configContent, ParametersMap & parameters, bool modifiedOnly)
1296 {
1297  CSimpleIniA ini;
1298  ini.LoadData(configContent);
1299  readINIImpl(ini, "", parameters, modifiedOnly);
1300 }
1301 
1302 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
1303 {
1304  CSimpleIniA ini;
1305  ini.LoadFile(configFile.c_str());
1306 
1307  // Save current version
1308  ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
1309 
1310  for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1311  {
1312  std::string key = iter->first;
1313  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1314 
1315  std::string value = iter->second.c_str();
1316  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1317 
1318  ini.SetValue("Core", key.c_str(), value.c_str(), NULL, true);
1319  }
1320 
1321  // Delete removed parameters
1322  if(parameters.size() == getDefaultParameters().size())
1323  {
1324  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter = removedParameters_.begin();
1325  iter!=removedParameters_.end();
1326  ++iter)
1327  {
1328  std::string key = iter->first;
1329  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1330 
1331  std::string value = ini.GetValue("Core", key.c_str(), "");
1332 
1333  if(ini.Delete("Core", key.c_str(), true))
1334  {
1335  if(iter->second.first && parameters.find(iter->second.second) != parameters.end())
1336  {
1337  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());
1338  }
1339  else
1340  {
1341  UWARN("Removed deprecated parameter %s=%s from \"%s\".", iter->first.c_str(), value.c_str(), configFile.c_str());
1342  }
1343  }
1344  }
1345  }
1346 
1347  ini.SaveFile(configFile.c_str());
1348 }
1349 
1350 }
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:966
rtabmap::Parameters::readINIStr
static void readINIStr(const std::string &configContent, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:1295
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:602
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:967
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:503
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:902
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:453
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:575
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:1288
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:968
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:972
UDEBUG
#define UDEBUG(...)
rtabmap::Parameters::getType
static std::string getType(const std::string &paramKey)
Definition: Parameters.cpp:473
icp
rtabmap::Parameters::removedParameters_
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
Definition: Parameters.h:971
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:1202
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:1302
rtabmap::Parameters::getDescription
static std::string getDescription(const std::string &paramKey)
Definition: Parameters.cpp:488
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:969
rtabmap::DBDriver::create
static DBDriver * create(const ParametersMap &parameters=ParametersMap())
Definition: DBDriver.cpp:41


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sun Dec 1 2024 03:42:50