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 
32 #include <rtabmap/utilite/UStl.h>
33 #include <cmath>
34 #include <stdlib.h>
35 #include <sstream>
36 #include <iostream>
37 #include <iomanip>
38 #include "SimpleIni.h"
39 
40 namespace rtabmap
41 {
42 
46 Parameters Parameters::instance_;
47 std::map<std::string, std::pair<bool, std::string> > Parameters::removedParameters_;
49 
51 {
52 }
53 
55 {
56 }
57 
59 {
60  std::string path = UDirectory::homeDir();
61  if(!path.empty())
62  {
63  UDirectory::makeDir(path += UDirectory::separator() + "Documents");
64  UDirectory::makeDir(path += UDirectory::separator() + "RTAB-Map");
65 
66  }
67  else
68  {
69  UFATAL("Can't get the HOME variable environment!");
70  }
71  return path;
72 }
73 
75 {
76  return RTABMAP_VERSION;
77  return ""; // Second return only to avoid compiler warning with RTABMAP_VERSION not yet set.
78 }
79 
81 {
82  return "rtabmap.db";
83 }
84 
85 std::string Parameters::serialize(const ParametersMap & parameters)
86 {
87  std::stringstream output;
88  for(ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
89  {
90  if(iter != parameters.begin())
91  {
92  output << ";";
93  }
94  // make sure there are no commas instead of dots
95  output << iter->first << ":" << uReplaceChar(iter->second, ',', '.');
96  }
97  UDEBUG("output=%s", output.str().c_str());
98  return output.str();
99 }
100 
101 ParametersMap Parameters::deserialize(const std::string & parameters)
102 {
103  UDEBUG("parameters=%s", parameters.c_str());
104  ParametersMap output;
105  std::list<std::string> tuplets = uSplit(parameters, ';');
106  for(std::list<std::string>::iterator iter=tuplets.begin(); iter!=tuplets.end(); ++iter)
107  {
108  std::list<std::string> p = uSplit(*iter, ':');
109  if(p.size() == 2)
110  {
111  std::string key = p.front();
112  std::string value = p.back();
113 
114  // look for old parameter name
115  bool addParameter = true;
116  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
117  if(oldIter!=Parameters::getRemovedParameters().end())
118  {
119  addParameter = oldIter->second.first;
120  if(addParameter)
121  {
122  key = oldIter->second.second;
123  UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
124  oldIter->first.c_str(), oldIter->second.second.c_str(), value.c_str());
125  }
126  else if(oldIter->second.second.empty())
127  {
128  UWARN("Parameter \"%s\" doesn't exist anymore.",
129  oldIter->first.c_str());
130  }
131  else
132  {
133  UWARN("Parameter \"%s\" doesn't exist anymore, you may want to use this similar parameter \"%s\":\"%s\".",
134  oldIter->first.c_str(), oldIter->second.second.c_str(), Parameters::getDescription(oldIter->second.second).c_str());
135  }
136 
137  }
138 
139  if(oldIter==Parameters::getRemovedParameters().end() &&
141  {
142  UWARN("Unknown parameter \"%s\"=\"%s\"! The parameter is still added to output map.", key.c_str(), value.c_str());
143  }
144  uInsert(output, ParametersPair(key, value));
145  }
146  }
147  return output;
148 }
149 
150 bool Parameters::isFeatureParameter(const std::string & parameter)
151 {
152  std::string group = uSplit(parameter, '/').front();
153  return group.compare("SURF") == 0 ||
154  group.compare("SIFT") == 0 ||
155  group.compare("ORB") == 0 ||
156  group.compare("FAST") == 0 ||
157  group.compare("FREAK") == 0 ||
158  group.compare("BRIEF") == 0 ||
159  group.compare("GFTT") == 0 ||
160  group.compare("BRISK") == 0 ||
161  group.compare("KAZE") == 0;
162 }
163 
165 {
166  rtabmap::ParametersMap odomParameters;
168  for(rtabmap::ParametersMap::iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
169  {
170  std::string group = uSplit(iter->first, '/').front();
171  if(uStrContains(group, "Odom") ||
172  (stereo && group.compare("Stereo") == 0) ||
173  (icp && group.compare("Icp") == 0) ||
174  (vis && Parameters::isFeatureParameter(iter->first)) ||
175  group.compare("Reg") == 0 ||
176  (vis && group.compare("Vis") == 0) ||
177  iter->first.compare(kRtabmapPublishRAMUsage())==0)
178  {
179  if(stereo)
180  {
181  if(iter->first.compare(Parameters::kVisEstimationType()) == 0)
182  {
183  iter->second = "1"; // 3D->2D (PNP)
184  }
185  }
186  odomParameters.insert(*iter);
187  }
188  }
189  return odomParameters;
190 }
191 
193 {
194  rtabmap::ParametersMap parameters;
196  for(rtabmap::ParametersMap::const_iterator iter=defaultParameters.begin(); iter!=defaultParameters.end(); ++iter)
197  {
198  UASSERT(uSplit(iter->first, '/').size() == 2);
199  std::string group = uSplit(iter->first, '/').front();
200  if(group.compare(groupIn) == 0)
201  {
202  parameters.insert(*iter);
203  }
204  }
205  UASSERT_MSG(parameters.size(), uFormat("No parameters found for group %s!", groupIn.c_str()).c_str());
206  return parameters;
207 }
208 
209 ParametersMap Parameters::filterParameters(const ParametersMap & parameters, const std::string & groupIn)
210 {
211  ParametersMap output;
212  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
213  {
214  UASSERT(uSplit(iter->first, '/').size() == 2);
215  std::string group = uSplit(iter->first, '/').front();
216  if(group.compare(groupIn) == 0)
217  {
218  output.insert(*iter);
219  }
220  }
221  return output;
222 }
223 
224 const std::map<std::string, std::pair<bool, std::string> > & Parameters::getRemovedParameters()
225 {
226  if(removedParameters_.empty())
227  {
228  // removed parameters
229 
230  // 0.17.5
231  removedParameters_.insert(std::make_pair("Grid/OctoMapOccupancyThr", std::make_pair(true, Parameters::kGridGlobalOccupancyThr())));
232 
233  // 0.17.0
234  removedParameters_.insert(std::make_pair("Grid/Scan2dMaxFilledRange", std::make_pair(false, Parameters::kGridRangeMax())));
235 
236  // 0.16.0
237  removedParameters_.insert(std::make_pair("Grid/ProjRayTracing", std::make_pair(true, Parameters::kGridRayTracing())));
238  removedParameters_.insert(std::make_pair("Grid/DepthMin", std::make_pair(true, Parameters::kGridRangeMin())));
239  removedParameters_.insert(std::make_pair("Grid/DepthMax", std::make_pair(true, Parameters::kGridRangeMax())));
240 
241  // 0.15.1
242  removedParameters_.insert(std::make_pair("Reg/VarianceFromInliersCount", std::make_pair(false, "")));
243  removedParameters_.insert(std::make_pair("Reg/VarianceNormalized", std::make_pair(false, "")));
244 
245  // 0.13.3
246  removedParameters_.insert(std::make_pair("Icp/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
247 
248 
249  // 0.13.1
250  removedParameters_.insert(std::make_pair("Rtabmap/VhStrategy", std::make_pair(true, Parameters::kVhEpEnabled())));
251 
252  // 0.12.5
253  removedParameters_.insert(std::make_pair("Grid/FullUpdate", std::make_pair(true, Parameters::kGridGlobalFullUpdate())));
254 
255  // 0.12.1
256  removedParameters_.insert(std::make_pair("Grid/3DGroundIsObstacle", std::make_pair(true, Parameters::kGridGroundIsObstacle())));
257 
258  // 0.11.12
259  removedParameters_.insert(std::make_pair("Optimizer/Slam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
260  removedParameters_.insert(std::make_pair("OdomF2M/FixedMapPath", std::make_pair(false, "")));
261 
262  // 0.11.10 typos
263  removedParameters_.insert(std::make_pair("Grid/FlatObstaclesDetected", std::make_pair(true, Parameters::kGridFlatObstacleDetected())));
264 
265  // 0.11.8
266  removedParameters_.insert(std::make_pair("Reg/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
267  removedParameters_.insert(std::make_pair("OdomF2M/ScanSubstractRadius", std::make_pair(true, Parameters::kOdomF2MScanSubtractRadius())));
268 
269  // 0.11.6
270  removedParameters_.insert(std::make_pair("RGBD/ProximityPathScansMerged", std::make_pair(false, "")));
271 
272  // 0.11.3
273  removedParameters_.insert(std::make_pair("Mem/ImageDecimation", std::make_pair(true, Parameters::kMemImagePostDecimation())));
274 
275  // 0.11.2
276  removedParameters_.insert(std::make_pair("OdomLocalMap/HistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
277  removedParameters_.insert(std::make_pair("OdomLocalMap/FixedMapPath", std::make_pair(false, "")));
278  removedParameters_.insert(std::make_pair("OdomF2F/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
279  removedParameters_.insert(std::make_pair("OdomF2F/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
280 
281  // 0.11.0
282  removedParameters_.insert(std::make_pair("OdomBow/LocalHistorySize", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
283  removedParameters_.insert(std::make_pair("OdomBow/FixedLocalMapPath", std::make_pair(false, "")));
284  removedParameters_.insert(std::make_pair("OdomFlow/KeyFrameThr", std::make_pair(false, Parameters::kOdomKeyFrameThr())));
285  removedParameters_.insert(std::make_pair("OdomFlow/GuessMotion", std::make_pair(true, Parameters::kOdomGuessMotion())));
286 
287  removedParameters_.insert(std::make_pair("Kp/WordsPerImage", std::make_pair(true, Parameters::kKpMaxFeatures())));
288 
289  removedParameters_.insert(std::make_pair("Mem/LocalSpaceLinksKeptInWM", std::make_pair(false, "")));
290 
291  removedParameters_.insert(std::make_pair("RGBD/PoseScanMatching", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
292 
293  removedParameters_.insert(std::make_pair("Odom/ParticleFiltering", std::make_pair(false, Parameters::kOdomFilteringStrategy())));
294  removedParameters_.insert(std::make_pair("Odom/FeatureType", std::make_pair(true, Parameters::kVisFeatureType())));
295  removedParameters_.insert(std::make_pair("Odom/EstimationType", std::make_pair(true, Parameters::kVisEstimationType())));
296  removedParameters_.insert(std::make_pair("Odom/MaxFeatures", std::make_pair(true, Parameters::kVisMaxFeatures())));
297  removedParameters_.insert(std::make_pair("Odom/InlierDistance", std::make_pair(true, Parameters::kVisInlierDistance())));
298  removedParameters_.insert(std::make_pair("Odom/MinInliers", std::make_pair(true, Parameters::kVisMinInliers())));
299  removedParameters_.insert(std::make_pair("Odom/Iterations", std::make_pair(true, Parameters::kVisIterations())));
300  removedParameters_.insert(std::make_pair("Odom/RefineIterations", std::make_pair(true, Parameters::kVisRefineIterations())));
301  removedParameters_.insert(std::make_pair("Odom/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
302  removedParameters_.insert(std::make_pair("Odom/RoiRatios", std::make_pair(true, Parameters::kVisRoiRatios())));
303  removedParameters_.insert(std::make_pair("Odom/Force2D", std::make_pair(true, Parameters::kRegForce3DoF())));
304  removedParameters_.insert(std::make_pair("Odom/VarianceFromInliersCount", std::make_pair(false, "")));
305  removedParameters_.insert(std::make_pair("Odom/PnPReprojError", std::make_pair(true, Parameters::kVisPnPReprojError())));
306  removedParameters_.insert(std::make_pair("Odom/PnPFlags", std::make_pair(true, Parameters::kVisPnPFlags())));
307 
308  removedParameters_.insert(std::make_pair("OdomBow/NNType", std::make_pair(true, Parameters::kVisCorNNType())));
309  removedParameters_.insert(std::make_pair("OdomBow/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
310 
311  removedParameters_.insert(std::make_pair("OdomFlow/WinSize", std::make_pair(true, Parameters::kVisCorFlowWinSize())));
312  removedParameters_.insert(std::make_pair("OdomFlow/Iterations", std::make_pair(true, Parameters::kVisCorFlowIterations())));
313  removedParameters_.insert(std::make_pair("OdomFlow/Eps", std::make_pair(true, Parameters::kVisCorFlowEps())));
314  removedParameters_.insert(std::make_pair("OdomFlow/MaxLevel", std::make_pair(true, Parameters::kVisCorFlowMaxLevel())));
315 
316  removedParameters_.insert(std::make_pair("OdomSubPix/WinSize", std::make_pair(true, Parameters::kVisSubPixWinSize())));
317  removedParameters_.insert(std::make_pair("OdomSubPix/Iterations", std::make_pair(true, Parameters::kVisSubPixIterations())));
318  removedParameters_.insert(std::make_pair("OdomSubPix/Eps", std::make_pair(true, Parameters::kVisSubPixEps())));
319 
320  removedParameters_.insert(std::make_pair("LccReextract/Activated", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
321  removedParameters_.insert(std::make_pair("LccReextract/FeatureType", std::make_pair(false, Parameters::kVisFeatureType())));
322  removedParameters_.insert(std::make_pair("LccReextract/MaxWords", std::make_pair(false, Parameters::kVisMaxFeatures())));
323  removedParameters_.insert(std::make_pair("LccReextract/MaxDepth", std::make_pair(false, Parameters::kVisMaxDepth())));
324  removedParameters_.insert(std::make_pair("LccReextract/RoiRatios", std::make_pair(false, Parameters::kVisRoiRatios())));
325  removedParameters_.insert(std::make_pair("LccReextract/NNType", std::make_pair(false, Parameters::kVisCorNNType())));
326  removedParameters_.insert(std::make_pair("LccReextract/NNDR", std::make_pair(false, Parameters::kVisCorNNDR())));
327 
328  removedParameters_.insert(std::make_pair("LccBow/EstimationType", std::make_pair(false, Parameters::kVisEstimationType())));
329  removedParameters_.insert(std::make_pair("LccBow/InlierDistance", std::make_pair(false, Parameters::kVisInlierDistance())));
330  removedParameters_.insert(std::make_pair("LccBow/MinInliers", std::make_pair(false, Parameters::kVisMinInliers())));
331  removedParameters_.insert(std::make_pair("LccBow/Iterations", std::make_pair(false, Parameters::kVisIterations())));
332  removedParameters_.insert(std::make_pair("LccBow/RefineIterations", std::make_pair(false, Parameters::kVisRefineIterations())));
333  removedParameters_.insert(std::make_pair("LccBow/Force2D", std::make_pair(false, Parameters::kRegForce3DoF())));
334  removedParameters_.insert(std::make_pair("LccBow/VarianceFromInliersCount", std::make_pair(false, "")));
335  removedParameters_.insert(std::make_pair("LccBow/PnPReprojError", std::make_pair(false, Parameters::kVisPnPReprojError())));
336  removedParameters_.insert(std::make_pair("LccBow/PnPFlags", std::make_pair(false, Parameters::kVisPnPFlags())));
337  removedParameters_.insert(std::make_pair("LccBow/EpipolarGeometryVar", std::make_pair(true, Parameters::kVisEpipolarGeometryVar())));
338 
339  removedParameters_.insert(std::make_pair("LccIcp/Type", std::make_pair(false, Parameters::kRegStrategy())));
340 
341  removedParameters_.insert(std::make_pair("LccIcp3/Decimation", std::make_pair(false, "")));
342  removedParameters_.insert(std::make_pair("LccIcp3/MaxDepth", std::make_pair(false, "")));
343  removedParameters_.insert(std::make_pair("LccIcp3/VoxelSize", std::make_pair(false, Parameters::kIcpVoxelSize())));
344  removedParameters_.insert(std::make_pair("LccIcp3/Samples", std::make_pair(false, Parameters::kIcpDownsamplingStep())));
345  removedParameters_.insert(std::make_pair("LccIcp3/MaxCorrespondenceDistance", std::make_pair(false, Parameters::kIcpMaxCorrespondenceDistance())));
346  removedParameters_.insert(std::make_pair("LccIcp3/Iterations", std::make_pair(false, Parameters::kIcpIterations())));
347  removedParameters_.insert(std::make_pair("LccIcp3/CorrespondenceRatio", std::make_pair(false, Parameters::kIcpCorrespondenceRatio())));
348  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlane", std::make_pair(true, Parameters::kIcpPointToPlane())));
349  removedParameters_.insert(std::make_pair("LccIcp3/PointToPlaneNormalNeighbors", std::make_pair(true, Parameters::kIcpPointToPlaneK())));
350 
351  removedParameters_.insert(std::make_pair("LccIcp2/MaxCorrespondenceDistance", std::make_pair(true, Parameters::kIcpMaxCorrespondenceDistance())));
352  removedParameters_.insert(std::make_pair("LccIcp2/Iterations", std::make_pair(true, Parameters::kIcpIterations())));
353  removedParameters_.insert(std::make_pair("LccIcp2/CorrespondenceRatio", std::make_pair(true, Parameters::kIcpCorrespondenceRatio())));
354  removedParameters_.insert(std::make_pair("LccIcp2/VoxelSize", std::make_pair(true, Parameters::kIcpVoxelSize())));
355 
356  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionByTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
357  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionBySpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
358  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionTime", std::make_pair(true, Parameters::kRGBDProximityByTime())));
359  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionSpace", std::make_pair(true, Parameters::kRGBDProximityBySpace())));
360  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathScansMerged", std::make_pair(false, "")));
361  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxGraphDepth", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
362  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathFilteringRadius", std::make_pair(true, Parameters::kRGBDProximityPathFilteringRadius())));
363  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionPathRawPosesUsed", std::make_pair(true, Parameters::kRGBDProximityPathRawPosesUsed())));
364 
365  removedParameters_.insert(std::make_pair("RGBD/OptimizeStrategy", std::make_pair(true, Parameters::kOptimizerStrategy())));
366  removedParameters_.insert(std::make_pair("RGBD/OptimizeEpsilon", std::make_pair(true, Parameters::kOptimizerEpsilon())));
367  removedParameters_.insert(std::make_pair("RGBD/OptimizeIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
368  removedParameters_.insert(std::make_pair("RGBD/OptimizeRobust", std::make_pair(true, Parameters::kOptimizerRobust())));
369  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2D", std::make_pair(true, Parameters::kRegForce3DoF())));
370  removedParameters_.insert(std::make_pair("RGBD/OptimizeSlam2d", std::make_pair(true, Parameters::kRegForce3DoF())));
371  removedParameters_.insert(std::make_pair("RGBD/OptimizeVarianceIgnored", std::make_pair(true, Parameters::kOptimizerVarianceIgnored())));
372 
373  removedParameters_.insert(std::make_pair("Stereo/WinSize", std::make_pair(true, Parameters::kStereoWinWidth())));
374 
375  // before 0.11.0
376  removedParameters_.insert(std::make_pair("GFTT/MaxCorners", std::make_pair(true, Parameters::kVisMaxFeatures())));
377  removedParameters_.insert(std::make_pair("LccBow/MaxDepth", std::make_pair(true, Parameters::kVisMaxDepth())));
378  removedParameters_.insert(std::make_pair("LccReextract/LoopClosureFeatures", std::make_pair(true, Parameters::kRGBDLoopClosureReextractFeatures())));
379  removedParameters_.insert(std::make_pair("Rtabmap/DetectorStrategy", std::make_pair(true, Parameters::kKpDetectorStrategy())));
380  removedParameters_.insert(std::make_pair("RGBD/ScanMatchingSize", std::make_pair(true, Parameters::kRGBDNeighborLinkRefining())));
381  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionRadius", std::make_pair(true, Parameters::kRGBDLocalRadius())));
382  removedParameters_.insert(std::make_pair("RGBD/ToroIterations", std::make_pair(true, Parameters::kOptimizerIterations())));
383  removedParameters_.insert(std::make_pair("Mem/RehearsedNodesKept", std::make_pair(true, Parameters::kMemNotLinkedNodesKept())));
384  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(true, Parameters::kRGBDProximityMaxGraphDepth())));
385  removedParameters_.insert(std::make_pair("RGBD/PlanVirtualLinksMaxDiffID", std::make_pair(false, "")));
386  removedParameters_.insert(std::make_pair("RGBD/LocalLoopDetectionMaxDiffID", std::make_pair(false, "")));
387  removedParameters_.insert(std::make_pair("Odom/Type", std::make_pair(true, Parameters::kVisFeatureType())));
388  removedParameters_.insert(std::make_pair("Odom/MaxWords", std::make_pair(true, Parameters::kVisMaxFeatures())));
389  removedParameters_.insert(std::make_pair("Odom/LocalHistory", std::make_pair(true, Parameters::kOdomF2MMaxSize())));
390  removedParameters_.insert(std::make_pair("Odom/NearestNeighbor", std::make_pair(true, Parameters::kVisCorNNType())));
391  removedParameters_.insert(std::make_pair("Odom/NNDR", std::make_pair(true, Parameters::kVisCorNNDR())));
392  }
393  return removedParameters_;
394 }
395 
397 {
398  if(backwardCompatibilityMap_.empty())
399  {
400  getRemovedParameters(); // make sure removedParameters is filled
401 
402  // compatibility
403  for(std::map<std::string, std::pair<bool, std::string> >::iterator iter=removedParameters_.begin();
404  iter!=removedParameters_.end();
405  ++iter)
406  {
407  if(iter->second.first)
408  {
409  backwardCompatibilityMap_.insert(ParametersPair(iter->second.second, iter->first));
410  }
411  }
412  }
414 }
415 
416 std::string Parameters::getType(const std::string & paramKey)
417 {
418  std::string type;
419  ParametersMap::iterator iter = parametersType_.find(paramKey);
420  if(iter != parametersType_.end())
421  {
422  type = iter->second;
423  }
424  else
425  {
426  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
427  }
428  return type;
429 }
430 
431 std::string Parameters::getDescription(const std::string & paramKey)
432 {
433  std::string description;
434  ParametersMap::iterator iter = descriptions_.find(paramKey);
435  if(iter != descriptions_.end())
436  {
437  description = iter->second;
438  }
439  else
440  {
441  UERROR("Parameters \"%s\" doesn't exist!", paramKey.c_str());
442  }
443  return description;
444 }
445 
446 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, bool & value)
447 {
448  ParametersMap::const_iterator iter = parameters.find(key);
449  if(iter != parameters.end())
450  {
451  value = uStr2Bool(iter->second.c_str());
452  return true;
453  }
454  return false;
455 }
456 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, int & value)
457 {
458  ParametersMap::const_iterator iter = parameters.find(key);
459  if(iter != parameters.end())
460  {
461  value = uStr2Int(iter->second.c_str());
462  return true;
463  }
464  return false;
465 }
466 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, unsigned int & value)
467 {
468  ParametersMap::const_iterator iter = parameters.find(key);
469  if(iter != parameters.end())
470  {
471  value = uStr2Int(iter->second.c_str());
472  return true;
473  }
474  return false;
475 }
476 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, float & value)
477 {
478  ParametersMap::const_iterator iter = parameters.find(key);
479  if(iter != parameters.end())
480  {
481  value = uStr2Float(iter->second);
482  return true;
483  }
484  return false;
485 }
486 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, double & value)
487 {
488  ParametersMap::const_iterator iter = parameters.find(key);
489  if(iter != parameters.end())
490  {
491  value = uStr2Double(iter->second);
492  return true;
493  }
494  return false;
495 }
496 bool Parameters::parse(const ParametersMap & parameters, const std::string & key, std::string & value)
497 {
498  ParametersMap::const_iterator iter = parameters.find(key);
499  if(iter != parameters.end())
500  {
501  value = iter->second;
502  return true;
503  }
504  return false;
505 }
506 void Parameters::parse(const ParametersMap & parameters, ParametersMap & parametersOut)
507 {
508  for(ParametersMap::iterator iter=parametersOut.begin(); iter!=parametersOut.end(); ++iter)
509  {
510  ParametersMap::const_iterator jter = parameters.find(iter->first);
511  if(jter != parameters.end())
512  {
513  iter->second = jter->second;
514  }
515  }
516 }
517 
518 const char * Parameters::showUsage()
519 {
520  return "RTAB-Map options:\n"
521  " --help Show usage.\n"
522  " --version Show version of rtabmap and its dependencies.\n"
523  " --params Show all parameters with their default value and description\n"
524  " --\"parameter name\" \"value\" Overwrite a specific RTAB-Map's parameter :\n"
525  " --SURF/HessianThreshold 150\n"
526  " For parameters in table format, add ',' between values :\n"
527  " --Kp/RoiRatios 0,0,0.1,0\n"
528  "Logger options:\n"
529  " --nolog Disable logger\n"
530  " --logconsole Set logger console type\n"
531  " --logfile \"path\" Set logger file type\n"
532  " --logfilea \"path\" Set logger file type with appending mode if the file already exists\n"
533  " --udebug Set logger level to debug\n"
534  " --uinfo Set logger level to info\n"
535  " --uwarn Set logger level to warn\n"
536  " --uerror Set logger level to error\n"
537  " --logtime \"bool\" Print time when logging\n"
538  " --logwhere \"bool\" Print where when logging\n"
539  " --logthread \"bool\" Print thread id when logging\n"
540  ;
541 }
542 
543 ParametersMap Parameters::parseArguments(int argc, char * argv[], bool onlyParameters)
544 {
545  ParametersMap out;
546  const ParametersMap & parameters = getDefaultParameters();
547  const std::map<std::string, std::pair<bool, std::string> > & removedParams = getRemovedParameters();
548  for(int i=0;i<argc;++i)
549  {
550  bool checkParameters = onlyParameters;
551  if(!checkParameters)
552  {
553  if(strcmp(argv[i], "--help") == 0)
554  {
555  std::cout << showUsage() << std::endl;
556  exit(0);
557  }
558  else if(strcmp(argv[i], "--version") == 0)
559  {
560  std::string str = "RTAB-Map:";
561 
562  int spacing = 30;
563  std::cout << str << std::setw(spacing - str.size()) << RTABMAP_VERSION << std::endl;
564  str = "OpenCV:";
565 #ifdef RTABMAP_OPENCV3
566  std::cout << str << std::setw(spacing - str.size()) << "3" << std::endl;
567 #else
568  std::cout << str << std::setw(spacing - str.size()) << "2" << std::endl;
569 #endif
570  str = "With OpenCV nonfree:";
571 #ifdef RTABMAP_NONFREE
572  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
573 #else
574  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
575 #endif
576  str = "With TORO:";
577 #ifdef RTABMAP_TORO
578  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
579 #else
580  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
581 #endif
582  str = "With g2o:";
583 #ifdef RTABMAP_G2O
584  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
585 #else
586  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
587 #endif
588  str = "With GTSAM:";
589 #ifdef RTABMAP_GTSAM
590  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
591 #else
592  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
593 #endif
594  str = "With Vertigo:";
595 #ifdef RTABMAP_VERTIGO
596  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
597 #else
598  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
599 #endif
600  str = "With CVSBA:";
601 #ifdef RTABMAP_CVSBA
602  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
603 #else
604  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
605 #endif
606  str = "With OpenNI2:";
607 #ifdef RTABMAP_OPENNI2
608  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
609 #else
610  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
611 #endif
612  str = "With Freenect:";
613 #ifdef RTABMAP_FREENECT
614  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
615 #else
616  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
617 #endif
618  str = "With Freenect2:";
619 #ifdef RTABMAP_FREENECT2
620  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
621 #else
622  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
623 #endif
624  str = "With K4W2:";
625 #ifdef RTABMAP_K4W2
626  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
627 #else
628  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
629 #endif
630  str = "With DC1394:";
631 #ifdef RTABMAP_DC1394
632  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
633 #else
634  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
635 #endif
636  str = "With FlyCapture2:";
637 #ifdef RTABMAP_FLYCAPTURE2
638  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
639 #else
640  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
641 #endif
642  str = "With ZED:";
643 #ifdef RTABMAP_ZED
644  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
645 #else
646  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
647 #endif
648  str = "With RealSense:";
649 #ifdef RTABMAP_REALSENSE
650  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
651 #else
652  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
653 #endif
654  str = "With RealSense SLAM:";
655 #ifdef RTABMAP_REALSENSE_SLAM
656  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
657 #else
658  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
659 #endif
660  str = "With RealSense2:";
661 #ifdef RTABMAP_REALSENSE2
662  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
663 #else
664  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
665 #endif
666  str = "With libpointmatcher:";
667 #ifdef RTABMAP_POINTMATCHER
668  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
669 #else
670  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
671 #endif
672  str = "With octomap:";
673 #ifdef RTABMAP_OCTOMAP
674  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
675 #else
676  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
677 #endif
678  str = "With cpu-tsdf:";
679 #ifdef RTABMAP_CPUTSDF
680  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
681 #else
682  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
683 #endif
684  str = "With open chisel:";
685 #ifdef RTABMAP_OPENCHISEL
686  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
687 #else
688  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
689 #endif
690  str = "With LOAM:";
691 #ifdef RTABMAP_LOAM
692  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
693 #else
694  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
695 #endif
696  str = "With FOVIS:";
697 #ifdef RTABMAP_FOVIS
698  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
699 #else
700  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
701 #endif
702  str = "With Viso2:";
703 #ifdef RTABMAP_VISO2
704  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
705 #else
706  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
707 #endif
708  str = "With DVO:";
709 #ifdef RTABMAP_DVO
710  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
711 #else
712  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
713 #endif
714  str = "With ORB_SLAM2:";
715 #ifdef RTABMAP_ORB_SLAM2
716  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
717 #else
718  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
719 #endif
720  str = "With OKVIS:";
721 #ifdef RTABMAP_OKVIS
722  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
723 #else
724  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
725 #endif
726  str = "With MSCKF_VIO:";
727 #ifdef RTABMAP_MSCKF_VIO
728  std::cout << str << std::setw(spacing - str.size()) << "true" << std::endl;
729 #else
730  std::cout << str << std::setw(spacing - str.size()) << "false" << std::endl;
731 #endif
732  exit(0);
733  }
734  else if(strcmp(argv[i], "--nolog") == 0)
735  {
737  }
738  else if(strcmp(argv[i], "--logconsole") == 0)
739  {
741  }
742  else if(strcmp(argv[i], "--logfile") == 0)
743  {
744  ++i;
745  if(i < argc)
746  {
747  ULogger::setType(ULogger::kTypeFile, argv[i], false);
748  }
749  else
750  {
751  UERROR("\"--logfile\" argument requires following file path");
752  }
753  }
754  else if(strcmp(argv[i], "--logfilea") == 0)
755  {
756  ++i;
757  if(i < argc)
758  {
759  ULogger::setType(ULogger::kTypeFile, argv[i], true);
760  }
761  else
762  {
763  UERROR("\"--logfilea\" argument requires following file path");
764  }
765  }
766  else if(strcmp(argv[i], "--udebug") == 0)
767  {
769  }
770  else if(strcmp(argv[i], "--uinfo") == 0)
771  {
773  }
774  else if(strcmp(argv[i], "--uwarn") == 0)
775  {
777  }
778  else if(strcmp(argv[i], "--uerror") == 0)
779  {
781  }
782  else if(strcmp(argv[i], "--ulogtime") == 0)
783  {
784  ++i;
785  if(i < argc)
786  {
788  }
789  else
790  {
791  UERROR("\"--ulogtime\" argument requires a following boolean value");
792  }
793  }
794  else if(strcmp(argv[i], "--ulogwhere") == 0)
795  {
796  ++i;
797  if(i < argc)
798  {
800  }
801  else
802  {
803  UERROR("\"--ulogwhere\" argument requires a following boolean value");
804  }
805  }
806  else if(strcmp(argv[i], "--ulogthread") == 0)
807  {
808  ++i;
809  if(i < argc)
810  {
812  }
813  else
814  {
815  UERROR("\"--ulogthread\" argument requires a following boolean value");
816  }
817  }
818  else
819  {
820  checkParameters = true;
821  }
822  }
823 
824  if(checkParameters) // check for parameters
825  {
826  if(strcmp(argv[i], "--params") == 0)
827  {
828  for(rtabmap::ParametersMap::const_iterator iter=parameters.begin(); iter!=parameters.end(); ++iter)
829  {
830  bool ignore = false;
831  UASSERT(uSplit(iter->first, '/').size() == 2);
832  std::string group = uSplit(iter->first, '/').front();
833 #ifndef RTABMAP_GTSAM
834  if(group.compare("GTSAM") == 0)
835  {
836  ignore = true;
837  }
838 #endif
839 #ifndef RTABMAP_G2O
840  if(group.compare("g2o") == 0)
841  {
842  ignore = true;
843  }
844 #endif
845 #ifndef RTABMAP_FOVIS
846  if(group.compare("OdomFovis") == 0)
847  {
848  ignore = true;
849  }
850 #endif
851 #ifndef RTABMAP_VISO2
852  if(group.compare("OdomViso2") == 0)
853  {
854  ignore = true;
855  }
856 #endif
857 #ifndef RTABMAP_ORBSLAM2
858  if(group.compare("OdomORBSLAM2") == 0)
859  {
860  ignore = true;
861  }
862 #endif
863 #ifndef RTABMAP_OKVIS
864  if(group.compare("OdomOKVIS") == 0)
865  {
866  ignore = true;
867  }
868 #endif
869 #ifndef RTABMAP_LOAM
870  if(group.compare("OdomLOAM") == 0)
871  {
872  ignore = true;
873  }
874 #endif
875 #ifndef RTABMAP_MSCKF_VIO
876  if(group.compare("OdomMSCKF") == 0)
877  {
878  ignore = true;
879  }
880 #endif
881  if(!ignore)
882  {
883  std::string str = "Param: " + iter->first + " = \"" + iter->second + "\"";
884  std::cout <<
885  str <<
886  std::setw(60 - str.size()) <<
887  " [" <<
888  rtabmap::Parameters::getDescription(iter->first).c_str() <<
889  "]" <<
890  std::endl;
891  }
892  }
893  UWARN("App will now exit after showing default RTAB-Map parameters because "
894  "argument \"--params\" is detected!");
895  exit(0);
896  }
897  else
898  {
899  std::string key = uReplaceChar(argv[i], '-', "");
900  ParametersMap::const_iterator iter = parameters.find(key);
901  if(iter != parameters.end())
902  {
903  ++i;
904  if(i < argc)
905  {
906  uInsert(out, ParametersPair(iter->first, argv[i]));
907  UINFO("Parsed parameter \"%s\"=\"%s\"", iter->first.c_str(), argv[i]);
908  }
909  }
910  else
911  {
912  // backward compatibility
913  std::map<std::string, std::pair<bool, std::string> >::const_iterator jter = removedParams.find(key);
914  if(jter!=removedParams.end())
915  {
916  if(jter->second.first)
917  {
918  ++i;
919  if(i < argc)
920  {
921  std::string value = argv[i];
922  if(!value.empty())
923  {
924  value = uReplaceChar(value, ',', ' '); // for table
925  key = jter->second.second;
926  UWARN("Parameter migration from \"%s\" to \"%s\" (value=%s).",
927  jter->first.c_str(), jter->second.second.c_str(), value.c_str());
928  uInsert(out, ParametersPair(key, value));
929  }
930  }
931  else
932  {
933  UERROR("Value missing for argument \"%s\"", argv[i-1]);
934  }
935  }
936  else if(jter->second.second.empty())
937  {
938  UERROR("Parameter \"%s\" doesn't exist anymore.", jter->first.c_str());
939  }
940  else
941  {
942  UERROR("Parameter \"%s\" doesn't exist anymore, check this similar parameter \"%s\".", jter->first.c_str(), jter->second.second.c_str());
943  }
944  }
945  }
946  }
947  }
948  }
949  return out;
950 }
951 
952 
953 void Parameters::readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly)
954 {
955  CSimpleIniA ini;
956  ini.LoadFile(configFile.c_str());
957  const CSimpleIniA::TKeyVal * keyValMap = ini.GetSection("Core");
958  if(keyValMap)
959  {
960  for(CSimpleIniA::TKeyVal::const_iterator iter=keyValMap->begin(); iter!=keyValMap->end(); ++iter)
961  {
962  std::string key = (*iter).first.pItem;
963  if(key.compare("Version") == 0)
964  {
965  // Compare version in ini with the current RTAB-Map version
966  std::vector<std::string> version = uListToVector(uSplit((*iter).second, '.'));
967  if(version.size() == 3)
968  {
969  if(!RTABMAP_VERSION_COMPARE(std::atoi(version[0].c_str()), std::atoi(version[1].c_str()), std::atoi(version[2].c_str())))
970  {
971  if(configFile.find(".rtabmap") != std::string::npos)
972  {
973  UWARN("Version in the config file \"%s\" is more recent (\"%s\") than "
974  "current RTAB-Map version used (\"%s\"). The config file will be upgraded "
975  "to new version.",
976  configFile.c_str(),
977  (*iter).second,
978  RTABMAP_VERSION);
979  }
980  else
981  {
982  UERROR("Version in the config file \"%s\" is more recent (\"%s\") than "
983  "current RTAB-Map version used (\"%s\"). New parameters (if there are some) will "
984  "be ignored.",
985  configFile.c_str(),
986  (*iter).second,
987  RTABMAP_VERSION);
988  }
989  }
990  }
991  }
992  else
993  {
994  key = uReplaceChar(key, '\\', '/'); // Ini files use \ by default for separators, so replace them
995 
996  // look for old parameter name
997  std::map<std::string, std::pair<bool, std::string> >::const_iterator oldIter = Parameters::getRemovedParameters().find(key);
998  if(oldIter!=Parameters::getRemovedParameters().end())
999  {
1000  if(oldIter->second.first)
1001  {
1002  if(parameters.find(oldIter->second.second) == parameters.end())
1003  {
1004  key = oldIter->second.second;
1005  UINFO("Parameter migration from \"%s\" to \"%s\" (value=%s, default=%s).",
1006  oldIter->first.c_str(), oldIter->second.second.c_str(), iter->second, Parameters::getDefaultParameters().at(oldIter->second.second).c_str());
1007  }
1008  }
1009  else if(oldIter->second.second.empty())
1010  {
1011  UWARN("Parameter \"%s\" doesn't exist anymore.",
1012  oldIter->first.c_str());
1013  }
1014  else if(parameters.find(oldIter->second.second) == parameters.end())
1015  {
1016  UWARN("Parameter \"%s\" (value=%s) doesn't exist anymore, you may want to use this similar parameter \"%s (default=%s): %s\".",
1017  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());
1018  }
1019 
1020  }
1021 
1023  {
1024  if(!modifiedOnly || std::string(iter->second).compare(Parameters::getDefaultParameters().find(key)->second) != 0)
1025  {
1026  uInsert(parameters, ParametersPair(key, iter->second));
1027  }
1028  }
1029  }
1030  }
1031  }
1032  else
1033  {
1034  ULOGGER_WARN("Section \"Core\" in %s doesn't exist... "
1035  "Ignore this warning if the ini file does not exist yet. "
1036  "The ini file will be automatically created when rtabmap will close.", configFile.c_str());
1037  }
1038 }
1039 
1040 void Parameters::writeINI(const std::string & configFile, const ParametersMap & parameters)
1041 {
1042  CSimpleIniA ini;
1043  ini.LoadFile(configFile.c_str());
1044 
1045  // Save current version
1046  ini.SetValue("Core", "Version", RTABMAP_VERSION, NULL, true);
1047 
1048  for(ParametersMap::const_iterator i=parameters.begin(); i!=parameters.end(); ++i)
1049  {
1050  std::string key = (*i).first;
1051  key = uReplaceChar(key, '/', '\\'); // Ini files use \ by default for separators, so replace the /
1052 
1053  std::string value = (*i).second.c_str();
1054  value = uReplaceChar(value, '\\', '/'); // use always slash for values
1055 
1056  ini.SetValue("Core", key.c_str(), value.c_str(), NULL, true);
1057  }
1058 
1059  ini.SaveFile(configFile.c_str());
1060 }
1061 
1062 }
static bool isFeatureParameter(const std::string &param)
Definition: Parameters.cpp:150
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:209
#define NULL
static bool parse(const ParametersMap &parameters, const std::string &key, bool &value)
Definition: Parameters.cpp:446
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters()
Definition: Parameters.cpp:224
static bool makeDir(const std::string &dirPath)
Definition: UDirectory.cpp:333
static std::string getDescription(const std::string &paramKey)
Definition: Parameters.cpp:431
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:518
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:42
bool UTILITE_EXP uStr2Bool(const char *str)
static std::string getVersion()
Definition: Parameters.cpp:74
static std::string separator()
Definition: UDirectory.cpp:391
static ParametersMap parseArguments(int argc, char *argv[], bool onlyParameters=false)
Definition: Parameters.cpp:543
float UTILITE_EXP uStr2Float(const std::string &str)
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
static ParametersMap descriptions_
Definition: Parameters.h:756
static void writeINI(const std::string &configFile, const ParametersMap &parameters)
static ParametersMap backwardCompatibilityMap_
Definition: Parameters.h:760
Some conversion functions.
static ParametersMap getDefaultOdometryParameters(bool stereo=false, bool vis=true, bool icp=false)
Definition: Parameters.cpp:164
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
#define UASSERT(condition)
Wrappers of STL for convenient functions.
static std::string serialize(const ParametersMap &parameters)
Definition: Parameters.cpp:85
static void setPrintTime(bool printTime)
Definition: ULogger.h:273
description
static Parameters instance_
Definition: Parameters.h:757
static const ParametersMap & getBackwardCompatibilityMap()
Definition: Parameters.cpp:396
static ParametersMap deserialize(const std::string &parameters)
Definition: Parameters.cpp:101
#define UASSERT_MSG(condition, msg_str)
Definition: ULogger.h:67
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
static ParametersMap parameters_
Definition: Parameters.h:754
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 std::string getType(const std::string &paramKey)
Definition: Parameters.cpp:416
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:695
#define UDEBUG(...)
virtual ~Parameters()
Definition: Parameters.cpp:54
#define UERROR(...)
#define ULOGGER_WARN(...)
Definition: ULogger.h:55
ULogger class and convenient macros.
static ParametersMap parametersType_
Definition: Parameters.h:755
#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:80
static void readINI(const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
Definition: Parameters.cpp:953
std::string UTILITE_EXP uFormat(const char *fmt,...)
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
Definition: Parameters.h:759
static std::string createDefaultWorkingDirectory()
Definition: Parameters.cpp:58
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 Wed Jun 5 2019 22:41:32