Parameters.h
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 
28 #ifndef PARAMETERS_H_
29 #define PARAMETERS_H_
30 
31 // default parameters
32 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
33 #include "rtabmap/core/Version.h" // DLL export/import defines
35 #include <string>
36 #include <map>
37 
38 namespace rtabmap
39 {
40 
41 typedef std::map<std::string, std::string> ParametersMap; // Key, value
42 typedef std::pair<std::string, std::string> ParametersPair;
43 
62 #define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION) \
63  public: \
64  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
65  static TYPE default##PREFIX##NAME() {return DEFAULT_VALUE;} \
66  static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
67  private: \
68  class Dummy##PREFIX##NAME { \
69  public: \
70  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, #DEFAULT_VALUE)); \
71  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
72  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
73  }; \
74  Dummy##PREFIX##NAME dummy##PREFIX##NAME;
75 // end define PARAM
76 
96 #define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION) \
97  public: \
98  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
99  static std::string default##PREFIX##NAME() {return DEFAULT_VALUE;} \
100  static std::string type##PREFIX##NAME() {return std::string("string");} \
101  private: \
102  class Dummy##PREFIX##NAME { \
103  public: \
104  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, DEFAULT_VALUE)); \
105  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, "string")); \
106  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
107  }; \
108  Dummy##PREFIX##NAME dummy##PREFIX##NAME;
109 // end define PARAM
110 
129 #define RTABMAP_PARAM_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
130  public: \
131  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
132  static TYPE default##PREFIX##NAME() {return COND?DEFAULT_VALUE1:DEFAULT_VALUE2;} \
133  static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
134  private: \
135  class Dummy##PREFIX##NAME { \
136  public: \
137  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, COND?#DEFAULT_VALUE1:#DEFAULT_VALUE2)); \
138  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
139  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
140  }; \
141  Dummy##PREFIX##NAME dummy##PREFIX##NAME;
142 // end define PARAM
143 
169 {
170  // Rtabmap parameters
171  RTABMAP_PARAM(Rtabmap, PublishStats, bool, true, "Publishing statistics.");
172  RTABMAP_PARAM(Rtabmap, PublishLastSignature, bool, true, "Publishing last signature.");
173  RTABMAP_PARAM(Rtabmap, PublishPdf, bool, true, "Publishing pdf.");
174  RTABMAP_PARAM(Rtabmap, PublishLikelihood, bool, true, "Publishing likelihood.");
175  RTABMAP_PARAM(Rtabmap, PublishRAMUsage, bool, false, "Publishing RAM usage in statistics (may add a small overhead to get info from the system).");
176  RTABMAP_PARAM(Rtabmap, ComputeRMSE, bool, true, "Compute root mean square error (RMSE) and publish it in statistics, if ground truth is provided.");
177  RTABMAP_PARAM(Rtabmap, SaveWMState, bool, false, "Save working memory state after each update in statistics.");
178  RTABMAP_PARAM(Rtabmap, TimeThr, float, 0, "Maximum time allowed for map update (ms) (0 means infinity). When map update time exceeds this fixed time threshold, some nodes in Working Memory (WM) are transferred to Long-Term Memory to limit the size of the WM and decrease the update time.");
179  RTABMAP_PARAM(Rtabmap, MemoryThr, int, 0, uFormat("Maximum nodes in the Working Memory (0 means infinity). Similar to \"%s\", when the number of nodes in Working Memory (WM) exceeds this treshold, some nodes are transferred to Long-Term Memory to keep WM size fixed.", kRtabmapTimeThr().c_str()));
180  RTABMAP_PARAM(Rtabmap, DetectionRate, float, 1, "Detection rate (Hz). RTAB-Map will filter input images to satisfy this rate.");
181  RTABMAP_PARAM(Rtabmap, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).");
182  RTABMAP_PARAM(Rtabmap, CreateIntermediateNodes, bool, false, uFormat("Create intermediate nodes between loop closure detection. Only used when %s>0.", kRtabmapDetectionRate().c_str()));
183  RTABMAP_PARAM_STR(Rtabmap, WorkingDirectory, "", "Working directory.");
184  RTABMAP_PARAM(Rtabmap, MaxRetrieved, unsigned int, 2, "Maximum locations retrieved at the same time from LTM.");
185  RTABMAP_PARAM(Rtabmap, StatisticLogsBufferedInRAM, bool, true, "Statistic logs buffered in RAM instead of written to hard drive after each iteration.");
186  RTABMAP_PARAM(Rtabmap, StatisticLogged, bool, false, "Logging enabled.");
187  RTABMAP_PARAM(Rtabmap, StatisticLoggedHeaders, bool, true, "Add column header description to log files.");
188  RTABMAP_PARAM(Rtabmap, StartNewMapOnLoopClosure, bool, false, "Start a new map only if there is a global loop closure with a previous map.");
189  RTABMAP_PARAM(Rtabmap, StartNewMapOnGoodSignature, bool, false, uFormat("Start a new map only if the first signature is not bad (i.e., has enough features, see %s).", kKpBadSignRatio().c_str()));
190  RTABMAP_PARAM(Rtabmap, ImagesAlreadyRectified, bool, true, "Images are already rectified. By default RTAB-Map assumes that received images are rectified. If they are not, they can be rectified by RTAB-Map if this parameter is false.");
191  RTABMAP_PARAM(Rtabmap, RectifyOnlyFeatures, bool, false, uFormat("If \"%s\" is false and this parameter is true, the whole RGB image will not be rectified, only the features. Warning: As projection of RGB-D image to point cloud is assuming that images are rectified, the generated point cloud map will have wrong colors if this parameter is true.", kRtabmapImagesAlreadyRectified().c_str()));
192 
193  // Hypotheses selection
194  RTABMAP_PARAM(Rtabmap, LoopThr, float, 0.11, "Loop closing threshold.");
195  RTABMAP_PARAM(Rtabmap, LoopRatio, float, 0, "The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.");
196 
197  // Memory
198  RTABMAP_PARAM(Mem, RehearsalSimilarity, float, 0.6, "Rehearsal similarity.");
199  RTABMAP_PARAM(Mem, ImageKept, bool, false, "Keep raw images in RAM.");
200  RTABMAP_PARAM(Mem, BinDataKept, bool, true, "Keep binary data in db.");
201  RTABMAP_PARAM(Mem, RawDescriptorsKept, bool, true, "Raw descriptors kept in memory.");
202  RTABMAP_PARAM(Mem, MapLabelsAdded, bool, true, "Create map labels. The first node of a map will be labelled as \"map#\" where # is the map ID.");
203  RTABMAP_PARAM(Mem, SaveDepth16Format, bool, false, "Save depth image into 16 bits format to reduce memory used. Warning: values over ~65 meters are ignored (maximum 65535 millimeters).");
204  RTABMAP_PARAM(Mem, NotLinkedNodesKept, bool, true, "Keep not linked nodes in db (rehearsed nodes and deleted nodes).");
205  RTABMAP_PARAM(Mem, IntermediateNodeDataKept, bool, false, "Keep intermediate node data in db.");
206  RTABMAP_PARAM(Mem, STMSize, unsigned int, 10, "Short-term memory size.");
207  RTABMAP_PARAM(Mem, IncrementalMemory, bool, true, "SLAM mode, otherwise it is Localization mode.");
208  RTABMAP_PARAM(Mem, ReduceGraph, bool, false, "Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set).");
209  RTABMAP_PARAM(Mem, RecentWmRatio, float, 0.2, "Ratio of locations after the last loop closure in WM that cannot be transferred.");
210  RTABMAP_PARAM(Mem, TransferSortingByWeightId, bool, false, "On transfer, signatures are sorted by weight->ID only (i.e. the oldest of the lowest weighted signatures are transferred first). If false, the signatures are sorted by weight->Age->ID (i.e. the oldest inserted in WM of the lowest weighted signatures are transferred first). Note that retrieval updates the age, not the ID.");
211  RTABMAP_PARAM(Mem, RehearsalIdUpdatedToNewOne, bool, false, "On merge, update to new id. When false, no copy.");
212  RTABMAP_PARAM(Mem, RehearsalWeightIgnoredWhileMoving, bool, false, "When the robot is moving, weights are not updated on rehearsal.");
213  RTABMAP_PARAM(Mem, GenerateIds, bool, true, "True=Generate location IDs, False=use input image IDs.");
214  RTABMAP_PARAM(Mem, BadSignaturesIgnored, bool, false, "Bad signatures are ignored.");
215  RTABMAP_PARAM(Mem, InitWMWithAllNodes, bool, false, "Initialize the Working Memory with all nodes in Long-Term Memory. When false, it is initialized with nodes of the previous session.");
216  RTABMAP_PARAM(Mem, DepthAsMask, bool, true, "Use depth image as mask when extracting features for vocabulary.");
217  RTABMAP_PARAM(Mem, ImagePreDecimation, int, 1, "Image decimation (>=1) before features extraction. Negative decimation is done from RGB size instead of depth size (if depth is smaller than RGB, it may be interpolated depending of the decimation value).");
218  RTABMAP_PARAM(Mem, ImagePostDecimation, int, 1, "Image decimation (>=1) of saved data in created signatures (after features extraction). Decimation is done from the original image. Negative decimation is done from RGB size instead of depth size (if depth is smaller than RGB, it may be interpolated depending of the decimation value).");
219  RTABMAP_PARAM(Mem, CompressionParallelized, bool, true, "Compression of sensor data is multi-threaded.");
220  RTABMAP_PARAM(Mem, LaserScanDownsampleStepSize, int, 1, "If > 1, downsample the laser scans when creating a signature.");
221  RTABMAP_PARAM(Mem, LaserScanVoxelSize, float, 0.0, uFormat("If > 0 m, voxel filtering is done on laser scans when creating a signature. If the laser scan had normals, they will be removed. To recompute the normals, make sure to use \"%s\" or \"%s\" parameters.", kMemLaserScanNormalK().c_str(), kMemLaserScanNormalRadius().c_str()).c_str());
222  RTABMAP_PARAM(Mem, LaserScanNormalK, int, 0, "If > 0 and laser scans don't have normals, normals will be computed with K search neighbors when creating a signature.");
223  RTABMAP_PARAM(Mem, LaserScanNormalRadius, float, 0.0, "If > 0 m and laser scans don't have normals, normals will be computed with radius search neighbors when creating a signature.");
224  RTABMAP_PARAM(Mem, UseOdomFeatures, bool, true, "Use odometry features.");
225  RTABMAP_PARAM(Mem, CovOffDiagIgnored, bool, true, "Ignore off diagonal values of the covariance matrix.");
226 
227  // KeypointMemory (Keypoint-based)
228  RTABMAP_PARAM(Kp, NNStrategy, int, 1, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
229  RTABMAP_PARAM(Kp, IncrementalDictionary, bool, true, "");
230  RTABMAP_PARAM(Kp, IncrementalFlann, bool, true, uFormat("When using FLANN based strategy, add/remove points to its index without always rebuilding the index (the index is built only when the dictionary increases of the factor \"%s\" in size).", kKpFlannRebalancingFactor().c_str()));
231  RTABMAP_PARAM(Kp, FlannRebalancingFactor, float, 2.0, uFormat("Factor used when rebuilding the incremental FLANN index (see \"%s\"). Set <=1 to disable.", kKpIncrementalFlann().c_str()));
232  RTABMAP_PARAM(Kp, MaxDepth, float, 0, "Filter extracted keypoints by depth (0=inf).");
233  RTABMAP_PARAM(Kp, MinDepth, float, 0, "Filter extracted keypoints by depth.");
234  RTABMAP_PARAM(Kp, MaxFeatures, int, 500, "Maximum features extracted from the images (0 means not bounded, <0 means no extraction).");
235  RTABMAP_PARAM(Kp, BadSignRatio, float, 0.5, "Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).");
236  RTABMAP_PARAM(Kp, NndrRatio, float, 0.8, "NNDR ratio (A matching pair is detected, if its distance is closer than X times the distance of the second nearest neighbor.)");
237 #ifndef RTABMAP_NONFREE
238 #ifdef RTABMAP_OPENCV3
239  // OpenCV 3 without xFeatures2D module doesn't have BRIEF
240  RTABMAP_PARAM(Kp, DetectorStrategy, int, 8, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
241 #else
242  RTABMAP_PARAM(Kp, DetectorStrategy, int, 6, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
243 #endif
244 #else
245  RTABMAP_PARAM(Kp, DetectorStrategy, int, 6, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
246 #endif
247  RTABMAP_PARAM(Kp, TfIdfLikelihoodUsed, bool, true, "Use of the td-idf strategy to compute the likelihood.");
248  RTABMAP_PARAM(Kp, Parallelized, bool, true, "If the dictionary update and signature creation were parallelized.");
249  RTABMAP_PARAM_STR(Kp, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
250  RTABMAP_PARAM_STR(Kp, DictionaryPath, "", "Path of the pre-computed dictionary");
251  RTABMAP_PARAM(Kp, NewWordsComparedTogether, bool, true, "When adding new words to dictionary, they are compared also with each other (to detect same words in the same signature).");
252  RTABMAP_PARAM(Kp, SubPixWinSize, int, 3, "See cv::cornerSubPix().");
253  RTABMAP_PARAM(Kp, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.");
254  RTABMAP_PARAM(Kp, SubPixEps, double, 0.02, "See cv::cornerSubPix().");
255  RTABMAP_PARAM(Kp, GridRows, int, 1, uFormat("Number of rows of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kKpMaxFeatures().c_str()));
256  RTABMAP_PARAM(Kp, GridCols, int, 1, uFormat("Number of columns of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kKpMaxFeatures().c_str()));
257 
258  //Database
259  RTABMAP_PARAM(DbSqlite3, InMemory, bool, false, "Using database in the memory instead of a file on the hard disk.");
260  RTABMAP_PARAM(DbSqlite3, CacheSize, unsigned int, 10000, "Sqlite cache size (default is 2000).");
261  RTABMAP_PARAM(DbSqlite3, JournalMode, int, 3, "0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")");
262  RTABMAP_PARAM(DbSqlite3, Synchronous, int, 0, "0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")");
263  RTABMAP_PARAM(DbSqlite3, TempStore, int, 2, "0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")");
264 
265  // Keypoints descriptors/detectors
266  RTABMAP_PARAM(SURF, Extended, bool, false, "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
267  RTABMAP_PARAM(SURF, HessianThreshold, float, 500, "Threshold for hessian keypoint detector used in SURF.");
268  RTABMAP_PARAM(SURF, Octaves, int, 4, "Number of pyramid octaves the keypoint detector will use.");
269  RTABMAP_PARAM(SURF, OctaveLayers, int, 2, "Number of octave layers within each octave.");
270  RTABMAP_PARAM(SURF, Upright, bool, false, "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
271  RTABMAP_PARAM(SURF, GpuVersion, bool, false, "GPU-SURF: Use GPU version of SURF. This option is enabled only if OpenCV is built with CUDA and GPUs are detected.");
272  RTABMAP_PARAM(SURF, GpuKeypointsRatio, float, 0.01, "Used with SURF GPU.");
273 
274  RTABMAP_PARAM(SIFT, NFeatures, int, 0, "The number of best features to retain. The features are ranked by their scores (measured in SIFT algorithm as the local contrast).");
275  RTABMAP_PARAM(SIFT, NOctaveLayers, int, 3, "The number of layers in each octave. 3 is the value used in D. Lowe paper. The number of octaves is computed automatically from the image resolution.");
276  RTABMAP_PARAM(SIFT, ContrastThreshold, double, 0.04, "The contrast threshold used to filter out weak features in semi-uniform (low-contrast) regions. The larger the threshold, the less features are produced by the detector.");
277  RTABMAP_PARAM(SIFT, EdgeThreshold, double, 10, "The threshold used to filter out edge-like features. Note that the its meaning is different from the contrastThreshold, i.e. the larger the edgeThreshold, the less features are filtered out (more features are retained).");
278  RTABMAP_PARAM(SIFT, Sigma, double, 1.6, "The sigma of the Gaussian applied to the input image at the octave #0. If your image is captured with a weak camera with soft lenses, you might want to reduce the number.");
279 
280  RTABMAP_PARAM(BRIEF, Bytes, int, 32, "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
281 
282  RTABMAP_PARAM(FAST, Threshold, int, 20, "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
283  RTABMAP_PARAM(FAST, NonmaxSuppression, bool, true, "If true, non-maximum suppression is applied to detected corners (keypoints).");
284  RTABMAP_PARAM(FAST, Gpu, bool, false, "GPU-FAST: Use GPU version of FAST. This option is enabled only if OpenCV is built with CUDA and GPUs are detected.");
285  RTABMAP_PARAM(FAST, GpuKeypointsRatio, double, 0.05, "Used with FAST GPU.");
286  RTABMAP_PARAM(FAST, MinThreshold, int, 7, "Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
287  RTABMAP_PARAM(FAST, MaxThreshold, int, 200, "Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
288  RTABMAP_PARAM(FAST, GridRows, int, 0, "Grid rows (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell.");
289  RTABMAP_PARAM(FAST, GridCols, int, 0, "Grid cols (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell.");
290 
291  RTABMAP_PARAM(GFTT, QualityLevel, double, 0.001, "");
292  RTABMAP_PARAM(GFTT, MinDistance, double, 3, "");
293  RTABMAP_PARAM(GFTT, BlockSize, int, 3, "");
294  RTABMAP_PARAM(GFTT, UseHarrisDetector, bool, false, "");
295  RTABMAP_PARAM(GFTT, K, double, 0.04, "");
296 
297  RTABMAP_PARAM(ORB, ScaleFactor, float, 1.2, "Pyramid decimation ratio, greater than 1. scaleFactor==2 means the classical pyramid, where each next level has 4x less pixels than the previous, but such a big scale factor will degrade feature matching scores dramatically. On the other hand, too close to 1 scale factor will mean that to cover certain scale range you will need more pyramid levels and so the speed will suffer.");
298  RTABMAP_PARAM(ORB, NLevels, int, 8, "The number of pyramid levels. The smallest level will have linear size equal to input_image_linear_size/pow(scaleFactor, nlevels).");
299  RTABMAP_PARAM(ORB, EdgeThreshold, int, 31, "This is size of the border where the features are not detected. It should roughly match the patchSize parameter.");
300  RTABMAP_PARAM(ORB, FirstLevel, int, 0, "It should be 0 in the current implementation.");
301  RTABMAP_PARAM(ORB, WTA_K, int, 2, "The number of points that produce each element of the oriented BRIEF descriptor. The default value 2 means the BRIEF where we take a random point pair and compare their brightnesses, so we get 0/1 response. Other possible values are 3 and 4. For example, 3 means that we take 3 random points (of course, those point coordinates are random, but they are generated from the pre-defined seed, so each element of BRIEF descriptor is computed deterministically from the pixel rectangle), find point of maximum brightness and output index of the winner (0, 1 or 2). Such output will occupy 2 bits, and therefore it will need a special variant of Hamming distance, denoted as NORM_HAMMING2 (2 bits per bin). When WTA_K=4, we take 4 random points to compute each bin (that will also occupy 2 bits with possible values 0, 1, 2 or 3).");
302  RTABMAP_PARAM(ORB, ScoreType, int, 0, "The default HARRIS_SCORE=0 means that Harris algorithm is used to rank features (the score is written to KeyPoint::score and is used to retain best nfeatures features); FAST_SCORE=1 is alternative value of the parameter that produces slightly less stable keypoints, but it is a little faster to compute.");
303  RTABMAP_PARAM(ORB, PatchSize, int, 31, "size of the patch used by the oriented BRIEF descriptor. Of course, on smaller pyramid layers the perceived image area covered by a feature will be larger.");
304  RTABMAP_PARAM(ORB, Gpu, bool, false, "GPU-ORB: Use GPU version of ORB. This option is enabled only if OpenCV is built with CUDA and GPUs are detected.");
305 
306  RTABMAP_PARAM(FREAK, OrientationNormalized, bool, true, "Enable orientation normalization.");
307  RTABMAP_PARAM(FREAK, ScaleNormalized, bool, true, "Enable scale normalization.");
308  RTABMAP_PARAM(FREAK, PatternScale, float, 22, "Scaling of the description pattern.");
309  RTABMAP_PARAM(FREAK, NOctaves, int, 4, "Number of octaves covered by the detected keypoints.");
310 
311  RTABMAP_PARAM(BRISK, Thresh, int, 30, "FAST/AGAST detection threshold score.");
312  RTABMAP_PARAM(BRISK, Octaves, int, 3, "Detection octaves. Use 0 to do single scale.");
313  RTABMAP_PARAM(BRISK, PatternScale, float, 1,"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
314 
315  RTABMAP_PARAM(KAZE, Extended, bool, false, "Set to enable extraction of extended (128-byte) descriptor.");
316  RTABMAP_PARAM(KAZE, Upright, bool, false, "Set to enable use of upright descriptors (non rotation-invariant).");
317  RTABMAP_PARAM(KAZE, Threshold, float, 0.001, "Detector response threshold to accept point.");
318  RTABMAP_PARAM(KAZE, NOctaves, int, 4, "Maximum octave evolution of the image.");
319  RTABMAP_PARAM(KAZE, NOctaveLayers, int, 4, "Default number of sublevels per scale level.");
320  RTABMAP_PARAM(KAZE, Diffusivity, int, 1, "Diffusivity type: 0=DIFF_PM_G1, 1=DIFF_PM_G2, 2=DIFF_WEICKERT or 3=DIFF_CHARBONNIER.");
321 
322  // BayesFilter
323  RTABMAP_PARAM(Bayes, VirtualPlacePriorThr, float, 0.9, "Virtual place prior");
324  RTABMAP_PARAM_STR(Bayes, PredictionLC, "0.1 0.36 0.30 0.16 0.062 0.0151 0.00255 0.000324 2.5e-05 1.3e-06 4.8e-08 1.2e-09 1.9e-11 2.2e-13 1.7e-15 8.5e-18 2.9e-20 6.9e-23", "Prediction of loop closures (Gaussian-like, here with sigma=1.6) - Format: {VirtualPlaceProb, LoopClosureProb, NeighborLvl1, NeighborLvl2, ...}.");
325  RTABMAP_PARAM(Bayes, FullPredictionUpdate, bool, false, "Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).");
326 
327  // Verify hypotheses
328  RTABMAP_PARAM(VhEp, Enabled, bool, false, uFormat("Verify visual loop closure hypothesis by computing a fundamental matrix. This is done prior to transformation computation when %s is enabled.", kRGBDEnabled().c_str()));
329  RTABMAP_PARAM(VhEp, MatchCountMin, int, 8, "Minimum of matching visual words pairs to accept the loop hypothesis.");
330  RTABMAP_PARAM(VhEp, RansacParam1, float, 3, "Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier.");
331  RTABMAP_PARAM(VhEp, RansacParam2, float, 0.99, "Fundamental matrix (see cvFindFundamentalMat()): Performance of RANSAC.");
332 
333  // RGB-D SLAM
334  RTABMAP_PARAM(RGBD, Enabled, bool, true, "");
335  RTABMAP_PARAM(RGBD, LinearUpdate, float, 0.1, "Minimum linear displacement (m) to update the map. Rehearsal is done prior to this, so weights are still updated.");
336  RTABMAP_PARAM(RGBD, AngularUpdate, float, 0.1, "Minimum angular displacement (rad) to update the map. Rehearsal is done prior to this, so weights are still updated.");
337  RTABMAP_PARAM(RGBD, LinearSpeedUpdate, float, 0.0, "Maximum linear speed (m/s) to update the map (0 means not limit).");
338  RTABMAP_PARAM(RGBD, AngularSpeedUpdate, float, 0.0, "Maximum angular speed (rad/s) to update the map (0 means not limit).");
339  RTABMAP_PARAM(RGBD, NewMapOdomChangeDistance, float, 0, "A new map is created if a change of odometry translation greater than X m is detected (0 m = disabled).");
340  RTABMAP_PARAM(RGBD, OptimizeFromGraphEnd, bool, false, "Optimize graph from the newest node. If false, the graph is optimized from the oldest node of the current graph (this adds an overhead computation to detect to oldest node of the current graph, but it can be useful to preserve the map referential from the oldest node). Warning when set to false: when some nodes are transferred, the first referential of the local map may change, resulting in momentary changes in robot/map position (which are annoying in teleoperation).");
341  RTABMAP_PARAM(RGBD, OptimizeMaxError, float, 1.0, uFormat("Reject loop closures if optimization error ratio is greater than this value (0=disabled). Ratio is computed as absolute error over standard deviation of each link. This will help to detect when a wrong loop closure is added to the graph. Not compatible with \"%s\" if enabled.", kOptimizerRobust().c_str()));
342  RTABMAP_PARAM(RGBD, SavedLocalizationIgnored, bool, false, "Ignore last saved localization pose from previous session. If true, RTAB-Map won't assume it is restarting from the same place than where it shut down previously.");
343  RTABMAP_PARAM(RGBD, GoalReachedRadius, float, 0.5, "Goal reached radius (m).");
344  RTABMAP_PARAM(RGBD, PlanStuckIterations, int, 0, "Mark the current goal node on the path as unreachable if it is not updated after X iterations (0=disabled). If all upcoming nodes on the path are unreachabled, the plan fails.");
345  RTABMAP_PARAM(RGBD, PlanLinearVelocity, float, 0, "Linear velocity (m/sec) used to compute path weights.");
346  RTABMAP_PARAM(RGBD, PlanAngularVelocity, float, 0, "Angular velocity (rad/sec) used to compute path weights.");
347  RTABMAP_PARAM(RGBD, GoalsSavedInUserData, bool, false, "When a goal is received and processed with success, it is saved in user data of the location with this format: \"GOAL:#\".");
348  RTABMAP_PARAM(RGBD, MaxLocalRetrieved, unsigned int, 2, "Maximum local locations retrieved (0=disabled) near the current pose in the local map or on the current planned path (those on the planned path have priority).");
349  RTABMAP_PARAM(RGBD, LocalRadius, float, 10, "Local radius (m) for nodes selection in the local map. This parameter is used in some approaches about the local map management.");
350  RTABMAP_PARAM(RGBD, LocalImmunizationRatio, float, 0.25, "Ratio of working memory for which local nodes are immunized from transfer.");
351  RTABMAP_PARAM(RGBD, ScanMatchingIdsSavedInLinks, bool, true, "Save scan matching IDs in link's user data.");
352  RTABMAP_PARAM(RGBD, NeighborLinkRefining, bool, false, uFormat("When a new node is added to the graph, the transformation of its neighbor link to the previous node is refined using registration approach selected (%s).", kRegStrategy().c_str()));
353  RTABMAP_PARAM(RGBD, LoopClosureReextractFeatures, bool, false, "Extract features even if there are some already in the nodes.");
354  RTABMAP_PARAM(RGBD, LocalBundleOnLoopClosure, bool, false, "Do local bundle adjustment with neighborhood of the loop closure.");
355  RTABMAP_PARAM(RGBD, CreateOccupancyGrid, bool, false, "Create local occupancy grid maps. See \"Grid\" group for parameters.");
356 
357  // Local/Proximity loop closure detection
358  RTABMAP_PARAM(RGBD, ProximityByTime, bool, false, "Detection over all locations in STM.");
359  RTABMAP_PARAM(RGBD, ProximityBySpace, bool, true, "Detection over locations (in Working Memory) near in space.");
360  RTABMAP_PARAM(RGBD, ProximityMaxGraphDepth, int, 50, "Maximum depth from the current/last loop closure location and the local loop closure hypotheses. Set 0 to ignore.");
361  RTABMAP_PARAM(RGBD, ProximityMaxPaths, int, 3, "Maximum paths compared (from the most recent) for proximity detection by space. 0 means no limit.");
362  RTABMAP_PARAM(RGBD, ProximityPathFilteringRadius, float, 1, "Path filtering radius to reduce the number of nodes to compare in a path. A path should also be inside that radius to be considered for proximity detection.");
363  RTABMAP_PARAM(RGBD, ProximityPathMaxNeighbors, int, 0, "Maximum neighbor nodes compared on each path. Set to 0 to disable merging the laser scans.");
364  RTABMAP_PARAM(RGBD, ProximityPathRawPosesUsed, bool, true, "When comparing to a local path, merge the scan using the odometry poses (with neighbor link optimizations) instead of the ones in the optimized local graph.");
365  RTABMAP_PARAM(RGBD, ProximityAngle, float, 45, "Maximum angle (degrees) for visual proximity detection.");
366 
367  // Graph optimization
368 #ifdef RTABMAP_GTSAM
369  RTABMAP_PARAM(Optimizer, Strategy, int, 2, "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
370  RTABMAP_PARAM(Optimizer, Iterations, int, 20, "Optimization iterations.");
371  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.00001, "Stop optimizing when the error improvement is less than this value.");
372 #else
373 #ifdef RTABMAP_G2O
374  RTABMAP_PARAM(Optimizer, Strategy, int, 1, "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
375  RTABMAP_PARAM(Optimizer, Iterations, int, 20, "Optimization iterations.");
376  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.0, "Stop optimizing when the error improvement is less than this value.");
377 #else
378  RTABMAP_PARAM(Optimizer, Strategy, int, 0, "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
379  RTABMAP_PARAM(Optimizer, Iterations, int, 100, "Optimization iterations.");
380  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.00001, "Stop optimizing when the error improvement is less than this value.");
381 #endif
382 #endif
383  RTABMAP_PARAM(Optimizer, VarianceIgnored, bool, false, "Ignore constraints' variance. If checked, identity information matrix is used for each constraint. Otherwise, an information matrix is generated from the variance saved in the links.");
384  RTABMAP_PARAM(Optimizer, Robust, bool, false, uFormat("Robust graph optimization using Vertigo (only work for g2o and GTSAM optimization strategies). Not compatible with \"%s\" if enabled.", kRGBDOptimizeMaxError().c_str()));
385  RTABMAP_PARAM(Optimizer, PriorsIgnored, bool, true, "Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this.");
386 
387 #ifdef RTABMAP_ORB_SLAM2
388  RTABMAP_PARAM(g2o, Solver, int, 3, "0=csparse 1=pcg 2=cholmod 3=Eigen");
389 #else
390  RTABMAP_PARAM(g2o, Solver, int, 0, "0=csparse 1=pcg 2=cholmod 3=Eigen");
391 #endif
392  RTABMAP_PARAM(g2o, Optimizer, int, 0, "0=Levenberg 1=GaussNewton");
393  RTABMAP_PARAM(g2o, PixelVariance, double, 1.0, "Pixel variance used for bundle adjustment.");
394  RTABMAP_PARAM(g2o, RobustKernelDelta, double, 8, "Robust kernel delta used for bundle adjustment (0 means don't use robust kernel). Observations with chi2 over this threshold will be ignored in the second optimization pass.");
395  RTABMAP_PARAM(g2o, Baseline, double, 0.075, "When doing bundle adjustment with RGB-D data, we can set a fake baseline (m) to do stereo bundle adjustment (if 0, mono bundle adjustment is done). For stereo data, the baseline in the calibration is used directly.");
396 
397  RTABMAP_PARAM(GTSAM, Optimizer, int, 1, "0=Levenberg 1=GaussNewton 2=Dogleg");
398 
399  // Odometry
400  RTABMAP_PARAM(Odom, Strategy, int, 0, "0=Frame-to-Map (F2M) 1=Frame-to-Frame (F2F) 2=Fovis 3=viso2 4=DVO-SLAM 5=ORB_SLAM2 6=OKVIS 7=LOAM 8=MSCKF_VIO");
401  RTABMAP_PARAM(Odom, ResetCountdown, int, 0, "Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).");
402  RTABMAP_PARAM(Odom, Holonomic, bool, true, "If the robot is holonomic (strafing commands can be issued). If not, y value will be estimated from x and yaw values (y=x*tan(yaw)).");
403  RTABMAP_PARAM(Odom, FillInfoData, bool, true, "Fill info with data (inliers/outliers features).");
404  RTABMAP_PARAM(Odom, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).");
405  RTABMAP_PARAM(Odom, FilteringStrategy, int, 0, "0=No filtering 1=Kalman filtering 2=Particle filtering");
406  RTABMAP_PARAM(Odom, ParticleSize, unsigned int, 400, "Number of particles of the filter.");
407  RTABMAP_PARAM(Odom, ParticleNoiseT, float, 0.002, "Noise (m) of translation components (x,y,z).");
408  RTABMAP_PARAM(Odom, ParticleLambdaT, float, 100, "Lambda of translation components (x,y,z).");
409  RTABMAP_PARAM(Odom, ParticleNoiseR, float, 0.002, "Noise (rad) of rotational components (roll,pitch,yaw).");
410  RTABMAP_PARAM(Odom, ParticleLambdaR, float, 100, "Lambda of rotational components (roll,pitch,yaw).");
411  RTABMAP_PARAM(Odom, KalmanProcessNoise, float, 0.001, "Process noise covariance value.");
412  RTABMAP_PARAM(Odom, KalmanMeasurementNoise, float, 0.01, "Process measurement covariance value.");
413  RTABMAP_PARAM(Odom, GuessMotion, bool, true, "Guess next transformation from the last motion computed.");
414  RTABMAP_PARAM(Odom, KeyFrameThr, float, 0.3, "[Visual] Create a new keyframe when the number of inliers drops under this ratio of features in last frame. Setting the value to 0 means that a keyframe is created for each processed frame.");
415  RTABMAP_PARAM(Odom, VisKeyFrameThr, int, 150, "[Visual] Create a new keyframe when the number of inliers drops under this threshold. Setting the value to 0 means that a keyframe is created for each processed frame.");
416  RTABMAP_PARAM(Odom, ScanKeyFrameThr, float, 0.9, "[Geometry] Create a new keyframe when the number of ICP inliers drops under this ratio of points in last frame's scan. Setting the value to 0 means that a keyframe is created for each processed frame.");
417  RTABMAP_PARAM(Odom, ImageDecimation, int, 1, "Decimation of the images before registration. Negative decimation is done from RGB size instead of depth size (if depth is smaller than RGB, it may be interpolated depending of the decimation value).");
418  RTABMAP_PARAM(Odom, AlignWithGround, bool, false, "Align odometry with the ground on initialization.");
419 
420  // Odometry Frame-to-Map
421  RTABMAP_PARAM(OdomF2M, MaxSize, int, 2000, "[Visual] Local map size: If > 0 (example 5000), the odometry will maintain a local map of X maximum words.");
422  RTABMAP_PARAM(OdomF2M, MaxNewFeatures, int, 0, "[Visual] Maximum features (sorted by keypoint response) added to local map from a new key-frame. 0 means no limit.");
423  RTABMAP_PARAM(OdomF2M, ScanMaxSize, int, 2000, "[Geometry] Maximum local scan map size.");
424  RTABMAP_PARAM(OdomF2M, ScanSubtractRadius, float, 0.05, "[Geometry] Radius used to filter points of a new added scan to local map. This could match the voxel size of the scans.");
425  RTABMAP_PARAM(OdomF2M, ScanSubtractAngle, float, 45, uFormat("[Geometry] Max angle (degrees) used to filter points of a new added scan to local map (when \"%s\">0). 0 means any angle.", kOdomF2MScanSubtractRadius().c_str()).c_str());
426 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM2)
427  RTABMAP_PARAM(OdomF2M, BundleAdjustment, int, 1, "Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba.");
428 #else
429  RTABMAP_PARAM(OdomF2M, BundleAdjustment, int, 0, "Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba.");
430 #endif
431  RTABMAP_PARAM(OdomF2M, BundleAdjustmentMaxFrames, int, 10, "Maximum frames used for bundle adjustment (0=inf or all current frames in the local map).");
432 
433  // Odometry Mono
434  RTABMAP_PARAM(OdomMono, InitMinFlow, float, 100, "Minimum optical flow required for the initialization step.");
435  RTABMAP_PARAM(OdomMono, InitMinTranslation, float, 0.1, "Minimum translation required for the initialization step.");
436  RTABMAP_PARAM(OdomMono, MinTranslation, float, 0.02, "Minimum translation to add new points to local map. On initialization, translation x 5 is used as the minimum.");
437  RTABMAP_PARAM(OdomMono, MaxVariance, float, 0.01, "Maximum variance to add new points to local map.");
438 
439  // Odometry Fovis
440  RTABMAP_PARAM(OdomFovis, FeatureWindowSize, int, 9, "The size of the n x n image patch surrounding each feature, used for keypoint matching.");
441  RTABMAP_PARAM(OdomFovis, MaxPyramidLevel, int, 3, "The maximum Gaussian pyramid level to process the image at. Pyramid level 1 corresponds to the original image.");
442  RTABMAP_PARAM(OdomFovis, MinPyramidLevel, int, 0, "The minimum pyramid level.");
443  RTABMAP_PARAM(OdomFovis, TargetPixelsPerFeature, int, 250, "Specifies the desired feature density as a ratio of input image pixels per feature detected. This number is used to control the adaptive feature thresholding.");
444  RTABMAP_PARAM(OdomFovis, FastThreshold, int, 20, "FAST threshold.");
445  RTABMAP_PARAM(OdomFovis, UseAdaptiveThreshold, bool, true, "Use FAST adaptive threshold.");
446  RTABMAP_PARAM(OdomFovis, FastThresholdAdaptiveGain, double, 0.005, "FAST threshold adaptive gain.");
447  RTABMAP_PARAM(OdomFovis, UseHomographyInitialization, bool, true, "Use homography initialization.");
448 
449  RTABMAP_PARAM(OdomFovis, UseBucketing, bool, true, "");
450  RTABMAP_PARAM(OdomFovis, BucketWidth, int, 80, "");
451  RTABMAP_PARAM(OdomFovis, BucketHeight, int, 80, "");
452  RTABMAP_PARAM(OdomFovis, MaxKeypointsPerBucket, int, 25, "");
453  RTABMAP_PARAM(OdomFovis, UseImageNormalization, bool, false, "");
454 
455  RTABMAP_PARAM(OdomFovis, InlierMaxReprojectionError, double, 1.5, "The maximum image-space reprojection error (in pixels) a feature match is allowed to have and still be considered an inlier in the set of features used for motion estimation.");
456  RTABMAP_PARAM(OdomFovis, CliqueInlierThreshold, double, 0.1, "See Howard's greedy max-clique algorithm for determining the maximum set of mutually consisten feature matches. This specifies the compatibility threshold, in meters.");
457  RTABMAP_PARAM(OdomFovis, MinFeaturesForEstimate, int, 20, "Minimum number of features in the inlier set for the motion estimate to be considered valid.");
458  RTABMAP_PARAM(OdomFovis, MaxMeanReprojectionError, double, 10.0, "Maximum mean reprojection error over the inlier feature matches for the motion estimate to be considered valid.");
459  RTABMAP_PARAM(OdomFovis, UseSubpixelRefinement, bool, true, "Specifies whether or not to refine feature matches to subpixel resolution.");
460  RTABMAP_PARAM(OdomFovis, FeatureSearchWindow, int, 25, "Specifies the size of the search window to apply when searching for feature matches across time frames. The search is conducted around the feature location predicted by the initial rotation estimate.");
461  RTABMAP_PARAM(OdomFovis, UpdateTargetFeaturesWithRefined, bool, false, "When subpixel refinement is enabled, the refined feature locations can be saved over the original feature locations. This has a slightly negative impact on frame-to-frame visual odometry, but is likely better when using this library as part of a visual SLAM algorithm.");
462 
463  RTABMAP_PARAM(OdomFovis, StereoRequireMutualMatch, bool, true, "");
464  RTABMAP_PARAM(OdomFovis, StereoMaxDistEpipolarLine, double, 1.5, "");
465  RTABMAP_PARAM(OdomFovis, StereoMaxRefinementDisplacement, double, 1.0, "");
466  RTABMAP_PARAM(OdomFovis, StereoMaxDisparity, int, 128, "");
467 
468  // Odometry viso2
469  RTABMAP_PARAM(OdomViso2, RansacIters, int, 200, "Number of RANSAC iterations.");
470  RTABMAP_PARAM(OdomViso2, InlierThreshold, double, 2.0, "Fundamental matrix inlier threshold.");
471  RTABMAP_PARAM(OdomViso2, Reweighting, bool, true, "Lower border weights (more robust to calibration errors).");
472  RTABMAP_PARAM(OdomViso2, MatchNmsN, int, 3, "Non-max-suppression: min. distance between maxima (in pixels).");
473  RTABMAP_PARAM(OdomViso2, MatchNmsTau, int, 50, "Non-max-suppression: interest point peakiness threshold.");
474  RTABMAP_PARAM(OdomViso2, MatchBinsize, int, 50, "Matching bin width/height (affects efficiency only).");
475  RTABMAP_PARAM(OdomViso2, MatchRadius, int, 200, "Matching radius (du/dv in pixels).");
476  RTABMAP_PARAM(OdomViso2, MatchDispTolerance, int, 2, "Disparity tolerance for stereo matches (in pixels).");
477  RTABMAP_PARAM(OdomViso2, MatchOutlierDispTolerance, int, 5, "Outlier removal: disparity tolerance (in pixels).");
478  RTABMAP_PARAM(OdomViso2, MatchOutlierFlowTolerance, int, 5, "Outlier removal: flow tolerance (in pixels).");
479  RTABMAP_PARAM(OdomViso2, MatchMultiStage, bool, true, "Multistage matching (denser and faster).");
480  RTABMAP_PARAM(OdomViso2, MatchHalfResolution, bool, true, "Match at half resolution, refine at full resolution.");
481  RTABMAP_PARAM(OdomViso2, MatchRefinement, int, 1, "Refinement (0=none,1=pixel,2=subpixel).");
482  RTABMAP_PARAM(OdomViso2, BucketMaxFeatures, int, 2, "Maximal number of features per bucket.");
483  RTABMAP_PARAM(OdomViso2, BucketWidth, double, 50, "Width of bucket.");
484  RTABMAP_PARAM(OdomViso2, BucketHeight, double, 50, "Height of bucket.");
485 
486  // Odometry ORB_SLAM2
487  RTABMAP_PARAM_STR(OdomORBSLAM2, VocPath, "", "Path to ORB vocabulary (*.txt).");
488  RTABMAP_PARAM(OdomORBSLAM2, Bf, double, 0.076, "Fake IR projector baseline (m) used only when stereo is not used.");
489  RTABMAP_PARAM(OdomORBSLAM2, ThDepth, double, 40.0, "Close/Far threshold. Baseline times.");
490  RTABMAP_PARAM(OdomORBSLAM2, Fps, float, 0.0, "Camera FPS.");
491  RTABMAP_PARAM(OdomORBSLAM2, MaxFeatures, int, 1000, "Maximum ORB features extracted per frame.");
492  RTABMAP_PARAM(OdomORBSLAM2, MapSize, int, 3000, "Maximum size of the feature map (0 means infinite).");
493 
494  // Odometry OKVIS
495  RTABMAP_PARAM_STR(OdomOKVIS, ConfigPath, "", "Path of OKVIS config file.");
496 
497  // Odometry LOAM
498  RTABMAP_PARAM(OdomLOAM, Sensor, int, 2, "Velodyne sensor: 0=VLP-16, 1=HDL-32, 2=HDL-64E");
499  RTABMAP_PARAM(OdomLOAM, ScanPeriod, float, 0.1, "Scan period (s)");
500  RTABMAP_PARAM(OdomLOAM, LinVar, float, 0.01, "Linear output variance.");
501  RTABMAP_PARAM(OdomLOAM, AngVar, float, 0.01, "Angular output variance.");
502  RTABMAP_PARAM(OdomLOAM, LocalMapping, bool, true, "Local mapping. It adds more time to compute odometry, but accuracy is significantly improved.");
503 
504  // Odometry MSCKF_VIO
505  RTABMAP_PARAM(OdomMSCKF, GridRow, int, 4, "");
506  RTABMAP_PARAM(OdomMSCKF, GridCol, int, 5, "");
507  RTABMAP_PARAM(OdomMSCKF, GridMinFeatureNum, int, 3, "");
508  RTABMAP_PARAM(OdomMSCKF, GridMaxFeatureNum, int, 4, "");
509  RTABMAP_PARAM(OdomMSCKF, PyramidLevels, int, 3, "");
510  RTABMAP_PARAM(OdomMSCKF, PatchSize, int, 15, "");
511  RTABMAP_PARAM(OdomMSCKF, FastThreshold, int, 10, "");
512  RTABMAP_PARAM(OdomMSCKF, MaxIteration, int, 30, "");
513  RTABMAP_PARAM(OdomMSCKF, TrackPrecision, double, 0.01, "");
514  RTABMAP_PARAM(OdomMSCKF, RansacThreshold, double, 3, "");
515  RTABMAP_PARAM(OdomMSCKF, StereoThreshold, double, 5, "");
516  RTABMAP_PARAM(OdomMSCKF, PositionStdThreshold, double, 8.0, "");
517  RTABMAP_PARAM(OdomMSCKF, RotationThreshold, double, 0.2618, "");
518  RTABMAP_PARAM(OdomMSCKF, TranslationThreshold, double, 0.4, "");
519  RTABMAP_PARAM(OdomMSCKF, TrackingRateThreshold, double, 0.5, "");
520  RTABMAP_PARAM(OdomMSCKF, OptTranslationThreshold, double, 0, "");
521  RTABMAP_PARAM(OdomMSCKF, NoiseGyro, double, 0.005, "");
522  RTABMAP_PARAM(OdomMSCKF, NoiseAcc, double, 0.05, "");
523  RTABMAP_PARAM(OdomMSCKF, NoiseGyroBias, double, 0.001, "");
524  RTABMAP_PARAM(OdomMSCKF, NoiseAccBias, double, 0.01, "");
525  RTABMAP_PARAM(OdomMSCKF, NoiseFeature, double, 0.035, "");
526  RTABMAP_PARAM(OdomMSCKF, InitCovVel, double, 0.25, "");
527  RTABMAP_PARAM(OdomMSCKF, InitCovGyroBias, double, 0.01, "");
528  RTABMAP_PARAM(OdomMSCKF, InitCovAccBias, double, 0.01, "");
529  RTABMAP_PARAM(OdomMSCKF, InitCovExRot, double, 0.00030462, "");
530  RTABMAP_PARAM(OdomMSCKF, InitCovExTrans, double, 0.000025, "");
531  RTABMAP_PARAM(OdomMSCKF, MaxCamStateSize, int, 20, "");
532 
533  // Common registration parameters
534  RTABMAP_PARAM(Reg, RepeatOnce, bool, true, "Do a second registration with the output of the first registration as guess. Only done if no guess was provided for the first registration (like on loop closure). It can be useful if the registration approach used can use a guess to get better matches.");
535  RTABMAP_PARAM(Reg, Strategy, int, 0, "0=Vis, 1=Icp, 2=VisIcp");
536  RTABMAP_PARAM(Reg, Force3DoF, bool, false, "Force 3 degrees-of-freedom transform (3Dof: x,y and yaw). Parameters z, roll and pitch will be set to 0.");
537 
538  // Visual registration parameters
539  RTABMAP_PARAM(Vis, EstimationType, int, 1, "Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP), 2:2D->2D (Epipolar Geometry)");
540  RTABMAP_PARAM(Vis, ForwardEstOnly, bool, true, "Forward estimation only (A->B). If false, a transformation is also computed in backward direction (B->A), then the two resulting transforms are merged (middle interpolation between the transforms).");
541  RTABMAP_PARAM(Vis, InlierDistance, float, 0.1, uFormat("[%s = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.", kVisEstimationType().c_str()));
542  RTABMAP_PARAM(Vis, RefineIterations, int, 5, uFormat("[%s = 0] Number of iterations used to refine the transformation found by RANSAC. 0 means that the transformation is not refined.", kVisEstimationType().c_str()));
543  RTABMAP_PARAM(Vis, PnPReprojError, float, 2, uFormat("[%s = 1] PnP reprojection error.", kVisEstimationType().c_str()));
544  RTABMAP_PARAM(Vis, PnPFlags, int, 0, uFormat("[%s = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P", kVisEstimationType().c_str()));
545 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM2)
546  RTABMAP_PARAM(Vis, PnPRefineIterations, int, 0, uFormat("[%s = 1] Refine iterations. Set to 0 if \"%s\" is also used.", kVisEstimationType().c_str(), kVisBundleAdjustment().c_str()));
547 #else
548  RTABMAP_PARAM(Vis, PnPRefineIterations, int, 1, uFormat("[%s = 1] Refine iterations. Set to 0 if \"%s\" is also used.", kVisEstimationType().c_str(), kVisBundleAdjustment().c_str()));
549 #endif
550 
551  RTABMAP_PARAM(Vis, EpipolarGeometryVar, float, 0.02, uFormat("[%s = 2] Epipolar geometry maximum variance to accept the transformation.", kVisEstimationType().c_str()));
552  RTABMAP_PARAM(Vis, MinInliers, int, 20, "Minimum feature correspondences to compute/accept the transformation.");
553  RTABMAP_PARAM(Vis, Iterations, int, 300, "Maximum iterations to compute the transform.");
554 #ifndef RTABMAP_NONFREE
555 #ifdef RTABMAP_OPENCV3
556  // OpenCV 3 without xFeatures2D module doesn't have BRIEF
557  RTABMAP_PARAM(Vis, FeatureType, int, 8, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
558 #else
559  RTABMAP_PARAM(Vis, FeatureType, int, 6, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
560 #endif
561 #else
562  RTABMAP_PARAM(Vis, FeatureType, int, 6, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB 9=KAZE.");
563 #endif
564  RTABMAP_PARAM(Vis, MaxFeatures, int, 1000, "0 no limits.");
565  RTABMAP_PARAM(Vis, MaxDepth, float, 0, "Max depth of the features (0 means no limit).");
566  RTABMAP_PARAM(Vis, MinDepth, float, 0, "Min depth of the features (0 means no limit).");
567  RTABMAP_PARAM(Vis, DepthAsMask, bool, true, "Use depth image as mask when extracting features.");
568  RTABMAP_PARAM_STR(Vis, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
569  RTABMAP_PARAM(Vis, SubPixWinSize, int, 3, "See cv::cornerSubPix().");
570  RTABMAP_PARAM(Vis, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.");
571  RTABMAP_PARAM(Vis, SubPixEps, float, 0.02, "See cv::cornerSubPix().");
572  RTABMAP_PARAM(Vis, GridRows, int, 1, uFormat("Number of rows of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kVisMaxFeatures().c_str()));
573  RTABMAP_PARAM(Vis, GridCols, int, 1, uFormat("Number of columns of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kVisMaxFeatures().c_str()));
574  RTABMAP_PARAM(Vis, CorType, int, 0, "Correspondences computation approach: 0=Features Matching, 1=Optical Flow");
575  RTABMAP_PARAM(Vis, CorNNType, int, 1, uFormat("[%s=0] kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4. Used for features matching approach.", kVisCorType().c_str()));
576  RTABMAP_PARAM(Vis, CorNNDR, float, 0.6, uFormat("[%s=0] NNDR: nearest neighbor distance ratio. Used for features matching approach.", kVisCorType().c_str()));
577  RTABMAP_PARAM(Vis, CorGuessWinSize, int, 20, uFormat("[%s=0] Matching window size (pixels) around projected points when a guess transform is provided to find correspondences. 0 means disabled.", kVisCorType().c_str()));
578  RTABMAP_PARAM(Vis, CorGuessMatchToProjection, bool, false, uFormat("[%s=0] Match frame's corners to source's projected points (when guess transform is provided) instead of projected points to frame's corners.", kVisCorType().c_str()));
579  RTABMAP_PARAM(Vis, CorFlowWinSize, int, 16, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
580  RTABMAP_PARAM(Vis, CorFlowIterations, int, 30, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
581  RTABMAP_PARAM(Vis, CorFlowEps, float, 0.01, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
582  RTABMAP_PARAM(Vis, CorFlowMaxLevel, int, 3, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
583 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM2)
584  RTABMAP_PARAM(Vis, BundleAdjustment, int, 1, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba.");
585 #else
586  RTABMAP_PARAM(Vis, BundleAdjustment, int, 0, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba.");
587 #endif
588 
589  // ICP registration parameters
590  RTABMAP_PARAM(Icp, MaxTranslation, float, 0.2, "Maximum ICP translation correction accepted (m).");
591  RTABMAP_PARAM(Icp, MaxRotation, float, 0.78, "Maximum ICP rotation correction accepted (rad).");
592  RTABMAP_PARAM(Icp, VoxelSize, float, 0.0, "Uniform sampling voxel size (0=disabled).");
593  RTABMAP_PARAM(Icp, DownsamplingStep, int, 1, "Downsampling step size (1=no sampling). This is done before uniform sampling.");
594 #ifdef RTABMAP_POINTMATCHER
595  RTABMAP_PARAM(Icp, MaxCorrespondenceDistance, float, 0.1, "Max distance for point correspondences.");
596 #else
597  RTABMAP_PARAM(Icp, MaxCorrespondenceDistance, float, 0.05, "Max distance for point correspondences.");
598 #endif
599  RTABMAP_PARAM(Icp, Iterations, int, 30, "Max iterations.");
600  RTABMAP_PARAM(Icp, Epsilon, float, 0, "Set the transformation epsilon (maximum allowable difference between two consecutive transformations) in order for an optimization to be considered as having converged to the final solution.");
601  RTABMAP_PARAM(Icp, CorrespondenceRatio, float, 0.1, "Ratio of matching correspondences to accept the transform.");
602 #ifdef RTABMAP_POINTMATCHER
603  RTABMAP_PARAM(Icp, PointToPlane, bool, true, "Use point to plane ICP.");
604 #else
605  RTABMAP_PARAM(Icp, PointToPlane, bool, false, "Use point to plane ICP.");
606 #endif
607  RTABMAP_PARAM(Icp, PointToPlaneK, int, 5, "Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals.");
608  RTABMAP_PARAM(Icp, PointToPlaneRadius, float, 1.0, "Search radius to compute normals for point to plane if the cloud doesn't have already normals.");
609  RTABMAP_PARAM(Icp, PointToPlaneMinComplexity, float, 0.02, "Minimum structural complexity (0.0=low, 1.0=high) of the scan to do point to plane registration, otherwise point to point registration is done instead.");
610 
611  // libpointmatcher
612 #ifdef RTABMAP_POINTMATCHER
613  RTABMAP_PARAM(Icp, PM, bool, true, "Use libpointmatcher for ICP registration instead of PCL's implementation.");
614 #else
615  RTABMAP_PARAM(Icp, PM, bool, false, "Use libpointmatcher for ICP registration instead of PCL's implementation.");
616 #endif
617  RTABMAP_PARAM_STR(Icp, PMConfig, "", uFormat("Configuration file (*.yaml) used by libpointmatcher. Note that data filters set for libpointmatcher are done after filtering done by rtabmap (i.e., %s, %s), so make sure to disable those in rtabmap if you want to use only those from libpointmatcher. Parameters %s, %s and %s are also ignored if configuration file is set.", kIcpVoxelSize().c_str(), kIcpDownsamplingStep().c_str(), kIcpIterations().c_str(), kIcpEpsilon().c_str(), kIcpMaxCorrespondenceDistance().c_str()).c_str());
618  RTABMAP_PARAM(Icp, PMMatcherKnn, int, 1, "KDTreeMatcher/knn: number of nearest neighbors to consider it the reference. For convenience when configuration file is not set.");
619  RTABMAP_PARAM(Icp, PMMatcherEpsilon, float, 0.0, "KDTreeMatcher/epsilon: approximation to use for the nearest-neighbor search. For convenience when configuration file is not set.");
620  RTABMAP_PARAM(Icp, PMOutlierRatio, float, 0.95, "TrimmedDistOutlierFilter/ratio: For convenience when configuration file is not set. For kinect-like point cloud, use 0.65.");
621 
622  // Stereo disparity
623  RTABMAP_PARAM(Stereo, WinWidth, int, 15, "Window width.");
624  RTABMAP_PARAM(Stereo, WinHeight, int, 3, "Window height.");
625  RTABMAP_PARAM(Stereo, Iterations, int, 30, "Maximum iterations.");
626  RTABMAP_PARAM(Stereo, MaxLevel, int, 5, "Maximum pyramid level.");
627  RTABMAP_PARAM(Stereo, MinDisparity, float, 0.5, "Minimum disparity.");
628  RTABMAP_PARAM(Stereo, MaxDisparity, float, 128.0, "Maximum disparity.");
629  RTABMAP_PARAM(Stereo, OpticalFlow, bool, true, "Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.");
630  RTABMAP_PARAM(Stereo, SSD, bool, true, uFormat("[%s=false] Use Sum of Squared Differences (SSD) window, otherwise Sum of Absolute Differences (SAD) window is used.", kStereoOpticalFlow().c_str()));
631  RTABMAP_PARAM(Stereo, Eps, double, 0.01, uFormat("[%s=true] Epsilon stop criterion.", kStereoOpticalFlow().c_str()));
632 
633  RTABMAP_PARAM(StereoBM, BlockSize, int, 15, "See cv::StereoBM");
634  RTABMAP_PARAM(StereoBM, MinDisparity, int, 0, "See cv::StereoBM");
635  RTABMAP_PARAM(StereoBM, NumDisparities, int, 128, "See cv::StereoBM");
636  RTABMAP_PARAM(StereoBM, PreFilterSize, int, 9, "See cv::StereoBM");
637  RTABMAP_PARAM(StereoBM, PreFilterCap, int, 31, "See cv::StereoBM");
638  RTABMAP_PARAM(StereoBM, UniquenessRatio, int, 15, "See cv::StereoBM");
639  RTABMAP_PARAM(StereoBM, TextureThreshold, int, 10, "See cv::StereoBM");
640  RTABMAP_PARAM(StereoBM, SpeckleWindowSize, int, 100, "See cv::StereoBM");
641  RTABMAP_PARAM(StereoBM, SpeckleRange, int, 4, "See cv::StereoBM");
642 
643  // Occupancy Grid
644  RTABMAP_PARAM(Grid, FromDepth, bool, true, "Create occupancy grid from depth image(s), otherwise it is created from laser scan.");
645  RTABMAP_PARAM(Grid, DepthDecimation, int, 4, uFormat("[%s=true] Decimation of the depth image before creating cloud. Negative decimation is done from RGB size instead of depth size (if depth is smaller than RGB, it may be interpolated depending of the decimation value).", kGridDepthDecimation().c_str()));
646  RTABMAP_PARAM(Grid, RangeMin, float, 0.0, "Minimum range from sensor.");
647  RTABMAP_PARAM(Grid, RangeMax, float, 5.0, "Maximum range from sensor. 0=inf.");
648  RTABMAP_PARAM_STR(Grid, DepthRoiRatios, "0.0 0.0 0.0 0.0", uFormat("[%s=true] Region of interest ratios [left, right, top, bottom].", kGridFromDepth().c_str()));
649  RTABMAP_PARAM(Grid, FootprintLength, float, 0.0, "Footprint length used to filter points over the footprint of the robot.");
650  RTABMAP_PARAM(Grid, FootprintWidth, float, 0.0, "Footprint width used to filter points over the footprint of the robot. Footprint length should be set.");
651  RTABMAP_PARAM(Grid, FootprintHeight, float, 0.0, "Footprint height used to filter points over the footprint of the robot. Footprint length and width should be set.");
652  RTABMAP_PARAM(Grid, ScanDecimation, int, 1, uFormat("[%s=false] Decimation of the laser scan before creating cloud.", kGridFromDepth().c_str()));
653  RTABMAP_PARAM(Grid, CellSize, float, 0.05, "Resolution of the occupancy grid.");
654  RTABMAP_PARAM(Grid, PreVoxelFiltering, bool, true, uFormat("Input cloud is downsampled by voxel filter (voxel size is \"%s\") before doing segmentation of obstacles and ground.", kGridCellSize().c_str()));
655  RTABMAP_PARAM(Grid, MapFrameProjection, bool, false, "Projection in map frame. On a 3D terrain and a fixed local camera transform (the cloud is created relative to ground), you may want to disable this to do the projection in robot frame instead.");
656  RTABMAP_PARAM(Grid, NormalsSegmentation, bool, true, "Segment ground from obstacles using point normals, otherwise a fast passthrough is used.");
657  RTABMAP_PARAM(Grid, MaxObstacleHeight, float, 0.0, "Maximum obstacles height (0=disabled).");
658  RTABMAP_PARAM(Grid, MinGroundHeight, float, 0.0, "Minimum ground height (0=disabled).");
659  RTABMAP_PARAM(Grid, MaxGroundHeight, float, 0.0, uFormat("Maximum ground height (0=disabled). Should be set if \"%s\" is false.", kGridNormalsSegmentation().c_str()));
660  RTABMAP_PARAM(Grid, MaxGroundAngle, float, 45, uFormat("[%s=true] Maximum angle (degrees) between point's normal to ground's normal to label it as ground. Points with higher angle difference are considered as obstacles.", kGridNormalsSegmentation().c_str()));
661  RTABMAP_PARAM(Grid, NormalK, int, 20, uFormat("[%s=true] K neighbors to compute normals.", kGridNormalsSegmentation().c_str()));
662  RTABMAP_PARAM(Grid, ClusterRadius, float, 0.1, uFormat("[%s=true] Cluster maximum radius.", kGridNormalsSegmentation().c_str()));
663  RTABMAP_PARAM(Grid, MinClusterSize, int, 10, uFormat("[%s=true] Minimum cluster size to project the points.", kGridNormalsSegmentation().c_str()));
664  RTABMAP_PARAM(Grid, FlatObstacleDetected, bool, true, uFormat("[%s=true] Flat obstacles detected.", kGridNormalsSegmentation().c_str()));
665 #ifdef RTABMAP_OCTOMAP
666  RTABMAP_PARAM(Grid, 3D, bool, true, uFormat("A 3D occupancy grid is required if you want an OctoMap (3D ray tracing). Set to false if you want only a 2D map, the cloud will be projected on xy plane. A 2D map can be still generated if checked, but it requires more memory and time to generate it. Ignored if laser scan is 2D and \"%s\" is false.", kGridFromDepth().c_str()));
667 #else
668  RTABMAP_PARAM(Grid, 3D, bool, false, uFormat("A 3D occupancy grid is required if you want an OctoMap (3D ray tracing). Set to false if you want only a 2D map, the cloud will be projected on xy plane. A 2D map can be still generated if checked, but it requires more memory and time to generate it. Ignored if laser scan is 2D and \"%s\" is false.", kGridFromDepth().c_str()));
669 #endif
670  RTABMAP_PARAM(Grid, GroundIsObstacle, bool, false, uFormat("[%s=true] Ground segmentation (%s) is ignored, all points are obstacles. Use this only if you want an OctoMap with ground identified as an obstacle (e.g., with an UAV).", kGrid3D().c_str(), kGridNormalsSegmentation().c_str()));
671  RTABMAP_PARAM(Grid, NoiseFilteringRadius, float, 0.0, "Noise filtering radius (0=disabled). Done after segmentation.");
672  RTABMAP_PARAM(Grid, NoiseFilteringMinNeighbors, int, 5, "Noise filtering minimum neighbors.");
673  RTABMAP_PARAM(Grid, Scan2dUnknownSpaceFilled, bool, false, uFormat("Unknown space filled. Only used with 2D laser scans. Use %s to set maximum range if laser scan max range is to set.", kGridRangeMax().c_str()));
674  RTABMAP_PARAM(Grid, RayTracing, bool, false, uFormat("Ray tracing is done for each occupied cell, filling unknown space between the sensor and occupied cells. If %s=true, RTAB-Map should be built with OctoMap support, otherwise 3D ray tracing is ignored.", kGrid3D().c_str()));
675 
676  RTABMAP_PARAM(GridGlobal, FullUpdate, bool, true, "When the graph is changed, the whole map will be reconstructed instead of moving individually each cells of the map. Also, data added to cache won't be released after updating the map. This process is longer but more robust to drift that would erase some parts of the map when it should not.");
677  RTABMAP_PARAM(GridGlobal, UpdateError, float, 0.01, "Graph changed detection error (m). Update map only if poses in new optimized graph have moved more than this value.");
678  RTABMAP_PARAM(GridGlobal, FootprintRadius, float, 0.0, "Footprint radius (m) used to clear all obstacles under the graph.");
679  RTABMAP_PARAM(GridGlobal, MinSize, float, 0.0, "Minimum map size (m).");
680  RTABMAP_PARAM(GridGlobal, Eroded, bool, false, "Erode obstacle cells.");
681  RTABMAP_PARAM(GridGlobal, MaxNodes, int, 0, "Maximum nodes assembled in the map starting from the last node (0=unlimited).");
682  RTABMAP_PARAM(GridGlobal, OccupancyThr, float, 0.5, "Occupancy threshold (value between 0 and 1).");
683  RTABMAP_PARAM(GridGlobal, ProbHit, float, 0.7, "Probability of a hit (value between 0.5 and 1).");
684  RTABMAP_PARAM(GridGlobal, ProbMiss, float, 0.4, "Probability of a miss (value between 0 and 0.5).");
685  RTABMAP_PARAM(GridGlobal, ProbClampingMin, float, 0.1192, "Probability clamping minimum (value between 0 and 1).");
686  RTABMAP_PARAM(GridGlobal, ProbClampingMax, float, 0.971, "Probability clamping maximum (value between 0 and 1).");
687 
688 public:
689  virtual ~Parameters();
690 
695  static const ParametersMap & getDefaultParameters()
696  {
697  return parameters_;
698  }
699 
704  static std::string getType(const std::string & paramKey);
705 
710  static std::string getDescription(const std::string & paramKey);
711 
712  static bool parse(const ParametersMap & parameters, const std::string & key, bool & value);
713  static bool parse(const ParametersMap & parameters, const std::string & key, int & value);
714  static bool parse(const ParametersMap & parameters, const std::string & key, unsigned int & value);
715  static bool parse(const ParametersMap & parameters, const std::string & key, float & value);
716  static bool parse(const ParametersMap & parameters, const std::string & key, double & value);
717  static bool parse(const ParametersMap & parameters, const std::string & key, std::string & value);
718  static void parse(const ParametersMap & parameters, ParametersMap & parametersOut);
719 
720  static const char * showUsage();
721  static ParametersMap parseArguments(int argc, char * argv[], bool onlyParameters = false);
722 
723  static std::string getVersion();
724  static std::string getDefaultDatabaseName();
725 
726  static std::string serialize(const ParametersMap & parameters);
727  static ParametersMap deserialize(const std::string & parameters);
728 
729  static bool isFeatureParameter(const std::string & param);
730  static ParametersMap getDefaultOdometryParameters(bool stereo = false, bool vis = true, bool icp = false);
731  static ParametersMap getDefaultParameters(const std::string & group);
732  static ParametersMap filterParameters(const ParametersMap & parameters, const std::string & group);
733 
734  static void readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly = false);
735  static void writeINI(const std::string & configFile, const ParametersMap & parameters);
736 
741  static const std::map<std::string, std::pair<bool, std::string> > & getRemovedParameters();
742 
746  static const ParametersMap & getBackwardCompatibilityMap();
747 
748  static std::string createDefaultWorkingDirectory();
749 
750 private:
751  Parameters();
752 
753 private:
754  static ParametersMap parameters_;
755  static ParametersMap parametersType_;
756  static ParametersMap descriptions_;
758 
759  static std::map<std::string, std::pair<bool, std::string> > removedParameters_;
760  static ParametersMap backwardCompatibilityMap_;
761 };
762 
763 }
764 
765 #endif /* PARAMETERS_H_ */
766 
#define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION)
Definition: Parameters.h:96
void serialize(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:42
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:41
static ParametersMap descriptions_
Definition: Parameters.h:756
static ParametersMap backwardCompatibilityMap_
Definition: Parameters.h:760
Some conversion functions.
void showUsage()
#define RTABMAP_EXP
Definition: RtabmapExp.h:38
static Parameters instance_
Definition: Parameters.h:757
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 ParametersMap parameters_
Definition: Parameters.h:754
Definition: sqlite3.c:13567
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:695
static ParametersMap parametersType_
Definition: Parameters.h:755
#define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION)
Definition: Parameters.h:62
std::string UTILITE_EXP uFormat(const char *fmt,...)
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
Definition: Parameters.h:759
void deserialize(std::istream &strm, Eigen::Matrix< S, T, U > *mat)


rtabmap
Author(s): Mathieu Labbe
autogenerated on Wed Jun 5 2019 22:41:32