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


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jan 23 2023 03:37:29