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 
54 Parameters Parameters::instance_;
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 }
172 
174 {
175  rtabmap::ParametersMap odomParameters;
177  for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
178  {
179  std::string group = uSplit(iter->first, '/').front();
180  if(uStrContains(group, "Odom") ||
181  (stereo && group.compare("Stereo") == 0) ||
182  (icp && group.compare("Icp") == 0) ||
183  (vis && Parameters::isFeatureParameter(iter->first)) ||
184  group.compare("Reg") == 0 ||
185  group.compare("Optimizer") == 0 ||
186  group.compare("g2o") == 0 ||
187  group.compare("GTSAM") == 0 ||
188  (vis && (group.compare("Vis") == 0 || group.compare("PyMatcher") == 0 || group.compare("GMS") == 0)) ||
189  iter->first.compare(kRtabmapPublishRAMUsage())==0)
190  {
191  odomParameters.insert(*iter);
192  }
193  }
194  return odomParameters;
195 }
196 
198 {
199  rtabmap::ParametersMap parameters;
201  for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
202  {
203  UASSERT(uSplit(iter->first, '/').size() == 2);
204  std::string group = uSplit(iter->first, '/').front();
205  if(group.compare(groupIn) == 0)
206  {
207  parameters.insert(*iter);
208  }
209  }
210  UASSERT_MSG(parameters.size(), uFormat("No parameters found for group %s!", groupIn.c_str()).c_str());
211  return parameters;
212 }
213 
214 ParametersMap Parameters::filterParameters(const ParametersMap & parameters, const std::string & groupIn)
215 {
216  ParametersMap output;
217  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
218  {
219  UASSERT(uSplit(iter->first, '/').size() == 2);
220  std::string group = uSplit(iter->first, '/').front();
221  if(group.compare(groupIn) == 0)
222  {
223  output.insert(*iter);
224  }
225  }
226  return output;
227 }
228 
229 const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemovedParameters()
230 {
231  if(removedParameters_.empty())
232  {
233  // removed parameters
234 
235  // 0.20.
236  removedParameters_.insert(std::make_pair("SuperGlue/Path", std::make_pair(true, Parameters::kPyMatcherPath())));
237  removedParameters_.insert(std::make_pair("SuperGlue/Iterations", std::make_pair(true, Parameters::kPyMatcherIterations())));
238  removedParameters_.insert(std::make_pair("SuperGlue/MatchThreshold", std::make_pair(true, Parameters::kPyMatcherThreshold())));
239  removedParameters_.insert(std::make_pair("SuperGlue/Cuda", std::make_pair(true, Parameters::kPyMatcherCuda())));
240  removedParameters_.insert(std::make_pair("SuperGlue/Indoor", std::make_pair(false, Parameters::kPyMatcherModel())));
241 
242  removedParameters_.insert(std::make_pair("Vis/CorCrossCheck", std::make_pair(false, Parameters::kVisCorNNType())));
243  removedParameters_.insert(std::make_pair("SPTorch/ModelPath", std::make_pair(true, Parameters::kSuperPointModelPath())));
244  removedParameters_.insert(std::make_pair("SPTorch/Threshold", std::make_pair(true, Parameters::kSuperPointThreshold())));
245  removedParameters_.insert(std::make_pair("SPTorch/NMS", std::make_pair(true, Parameters::kSuperPointNMS())));
246  removedParameters_.insert(std::make_pair("SPTorch/MinDistance", std::make_pair(true, Parameters::kSuperPointNMSRadius())));
247  removedParameters_.insert(std::make_pair("SPTorch/Cuda", std::make_pair(true, Parameters::kSuperPointCuda())));
248 
249  // 0.19.4
250  removedParameters_.insert(std::make_pair("RGBD/MaxLocalizationDistance", std::make_pair(true, Parameters::kRGBDMaxLoopClosureDistance())));
251 
252  // 0.19.3
253  removedParameters_.insert(std::make_pair("Aruco/Dictionary", std::make_pair(true, Parameters::kMarkerDictionary())));
254  removedParameters_.insert(std::make_pair("Aruco/MarkerLength", std::make_pair(true, Parameters::kMarkerLength())));
255  removedParameters_.insert(std::make_pair("Aruco/MaxDepthError", std::make_pair(true, Parameters::kMarkerMaxDepthError())));
256  removedParameters_.insert(std::make_pair("Aruco/VarianceLinear", std::make_pair(true, Parameters::kMarkerVarianceLinear())));
257  removedParameters_.insert(std::make_pair("Aruco/VarianceAngular", std::make_pair(true, Parameters::kMarkerVarianceAngular())));
258  removedParameters_.insert(std::make_pair("Aruco/CornerRefinementMethod", std::make_pair(true, Parameters::kMarkerCornerRefinementMethod())));
259 
260  // 0.17.5
261  removedParameters_.insert(std::make_pair("Grid/OctoMapOccupancyThr", std::make_pair(true, Parameters::kGridGlobalOccupancyThr())));
262 
263  // 0.17.0
264  removedParameters_.insert(std::make_pair("Grid/Scan2dMaxFilledRange", std::make_pair(false, Parameters::kGridRangeMax())));
265 
266  // 0.16.0
267  removedParameters_.insert(std::make_pair("Grid/ProjRayTracing", std::make_pair(true, Parameters::kGridRayTracing())));
268  removedParameters_.insert(std::make_pair("Grid/DepthMin", std::make_pair(true, Parameters::kGridRangeMin())));
269  removedParameters_.insert(std::make_pair("Grid/DepthMax", std::make_pair(true, Parameters::kGridRangeMax())));
270 
271  // 0.15.1
272  removedParameters_.insert(std::make_pair("Reg/VarianceFromInliersCount", std::make_pair(false, "")));
273  removedParameters_.insert(std::make_pair("Reg/VarianceNormalized", std::make_pair(false, "")));
274 
275  // 0.13.3
276  removedParameters_.insert(std::make_pair("Icp/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
277 
278 
279  // 0.13.1
280  removedParameters_.insert(std::make_pair("Rtabmap/VhStrategy", std::make_pair(true, Parameters::kVhEpEnabled())));
281 
282  // 0.12.5
283  removedParameters_.insert(std::make_pair("Grid/FullUpdate", std::make_pair(true, Parameters::kGridGlobalFullUpdate())));
284 
285  // 0.12.1
286  removedParameters_.insert(std::make_pair("Grid/3DGroundIsObstacle", std::make_pair(true, Parameters::kGridGroundIsObstacle())));
287 
288  // 0.11.12
289  removedParameters_.insert(std::make_pair("Optimizer/Slam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
290  removedParameters_.insert(std::make_pair("OdomF2M/FixedMapPath", std::make_pair(false, "")));
291 
292  // 0.11.10 typos
293  removedParameters_.insert(std::make_pair("Grid/FlatObstaclesDetected", std::make_pair(true, Parameters::kGridFlatObstacleDetected())));
294 
295  // 0.11.8
296  removedParameters_.insert(std::make_pair("Reg/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
297  removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius", std::make_pair(true, Parameters::kOdomF2MScanSubtractRadius())));
298 
299  // 0.11.6
300  removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false, "")));
301 
302  // 0.11.3
303  removedParameters_.insert(std::make_pair("Mem/ImageDecimation", std::make_pair(true, Parameters::kMemImagePostDecimation())));
304 
305  // 0.11.2
306  removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
307  removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath", std::make_pair(false, "")));
308  removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
309  removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
310 
311  // 0.11.0
312  removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
313  removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath", std::make_pair(false, "")));
314  removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
315  removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
316 
317  removedParameters_.insert(std::make_pair("Kp/WordsPerImage", std::make_pair(true, Parameters::kKpMaxFeatures())));
318 
319  removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM", std::make_pair(false, "")));
320 
321  removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
322 
323  removedParameters_.insert(std::make_pair("Odom/ParticleFiltering", std::make_pair(false, Parameters::kOdomFilteringStrategy())));
324  removedParameters_.insert(std::make_pair("Odom/FeatureType", std::make_pair(true, Parameters::kVisFeatureType())));
325  removedParameters_.insert(std::make_pair("Odom/EstimationType", std::make_pair(true, Parameters::kVisEstimationType())));
326  removedParameters_.insert(std::make_pair("Odom/MaxFeatures", std::make_pair(true, Parameters::kVisMaxFeatures())));
327  removedParameters_.insert(std::make_pair("Odom/InlierDistance", std::make_pair(true, Parameters::kVisInlierDistance())));
328  removedParameters_.insert(std::make_pair("Odom/MinInliers", std::make_pair(true, Parameters::kVisMinInliers())));
329  removedParameters_.insert(std::make_pair("Odom/Iterations", std::make_pair(true, Parameters::kVisIterations())));
330  removedParameters_.insert(std::make_pair("Odom/RefineIterations", std::make_pair(true, Parameters::kVisRefineIterations())));
331  removedParameters_.insert(std::make_pair("Odom/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
332  removedParameters_.insert(std::make_pair("Odom/RoiRatios", std::make_pair(true, Parameters::kVisRoiRatios())));
333  removedParameters_.insert(std::make_pair("Odom/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
334  removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(false, "")));
335  removedParameters_.insert(std::make_pair("Odom/PnPReprojError", std::make_pair(true, Parameters::kVisPnPReprojError())));
336  removedParameters_.insert(std::make_pair("Odom/PnPFlags", std::make_pair(true, Parameters::kVisPnPFlags())));
337 
338  removedParameters_.insert(std::make_pair("OdomBow/NNType", std::make_pair(true, Parameters::kVisCorNNType())));
339  removedParameters_.insert(std::make_pair("OdomBow/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
340 
341  removedParameters_.insert(std::make_pair("OdomFlow/WinSize", std::make_pair(true, Parameters::kVisCorFlowWinSize())));
342  removedParameters_.insert(std::make_pair("OdomFlow/Iterations", std::make_pair(true, Parameters::kVisCorFlowIterations())));
343  removedParameters_.insert(std::make_pair("OdomFlow/Eps", std::make_pair(true, Parameters::kVisCorFlowEps())));
344  removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel", std::make_pair(true, Parameters::kVisCorFlowMaxLevel())));
345 
346  removedParameters_.insert(std::make_pair("OdomSubPix/WinSize", std::make_pair(true, Parameters::kVisSubPixWinSize())));
347  removedParameters_.insert(std::make_pair("OdomSubPix/Iterations", std::make_pair(true, Parameters::kVisSubPixIterations())));
348  removedParameters_.insert(std::make_pair("OdomSubPix/Eps", std::make_pair(true, Parameters::kVisSubPixEps())));
349 
350  removedParameters_.insert(std::make_pair("LccReextract/Activated", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
351  removedParameters_.insert(std::make_pair("LccReextract/FeatureType", std::make_pair(false, Parameters::kVisFeatureType())));
352  removedParameters_.insert(std::make_pair("LccReextract/MaxWords", std::make_pair(false, Parameters::kVisMaxFeatures())));
353  removedParameters_.insert(std::make_pair("LccReextract/MaxDepth", std::make_pair(false, Parameters::kVisMaxDepth())));
354  removedParameters_.insert(std::make_pair("LccReextract/RoiRatios", std::make_pair(false, Parameters::kVisRoiRatios())));
355  removedParameters_.insert(std::make_pair("LccReextract/NNType", std::make_pair(false, Parameters::kVisCorNNType())));
356  removedParameters_.insert(std::make_pair("LccReextract/NNDR", std::make_pair(false, Parameters::kVisCorNNDR())));
357 
358  removedParameters_.insert(std::make_pair("LccBow/EstimationType", std::make_pair(false, Parameters::kVisEstimationType())));
359  removedParameters_.insert(std::make_pair("LccBow/InlierDistance", std::make_pair(false, Parameters::kVisInlierDistance())));
360  removedParameters_.insert(std::make_pair("LccBow/MinInliers", std::make_pair(false, Parameters::kVisMinInliers())));
361  removedParameters_.insert(std::make_pair("LccBow/Iterations", std::make_pair(false, Parameters::kVisIterations())));
362  removedParameters_.insert(std::make_pair("LccBow/RefineIterations", std::make_pair(false, Parameters::kVisRefineIterations())));
363  removedParameters_.insert(std::make_pair("LccBow/Force2D", std::make_pair(false, Parameters::kRegForce3DoF())));
364  removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false, "")));
365  removedParameters_.insert(std::make_pair("LccBow/PnPReprojError", std::make_pair(false, Parameters::kVisPnPReprojError())));
366  removedParameters_.insert(std::make_pair("LccBow/PnPFlags", std::make_pair(false, Parameters::kVisPnPFlags())));
367  removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar", std::make_pair(true, Parameters::kVisEpipolarGeometryVar())));
368 
369  removedParameters_.insert(std::make_pair("LccIcp/Type", std::make_pair(false, Parameters::kRegStrategy())));
370 
371  removedParameters_.insert(std::make_pair("LccIcp3/Decimation", std::make_pair(false, "")));
372  removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth", std::make_pair(false, "")));
373  removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize", std::make_pair(false, Parameters::kIcpVoxelSize())));
374  removedParameters_.insert(std::make_pair("LccIcp3/Samples", std::make_pair(false, Parameters::kIcpDownsamplingStep())));
375  removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance", std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
376  removedParameters_.insert(std::make_pair("LccIcp3/Iterations", std::make_pair(false, Parameters::kIcpIterations())));
377  removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio", std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
378  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane", std::make_pair(true, Parameters::kIcpPointToPlane())));
379  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
380 
381  removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance", std::make_pair(true, Parameters::kIcpMaxCorrespondenceDistance())));
382  removedParameters_.insert(std::make_pair("LccIcp2/Iterations", std::make_pair(true, Parameters::kIcpIterations())));
383  removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio", std::make_pair(true, Parameters::kIcpCorrespondenceRatio())));
384  removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize", std::make_pair(true, Parameters::kIcpVoxelSize())));
385 
386  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
387  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
388  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
389  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
390  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(false, "")));
391  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
392  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true, Parameters::kRGBDProximityPathFilteringRadius())));
393  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(true, Parameters::kRGBDProximityPathRawPosesUsed())));
394 
395  removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy", std::make_pair(true, Parameters::kOptimizerStrategy())));
396  removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon", std::make_pair(true, Parameters::kOptimizerEpsilon())));
397  removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
398  removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust", std::make_pair(true, Parameters::kOptimizerRobust())));
399  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
400  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d", std::make_pair(true, Parameters::kRegForce3DoF())));
401  removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored", std::make_pair(true, Parameters::kOptimizerVarianceIgnored())));
402 
403  removedParameters_.insert(std::make_pair("Stereo/WinSize", std::make_pair(true, Parameters::kStereoWinWidth())));
404 
405  // before 0.11.0
406  removedParameters_.insert(std::make_pair("GFTT/MaxCorners", std::make_pair(true, Parameters::kVisMaxFeatures())));
407  removedParameters_.insert(std::make_pair("LccBow/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
408  removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
409  removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy", std::make_pair(true, Parameters::kKpDetectorStrategy())));
410  removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
411  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius", std::make_pair(true, Parameters::kRGBDLocalRadius())));
412  removedParameters_.insert(std::make_pair("RGBD/ToroIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
413  removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept", std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
414  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
415  removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(false, "")));
416  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
417  removedParameters_.insert(std::make_pair("Odom/Type", std::make_pair(true, Parameters::kVisFeatureType())));
418  removedParameters_.insert(std::make_pair("Odom/MaxWords", std::make_pair(true, Parameters::kVisMaxFeatures())));
419  removedParameters_.insert(std::make_pair("Odom/LocalHistory", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
420  removedParameters_.insert(std::make_pair("Odom/NearestNeighbor", std::make_pair(true, Parameters::kVisCorNNType())));
421  removedParameters_.insert(std::make_pair("Odom/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
422  }
423  return removedParameters_;
424 }
425 
427 {
428  if(backwardCompatibilityMap_.empty())
429  {
430  getRemovedParameters(); // make sure removedParameters is filled
431 
432  // compatibility
433  for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
434  iter!=removedParameters_.end();
435  ++iter)
436  {
437  if(iter->second.first)
438  {
439  backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
440  }
441  }
442  }
444 }
445 
446 std::string Parameters::getType(const std::string & paramKey)
447 {
448  std::string type;
449  ParametersMap::iterator iter = parametersType_.find(paramKey);
450  if(iter != parametersType_.end())
451  {
452  type = iter->second;
453  }
454  else
455  {
456  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
457  }
458  return type;
459 }
460 
461 std::string Parameters::getDescription(const std::string & paramKey)
462 {
463  std::string description;
464  ParametersMap::iterator iter = descriptions_.find(paramKey);
465  if(iter != descriptions_.end())
466  {
467  description = iter->second;
468  }
469  else
470  {
471  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
472  }
473  return description;
474 }
475 
476 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
477 {
478  ParametersMap::const_iterator iter = parameters.find(key);
479  if(iter != parameters.end())
480  {
481  value = uStr2Bool(iter->second.c_str());
482  return true;
483  }
484  return false;
485 }
486 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
487 {
488  ParametersMap::const_iterator iter = parameters.find(key);
489  if(iter != parameters.end())
490  {
491  value = uStr2Int(iter->second.c_str());
492  return true;
493  }
494  return false;
495 }
496 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
497 {
498  ParametersMap::const_iterator iter = parameters.find(key);
499  if(iter != parameters.end())
500  {
501  value = uStr2Int(iter->second.c_str());
502  return true;
503  }
504  return false;
505 }
506 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
507 {
508  ParametersMap::const_iterator iter = parameters.find(key);
509  if(iter != parameters.end())
510  {
511  value = uStr2Float(iter->second);
512  return true;
513  }
514  return false;
515 }
516 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
517 {
518  ParametersMap::const_iterator iter = parameters.find(key);
519  if(iter != parameters.end())
520  {
521  value = uStr2Double(iter->second);
522  return true;
523  }
524  return false;
525 }
526 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
527 {
528  ParametersMap::const_iterator iter = parameters.find(key);
529  if(iter != parameters.end())
530  {
531  value = iter->second;
532  return true;
533  }
534  return false;
535 }
536 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
537 {
538  for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
539  {
540  ParametersMap::const_iterator jter = parameters.find(iter->first);
541  if(jter != parameters.end())
542  {
543  iter->second = jter->second;
544  }
545  }
546 }
547 
548 const char * Parameters::showUsage()
549 {
550  return "RTAB-Map options:\n"
551  " --help Show usage.\n"
552  " --version Show version of rtabmap and its dependencies.\n"
553  " --params Show all parameters with their default value and description. \n"
554  " If a database path is set as last argument, the parameters in the \n"
555  " database will be shown in INI format.\n"
556  " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n"
557  " --SURF/HessianThreshold 150\n"
558  " For parameters in table format, add ',' between values :\n"
559  " --Kp/RoiRatios 0,0,0.1,0\n"
560  "Logger options:\n"
561  " --nolog Disable logger\n"
562  " --logconsole Set logger console type\n"
563  " --logfile \"path\" Set logger file type\n"
564  " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n"
565  " --udebug Set logger level to debug\n"
566  " --uinfo Set logger level to info\n"
567  " --uwarn Set logger level to warn\n"
568  " --uerror Set logger level to error\n"
569  " --logtime \"bool\" Print time when logging\n"
570  " --logwhere \"bool\" Print where when logging\n"
571  " --logthread \"bool\" Print thread id when logging\n"
572  ;
573 }
574 
575 ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParameters)
576 {
577  ParametersMap out;
578  const ParametersMap & parameters = getDefaultParameters();
579  const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
580  for(int i=0;i<argc;++i)
581  {
582  bool checkParameters = onlyParameters;
583  if(!checkParameters)
584  {
585  if(strcmp(argv[i], "--help") == 0)
586  {
587  std::cout << showUsage() << std::endl;
588  exit(0);
589  }
590  else if(strcmp(argv[i], "--version") == 0)
591  {
592  std::string str = "RTAB-Map:";
593 
594  int spacing = 30;
595  std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
596  str = "PCL:";
597  std::cout << str << std::setw(spacing - str.size()) << PCL_VERSION_PRETTY << std::endl;
598  str = "With VTK:";
599 #ifndef DISABLE_VTK
600  std::cout << str << std::setw(spacing - str.size()) << vtkVersion::GetVTKVersion() << std::endl;
601 #else
602  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
603 #endif
604  str = "OpenCV:";
605  std::cout << str << std::setw(spacing - str.size()) << CV_VERSION << std::endl;
606 #if CV_MAJOR_VERSION >= 3
607  str = "With OpenCV xfeatures2d:";
608 #ifdef HAVE_OPENCV_XFEATURES2D
609  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
610 #else
611  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
612 #endif
613 #endif
614  str = "With OpenCV nonfree:";
615 #ifdef RTABMAP_NONFREE
616  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
617 #else
618  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
619 #endif
620  str = "With ORB OcTree:";
621 #ifdef RTABMAP_ORB_OCTREE
622  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
623 #else
624  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
625 #endif
626  str = "With SuperPoint Torch:";
627 #ifdef RTABMAP_SUPERPOINT_TORCH
628  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
629 #else
630  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
631 #endif
632  str = "With Python3:";
633 #ifdef RTABMAP_PYMATCHER
634  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
635 #else
636  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
637 #endif
638  str = "With FastCV:";
639 #ifdef RTABMAP_FASTCV
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 Madgwick:";
645 #ifdef RTABMAP_MADGWICK
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 TORO:";
651 #ifdef RTABMAP_TORO
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 g2o:";
657 #ifdef RTABMAP_G2O
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 GTSAM:";
663 #ifdef RTABMAP_GTSAM
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 Vertigo:";
669 #ifdef RTABMAP_VERTIGO
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 CVSBA:";
675 #ifdef RTABMAP_CVSBA
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 Ceres:";
681 #ifdef RTABMAP_CERES
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 OpenNI2:";
687 #ifdef RTABMAP_OPENNI2
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 Freenect:";
693 #ifdef RTABMAP_FREENECT
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 Freenect2:";
699 #ifdef RTABMAP_FREENECT2
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 K4W2:";
705 #ifdef RTABMAP_K4W2
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 K4A:";
711 #ifdef RTABMAP_K4A
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 DC1394:";
717 #ifdef RTABMAP_DC1394
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 FlyCapture2:";
723 #ifdef RTABMAP_FLYCAPTURE2
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 ZED:";
729 #ifdef RTABMAP_ZED
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 RealSense:";
735 #ifdef RTABMAP_REALSENSE
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 RealSense SLAM:";
741 #ifdef RTABMAP_REALSENSE_SLAM
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 RealSense2:";
747 #ifdef RTABMAP_REALSENSE2
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 MYNT EYE S:";
753 #ifdef RTABMAP_MYNTEYE
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 libpointmatcher:";
759 #ifdef RTABMAP_POINTMATCHER
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 octomap:";
765 #ifdef RTABMAP_OCTOMAP
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 cpu-tsdf:";
771 #ifdef RTABMAP_CPUTSDF
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 open chisel:";
777 #ifdef RTABMAP_OPENCHISEL
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 Alice Vision:";
783 #ifdef RTABMAP_ALICE_VISION
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 LOAM:";
789 #ifdef RTABMAP_LOAM
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 FOVIS:";
795 #ifdef RTABMAP_FOVIS
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 Viso2:";
801 #ifdef RTABMAP_VISO2
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 DVO:";
807 #ifdef RTABMAP_DVO
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 ORB_SLAM2:";
813 #ifdef RTABMAP_ORB_SLAM2
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 OKVIS:";
819 #ifdef RTABMAP_OKVIS
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 MSCKF_VIO:";
825 #ifdef RTABMAP_MSCKF_VIO
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 VINS-Fusion:";
831 #ifdef RTABMAP_VINS
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  exit(0);
837  }
838  else if(strcmp(argv[i], "--nolog") == 0)
839  {
841  }
842  else if(strcmp(argv[i], "--logconsole") == 0)
843  {
845  }
846  else if(strcmp(argv[i], "--logfile") == 0)
847  {
848  ++i;
849  if(i < argc)
850  {
851  ULogger::setType(ULogger::kTypeFile, argv[i], false);
852  }
853  else
854  {
855  UERROR("\"--logfile\" argument requires following file path");
856  }
857  }
858  else if(strcmp(argv[i], "--logfilea") == 0)
859  {
860  ++i;
861  if(i < argc)
862  {
863  ULogger::setType(ULogger::kTypeFile, argv[i], true);
864  }
865  else
866  {
867  UERROR("\"--logfilea\" argument requires following file path");
868  }
869  }
870  else if(strcmp(argv[i], "--udebug") == 0)
871  {
873  }
874  else if(strcmp(argv[i], "--uinfo") == 0)
875  {
877  }
878  else if(strcmp(argv[i], "--uwarn") == 0)
879  {
881  }
882  else if(strcmp(argv[i], "--uerror") == 0)
883  {
885  }
886  else if(strcmp(argv[i], "--ulogtime") == 0)
887  {
888  ++i;
889  if(i < argc)
890  {
892  }
893  else
894  {
895  UERROR("\"--ulogtime\" argument requires a following boolean value");
896  }
897  }
898  else if(strcmp(argv[i], "--ulogwhere") == 0)
899  {
900  ++i;
901  if(i < argc)
902  {
904  }
905  else
906  {
907  UERROR("\"--ulogwhere\" argument requires a following boolean value");
908  }
909  }
910  else if(strcmp(argv[i], "--ulogthread") == 0)
911  {
912  ++i;
913  if(i < argc)
914  {
916  }
917  else
918  {
919  UERROR("\"--ulogthread\" argument requires a following boolean value");
920  }
921  }
922  else
923  {
924  checkParameters = true;
925  }
926  }
927 
928  if(checkParameters) // check for parameters
929  {
930  if(strcmp(argv[i], "--params") == 0)
931  {
932  if (i < argc - 1)
933  {
934  // If the last argument is a database, dump the parameters in INI format
935  std::string dbName = argv[argc - 1];
936  if (UFile::exists(dbName) && UFile::getExtension(dbName).compare("db") == 0)
937  {
938  DBDriver * driver = DBDriver::create();
939  bool read = false;
940  if (driver->openConnection(dbName))
941  {
942  ParametersMap dbParameters = driver->getLastParameters();
943  if (!dbParameters.empty())
944  {
945  std::cout << "[Core]" << std::endl;
946  std::cout << "Version = " << RTABMAP_VERSION << std::endl;
947  for (ParametersMap::const_iterator iter = dbParameters.begin(); iter != dbParameters.end(); ++iter)
948  {
949  std::string key = iter->first;
950  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
951 
952  std::string value = iter->second.c_str();
953  value = uReplaceChar(value, '\\', '/'); // use always slash for values
954 
955  std::cout << key << " = " << value << std::endl;
956  }
957  read = true;
958  }
959  driver->closeConnection(false);
960  }
961  delete driver;
962  if (read)
963  {
964  exit(0);
965  }
966  }
967  }
968 
969  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
970  {
971  bool ignore = false;
972  UASSERT(uSplit(iter->first, '/').size() == 2);
973  std::string group = uSplit(iter->first, '/').front();
974 #ifndef RTABMAP_GTSAM
975  if(group.compare("GTSAM") == 0)
976  {
977  ignore = true;
978  }
979 #endif
980 #ifndef RTABMAP_G2O
981  if(group.compare("g2o") == 0)
982  {
983  ignore = true;
984  }
985 #endif
986 #ifndef RTABMAP_FOVIS
987  if(group.compare("OdomFovis") == 0)
988  {
989  ignore = true;
990  }
991 #endif
992 #ifndef RTABMAP_VISO2
993  if(group.compare("OdomViso2") == 0)
994  {
995  ignore = true;
996  }
997 #endif
998 #ifndef RTABMAP_ORBSLAM2
999  if(group.compare("OdomORBSLAM2") == 0)
1000  {
1001  ignore = true;
1002  }
1003 #endif
1004 #ifndef RTABMAP_OKVIS
1005  if(group.compare("OdomOKVIS") == 0)
1006  {
1007  ignore = true;
1008  }
1009 #endif
1010 #ifndef RTABMAP_LOAM
1011  if(group.compare("OdomLOAM") == 0)
1012  {
1013  ignore = true;
1014  }
1015 #endif
1016 #ifndef RTABMAP_MSCKF_VIO
1017  if(group.compare("OdomMSCKF") == 0)
1018  {
1019  ignore = true;
1020  }
1021 #endif
1022  if(!ignore)
1023  {
1024  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
1025  std::cout <<
1026  str <<
1027  std::setw(60 - str.size()) <<
1028  " [" <<
1029  rtabmap::Parameters::getDescription(iter->first).c_str() <<
1030  "]" <<
1031  std::endl;
1032  }
1033  }
1034  exit(0);
1035  }
1036  else
1037  {
1038  std::string key = uReplaceChar(argv[i], '-', "");
1039  ParametersMap::const_iterator iter = parameters.find(key);
1040  if(iter != parameters.end())
1041  {
1042  ++i;
1043  if(i < argc)
1044  {
1045  uInsert(out, ParametersPair(iter->first, argv[i]));
1046  UINFO("Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
1047  }
1048  }
1049  else
1050  {
1051  // backward compatibility
1052  std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
1053  if(jter!=removedParams.end())
1054  {
1055  if(jter->second.first)
1056  {
1057  ++i;
1058  if(i < argc)
1059  {
1060  std::string value = argv[i];
1061  if(!value.empty())
1062  {
1063  value = uReplaceChar(value, ',', ' '); // for table
1064  key = jter->second.second;
1065  UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
1066  jter->first.c_str(), jter->second.second.c_str(), value.c_str());
1067  uInsert(out, ParametersPair(key, value));
1068  }
1069  }
1070  else
1071  {
1072  UERROR("Value missing for argument \"%s\"", argv[i-1]);
1073  }
1074  }
1075  else if(jter->second.second.empty())
1076  {
1077  UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
1078  }
1079  else
1080  {
1081  UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
1082  }
1083  }
1084  }
1085  }
1086  }
1087  }
1088  return out;
1089 }
1090 
1091 
1092 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly)
1093 {
1094  CSimpleIniA ini;
1095  ini.LoadFile(configFile.c_str());
1096  const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
1097  if(keyValMap)
1098  {
1099  for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
1100  {
1101  std::string key = (*iter).first.pItem;
1102  if(key.compare("Version") == 0)
1103  {
1104  // Compare version in ini with the current RTAB-Map version
1105  std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
1106  if(version.size() == 3)
1107  {
1108  if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
1109  {
1110  if(configFile.find(".rtabmap") != std::string::npos)
1111  {
1112  UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
1113  "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
1114  "to new version.",
1115  configFile.c_str(),
1116  (*iter).second,
1117  RTABMAP_VERSION);
1118  }
1119  else
1120  {
1121  UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
1122  "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
1123  "be ignored.",
1124  configFile.c_str(),
1125  (*iter).second,
1126  RTABMAP_VERSION);
1127  }
1128  }
1129  }
1130  }
1131  else
1132  {
1133  key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
1134 
1135  // look for old parameter name
1136  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
1137  if(oldIter!=Parameters::getRemovedParameters().end())
1138  {
1139  if(oldIter->second.first)
1140  {
1141  if(parameters.find(oldIter->second.second) == parameters.end())
1142  {
1143  key = oldIter->second.second;
1144  UINFO("Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1145  oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second, Parameters::getDefaultParameters().at(oldIter->second.second).c_str());
1146  }
1147  }
1148  else if(oldIter->second.second.empty())
1149  {
1150  UWARN("Parameter \"%s\" doesn't exist anymore.",
1151  oldIter->first.c_str());
1152  }
1153  else if(parameters.find(oldIter->second.second) == parameters.end())
1154  {
1155  UWARN("Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1156  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());
1157  }
1158 
1159  }
1160 
1162  {
1163  if(!modifiedOnly || std::string(iter->second).compare(Parameters::getDefaultParameters().find(key)->second) != 0)
1164  {
1165  uInsert(parameters, ParametersPair(key, iter->second));
1166  }
1167  }
1168  }
1169  }
1170  }
1171  else
1172  {
1173  ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
1174  "Ignore this warning if the ini file does not exist yet. "
1175  "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
1176  }
1177 }
1178 
1179 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
1180 {
1181  CSimpleIniA ini;
1182  ini.LoadFile(configFile.c_str());
1183 
1184  // Save current version
1185  ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
1186 
1187  for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
1188  {
1189  std::string key = iter->first;
1190  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1191 
1192  std::string value = iter->second.c_str();
1193  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1194 
1195  ini.SetValue("Core", key.c_str(), value.c_str(), NULL, true);
1196  }
1197 
1198  // Delete removed parameters
1199  if(parameters.size() == getDefaultParameters().size())
1200  {
1201  for(std::map<std::string, std::pair<bool, std::string> >::const_iterator iter = removedParameters_.begin();
1202  iter!=removedParameters_.end();
1203  ++iter)
1204  {
1205  std::string key = iter->first;
1206  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1207 
1208  std::string value = ini.GetValue("Core", key.c_str(), "");
1209 
1210  if(ini.Delete("Core", key.c_str(), true))
1211  {
1212  if(iter->second.first && parameters.find(iter->second.second) != parameters.end())
1213  {
1214  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());
1215  }
1216  else
1217  {
1218  UWARN("Removed deprecated parameter %s=%s from \"%s\".", iter->first.c_str(), value.c_str(), configFile.c_str());
1219  }
1220  }
1221  }
1222  }
1223 
1224  ini.SaveFile(configFile.c_str());
1225 }
1226 
1227 }
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
static ParametersMap filterParameters(const ParametersMap &parameters, const std::string &group)
Definition: Parameters.cpp:214
#define NULL
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:476
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
Definition: Parameters.cpp:229
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:461
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:548
SI_Error SaveFile(const char *a_pszFile, bool a_bAddSignature=true) const
Definition: SimpleIni.h:2305
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:575
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:839
static void writeINI(const std::string &configFile, const ParametersMap &parameters)
static ParametersMap backwardCompatibilityMap_
Definition: Parameters.h:843
Some conversion functions.
static ParametersMap getDefaultOdometryParameters(bool stereo=false, bool vis=true, bool icp=false)
Definition: Parameters.cpp:173
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(...)
std::list< std::string > uSplit(const std::string &str, char separator= ' ')
Definition: UStl.h:566
const TKeyVal * GetSection(const SI_CHAR *a_pSection) const
Definition: SimpleIni.h:2246
bool openConnection(const std::string &url, bool overwritten=false)
Definition: DBDriver.cpp:86
#define UASSERT(condition)
Wrappers of STL for convenient functions.
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:840
static const ParametersMap & getBackwardCompatibilityMap()
Definition: Parameters.cpp:426
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
Transform RTABMAP_EXP icp(const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_source, const pcl::PointCloud< pcl::PointXYZ >::ConstPtr &cloud_target, double maxCorrespondenceDistance, int maximumIterations, bool &hasConverged, pcl::PointCloud< pcl::PointXYZ > &cloud_source_registered, float epsilon=0.0f, bool icp2D=false)
static void setType(Type type, const std::string &fileName=kDefaultLogFileName, bool append=true)
Definition: ULogger.cpp:176
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
static ParametersMap parameters_
Definition: Parameters.h:837
std::string UTILITE_EXP uReplaceChar(const std::string &str, char before, char after)
Definition: UConversion.cpp:32
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:446
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:778
#define UDEBUG(...)
bool exists()
Definition: UFile.h:104
virtual ~Parameters()
Definition: Parameters.cpp:62
#define UERROR(...)
ParametersMap getLastParameters() const
Definition: DBDriver.cpp:239
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
ULogger class and convenient macros.
static ParametersMap parametersType_
Definition: Parameters.h:838
#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
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:842
static std::string createDefaultWorkingDirectory()
Definition: Parameters.cpp:66
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 Dec 14 2020 03:34:59