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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:32