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/rtabmap_core_export.h" // DLL export/import defines
33 #include "rtabmap/core/Version.h" // DLL export/import defines
35 #include <opencv2/core/version.hpp>
36 #include <opencv2/opencv_modules.hpp>
37 #include <string>
38 #include <map>
39 
40 namespace rtabmap
41 {
42 
43 typedef std::map<std::string, std::string> ParametersMap; // Key, value
44 typedef std::pair<std::string, std::string> ParametersPair;
45 
64 #define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION) \
65  public: \
66  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
67  static TYPE default##PREFIX##NAME() {return (TYPE)DEFAULT_VALUE;} \
68  static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
69  private: \
70  class Dummy##PREFIX##NAME { \
71  public: \
72  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, #DEFAULT_VALUE)); \
73  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
74  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
75  }; \
76  Dummy##PREFIX##NAME dummy##PREFIX##NAME
77 // end define PARAM
78 
98 #define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION) \
99  public: \
100  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
101  static std::string default##PREFIX##NAME() {return DEFAULT_VALUE;} \
102  static std::string type##PREFIX##NAME() {return std::string("string");} \
103  private: \
104  class Dummy##PREFIX##NAME { \
105  public: \
106  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, DEFAULT_VALUE)); \
107  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, "string")); \
108  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
109  }; \
110  Dummy##PREFIX##NAME dummy##PREFIX##NAME
111 // end define PARAM
112 
131 #define RTABMAP_PARAM_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
132  public: \
133  static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
134  static TYPE default##PREFIX##NAME() {return COND?DEFAULT_VALUE1:DEFAULT_VALUE2;} \
135  static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
136  private: \
137  class Dummy##PREFIX##NAME { \
138  public: \
139  Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, COND?#DEFAULT_VALUE1:#DEFAULT_VALUE2)); \
140  parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
141  descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
142  }; \
143  Dummy##PREFIX##NAME dummy##PREFIX##NAME
144 // end define PARAM
145 
170 class RTABMAP_CORE_EXPORT Parameters
171 {
172  // Rtabmap parameters
173  RTABMAP_PARAM(Rtabmap, PublishStats, bool, true, "Publishing statistics.");
174  RTABMAP_PARAM(Rtabmap, PublishLastSignature, bool, true, "Publishing last signature.");
175  RTABMAP_PARAM(Rtabmap, PublishPdf, bool, true, "Publishing pdf.");
176  RTABMAP_PARAM(Rtabmap, PublishLikelihood, bool, true, "Publishing likelihood.");
177  RTABMAP_PARAM(Rtabmap, PublishRAMUsage, bool, false, "Publishing RAM usage in statistics (may add a small overhead to get info from the system).");
178  RTABMAP_PARAM(Rtabmap, ComputeRMSE, bool, true, "Compute root mean square error (RMSE) and publish it in statistics, if ground truth is provided.");
179  RTABMAP_PARAM(Rtabmap, SaveWMState, bool, false, "Save working memory state after each update in statistics.");
180  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.");
181  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()));
182  RTABMAP_PARAM(Rtabmap, DetectionRate, float, 1, "Detection rate (Hz). RTAB-Map will filter input images to satisfy this rate.");
183  RTABMAP_PARAM(Rtabmap, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).");
184  RTABMAP_PARAM(Rtabmap, CreateIntermediateNodes, bool, false, uFormat("Create intermediate nodes between loop closure detection. Only used when %s>0.", kRtabmapDetectionRate().c_str()));
185  RTABMAP_PARAM_STR(Rtabmap, WorkingDirectory, "", "Working directory.");
186  RTABMAP_PARAM(Rtabmap, MaxRetrieved, unsigned int, 2, "Maximum nodes retrieved at the same time from LTM.");
187  RTABMAP_PARAM(Rtabmap, MaxRepublished, unsigned int, 2, uFormat("Maximum nodes republished when requesting missing data. When %s=false, only loop closure data is republished, otherwise the closest nodes from the current localization are republished first. Ignored if %s=false.", kRGBDEnabled().c_str(), kRtabmapPublishLastSignature().c_str()));
188  RTABMAP_PARAM(Rtabmap, StatisticLogsBufferedInRAM, bool, true, "Statistic logs buffered in RAM instead of written to hard drive after each iteration.");
189  RTABMAP_PARAM(Rtabmap, StatisticLogged, bool, false, "Logging enabled.");
190  RTABMAP_PARAM(Rtabmap, StatisticLoggedHeaders, bool, true, "Add column header description to log files.");
191  RTABMAP_PARAM(Rtabmap, StartNewMapOnLoopClosure, bool, false, "Start a new map only if there is a global loop closure with a previous map.");
192  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()));
193  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.");
194  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()));
195 
196  // Hypotheses selection
197  RTABMAP_PARAM(Rtabmap, LoopThr, float, 0.11, "Loop closing threshold.");
198  RTABMAP_PARAM(Rtabmap, LoopRatio, float, 0, "The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.");
199  RTABMAP_PARAM(Rtabmap, LoopGPS, bool, true, uFormat("Use GPS to filter likelihood (if GPS is recorded). Only locations inside the local radius \"%s\" of the current GPS location are considered for loop closure detection.", kRGBDLocalRadius().c_str()));
200  RTABMAP_PARAM(Rtabmap, VirtualPlaceLikelihoodRatio, int, 0, "Likelihood ratio for virtual place (for no loop closure hypothesis): 0=Mean / StdDev, 1=StdDev / (Max-Mean)");
201 
202  // Memory
203  RTABMAP_PARAM(Mem, RehearsalSimilarity, float, 0.6, "Rehearsal similarity.");
204  RTABMAP_PARAM(Mem, ImageKept, bool, false, "Keep raw images in RAM.");
205  RTABMAP_PARAM(Mem, BinDataKept, bool, true, "Keep binary data in db.");
206  RTABMAP_PARAM(Mem, RawDescriptorsKept, bool, true, "Raw descriptors kept in memory.");
207  RTABMAP_PARAM(Mem, MapLabelsAdded, bool, true, "Create map labels. The first node of a map will be labeled as \"map#\" where # is the map ID.");
208  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).");
209  RTABMAP_PARAM(Mem, NotLinkedNodesKept, bool, true, "Keep not linked nodes in db (rehearsed nodes and deleted nodes).");
210  RTABMAP_PARAM(Mem, IntermediateNodeDataKept, bool, false, "Keep intermediate node data in db.");
211  RTABMAP_PARAM_STR(Mem, ImageCompressionFormat, ".jpg", "RGB image compression format. It should be \".jpg\" or \".png\".");
212  RTABMAP_PARAM(Mem, STMSize, unsigned int, 10, "Short-term memory size.");
213  RTABMAP_PARAM(Mem, IncrementalMemory, bool, true, "SLAM mode, otherwise it is Localization mode.");
214  RTABMAP_PARAM(Mem, LocalizationDataSaved, bool, false, uFormat("Save localization data during localization session (when %s=false). When enabled, the database will then also grow in localization mode. This mode would be used only for debugging purpose.", kMemIncrementalMemory().c_str()).c_str());
215  RTABMAP_PARAM(Mem, ReduceGraph, bool, false, "Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set).");
216  RTABMAP_PARAM(Mem, RecentWmRatio, float, 0.2, "Ratio of locations after the last loop closure in WM that cannot be transferred.");
217  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.");
218  RTABMAP_PARAM(Mem, RehearsalIdUpdatedToNewOne, bool, false, "On merge, update to new id. When false, no copy.");
219  RTABMAP_PARAM(Mem, RehearsalWeightIgnoredWhileMoving, bool, false, "When the robot is moving, weights are not updated on rehearsal.");
220  RTABMAP_PARAM(Mem, GenerateIds, bool, true, "True=Generate location IDs, False=use input image IDs.");
221  RTABMAP_PARAM(Mem, BadSignaturesIgnored, bool, false, "Bad signatures are ignored.");
222  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.");
223  RTABMAP_PARAM(Mem, DepthAsMask, bool, true, "Use depth image as mask when extracting features for vocabulary.");
224  RTABMAP_PARAM(Mem, StereoFromMotion, bool, false, uFormat("Triangulate features without depth using stereo from motion (odometry). It would be ignored if %s is true and the feature detector used supports masking.", kMemDepthAsMask().c_str()));
225  RTABMAP_PARAM(Mem, ImagePreDecimation, unsigned int, 1, uFormat("Decimation of the RGB image before visual feature detection. If depth size is larger than decimated RGB size, depth is decimated to be always at most equal to RGB size. If %s is true and if depth is smaller than decimated RGB, depth may be interpolated to match RGB size for feature detection.",kMemDepthAsMask().c_str()));
226  RTABMAP_PARAM(Mem, ImagePostDecimation, unsigned int, 1, uFormat("Decimation of the RGB image before saving it to database. If depth size is larger than decimated RGB size, depth is decimated to be always at most equal to RGB size. Decimation is done from the original image. If set to same value than %s, data already decimated is saved (no need to re-decimate the image).", kMemImagePreDecimation().c_str()));
227  RTABMAP_PARAM(Mem, CompressionParallelized, bool, true, "Compression of sensor data is multi-threaded.");
228  RTABMAP_PARAM(Mem, LaserScanDownsampleStepSize, int, 1, "If > 1, downsample the laser scans when creating a signature.");
229  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()));
230  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.");
231  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.");
232  RTABMAP_PARAM(Mem, UseOdomFeatures, bool, true, "Use odometry features instead of regenerating them.");
233  RTABMAP_PARAM(Mem, UseOdomGravity, bool, false, uFormat("Use odometry instead of IMU orientation to add gravity links to new nodes created. We assume that odometry is already aligned with gravity (e.g., we are using a VIO approach). Gravity constraints are used by graph optimization only if \"%s\" is not zero.", kOptimizerGravitySigma().c_str()));
234  RTABMAP_PARAM(Mem, CovOffDiagIgnored, bool, true, "Ignore off diagonal values of the covariance matrix.");
235  RTABMAP_PARAM(Mem, GlobalDescriptorStrategy, int, 0, "Extract global descriptor from sensor data. 0=disabled, 1=PyDescriptor");
236  RTABMAP_PARAM(Mem, RotateImagesUpsideUp, bool, false, "Rotate images so that upside is up if they are not already. This can be useful in case the robots don't have all same camera orientation but are using the same map, so that not rotation-invariant visual features can still be used across the fleet.");
237 
238  // KeypointMemory (Keypoint-based)
239  RTABMAP_PARAM(Kp, NNStrategy, int, 1, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
240  RTABMAP_PARAM(Kp, IncrementalDictionary, bool, true, "");
241  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()));
242  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()));
243  RTABMAP_PARAM(Kp, ByteToFloat, bool, false, uFormat("For %s=1, binary descriptors are converted to float by converting each byte to float instead of converting each bit to float. When converting bytes instead of bits, less memory is used and search is faster at the cost of slightly less accurate matching.", kKpNNStrategy().c_str()));
244  RTABMAP_PARAM(Kp, MaxDepth, float, 0, "Filter extracted keypoints by depth (0=inf).");
245  RTABMAP_PARAM(Kp, MinDepth, float, 0, "Filter extracted keypoints by depth.");
246  RTABMAP_PARAM(Kp, MaxFeatures, int, 500, "Maximum features extracted from the images (0 means not bounded, <0 means no extraction).");
247  RTABMAP_PARAM(Kp, SSC, bool, false, "If true, SSC (Suppression via Square Covering) is applied to limit keypoints.");
248  RTABMAP_PARAM(Kp, BadSignRatio, float, 0.5, "Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).");
249  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.)");
250 #if CV_MAJOR_VERSION > 2 && !defined(HAVE_OPENCV_XFEATURES2D)
251  // OpenCV>2 without xFeatures2D module doesn't have BRIEF
252  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 10=ORB-OCTREE 11=SuperPoint 12=SURF/FREAK 13=GFTT/DAISY 14=SURF/DAISY 15=PyDetector");
253 #else
254  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 10=ORB-OCTREE 11=SuperPoint 12=SURF/FREAK 13=GFTT/DAISY 14=SURF/DAISY 15=PyDetector");
255 #endif
256  RTABMAP_PARAM(Kp, TfIdfLikelihoodUsed, bool, true, "Use of the td-idf strategy to compute the likelihood.");
257  RTABMAP_PARAM(Kp, Parallelized, bool, true, "If the dictionary update and signature creation were parallelized.");
258  RTABMAP_PARAM_STR(Kp, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
259  RTABMAP_PARAM_STR(Kp, DictionaryPath, "", "Path of the pre-computed dictionary");
260  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).");
261  RTABMAP_PARAM(Kp, SubPixWinSize, int, 3, "See cv::cornerSubPix().");
262  RTABMAP_PARAM(Kp, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.");
263  RTABMAP_PARAM(Kp, SubPixEps, double, 0.02, "See cv::cornerSubPix().");
264  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()));
265  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()));
266 
267  //Database
268  RTABMAP_PARAM(DbSqlite3, InMemory, bool, false, "Using database in the memory instead of a file on the hard disk.");
269  RTABMAP_PARAM(DbSqlite3, CacheSize, unsigned int, 10000, "Sqlite cache size (default is 2000).");
270  RTABMAP_PARAM(DbSqlite3, JournalMode, int, 3, "0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")");
271  RTABMAP_PARAM(DbSqlite3, Synchronous, int, 0, "0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")");
272  RTABMAP_PARAM(DbSqlite3, TempStore, int, 2, "0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")");
273  RTABMAP_PARAM_STR(Db, TargetVersion, "", "Target database version for backward compatibility purpose. Only Major and minor versions are used and should be set (e.g., 0.19 vs 0.20 or 1.0 vs 2.0). Patch version is ignored (e.g., 0.20.1 and 0.20.3 will generate a 0.20 database).");
274 
275  // Keypoints descriptors/detectors
276  RTABMAP_PARAM(SURF, Extended, bool, false, "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
277  RTABMAP_PARAM(SURF, HessianThreshold, float, 500, "Threshold for hessian keypoint detector used in SURF.");
278  RTABMAP_PARAM(SURF, Octaves, int, 4, "Number of pyramid octaves the keypoint detector will use.");
279  RTABMAP_PARAM(SURF, OctaveLayers, int, 2, "Number of octave layers within each octave.");
280  RTABMAP_PARAM(SURF, Upright, bool, false, "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
281  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.");
282  RTABMAP_PARAM(SURF, GpuKeypointsRatio, float, 0.01, "Used with SURF GPU.");
283 
284  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).");
285  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.");
286  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.");
287  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).");
288  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.");
289  RTABMAP_PARAM(SIFT, RootSIFT, bool, false, "Apply RootSIFT normalization of the descriptors.");
290 
291  RTABMAP_PARAM(BRIEF, Bytes, int, 32, "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
292 
293  RTABMAP_PARAM(FAST, Threshold, int, 20, "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
294  RTABMAP_PARAM(FAST, NonmaxSuppression, bool, true, "If true, non-maximum suppression is applied to detected corners (keypoints).");
295  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.");
296  RTABMAP_PARAM(FAST, GpuKeypointsRatio, double, 0.05, "Used with FAST GPU.");
297  RTABMAP_PARAM(FAST, MinThreshold, int, 7, "Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
298  RTABMAP_PARAM(FAST, MaxThreshold, int, 200, "Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
299  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.");
300  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.");
301  RTABMAP_PARAM(FAST, CV, int, 0, "Enable FastCV implementation if non-zero (and RTAB-Map is built with FastCV support). Values should be 9 and 10.");
302 
303  RTABMAP_PARAM(GFTT, QualityLevel, double, 0.001, "");
304  RTABMAP_PARAM(GFTT, MinDistance, double, 7, "");
305  RTABMAP_PARAM(GFTT, BlockSize, int, 3, "");
306  RTABMAP_PARAM(GFTT, UseHarrisDetector, bool, false, "");
307  RTABMAP_PARAM(GFTT, K, double, 0.04, "");
308 
309  RTABMAP_PARAM(ORB, ScaleFactor, float, 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.");
310  RTABMAP_PARAM(ORB, NLevels, int, 3, "The number of pyramid levels. The smallest level will have linear size equal to input_image_linear_size/pow(scaleFactor, nlevels).");
311  RTABMAP_PARAM(ORB, EdgeThreshold, int, 19, "This is size of the border where the features are not detected. It should roughly match the patchSize parameter.");
312  RTABMAP_PARAM(ORB, FirstLevel, int, 0, "It should be 0 in the current implementation.");
313  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).");
314  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.");
315  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.");
316  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.");
317 
318  RTABMAP_PARAM(FREAK, OrientationNormalized, bool, true, "Enable orientation normalization.");
319  RTABMAP_PARAM(FREAK, ScaleNormalized, bool, true, "Enable scale normalization.");
320  RTABMAP_PARAM(FREAK, PatternScale, float, 22, "Scaling of the description pattern.");
321  RTABMAP_PARAM(FREAK, NOctaves, int, 4, "Number of octaves covered by the detected keypoints.");
322 
323  RTABMAP_PARAM(BRISK, Thresh, int, 30, "FAST/AGAST detection threshold score.");
324  RTABMAP_PARAM(BRISK, Octaves, int, 3, "Detection octaves. Use 0 to do single scale.");
325  RTABMAP_PARAM(BRISK, PatternScale, float, 1,"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
326 
327  RTABMAP_PARAM(KAZE, Extended, bool, false, "Set to enable extraction of extended (128-byte) descriptor.");
328  RTABMAP_PARAM(KAZE, Upright, bool, false, "Set to enable use of upright descriptors (non rotation-invariant).");
329  RTABMAP_PARAM(KAZE, Threshold, float, 0.001, "Detector response threshold to accept keypoint.");
330  RTABMAP_PARAM(KAZE, NOctaves, int, 4, "Maximum octave evolution of the image.");
331  RTABMAP_PARAM(KAZE, NOctaveLayers, int, 4, "Default number of sublevels per scale level.");
332  RTABMAP_PARAM(KAZE, Diffusivity, int, 1, "Diffusivity type: 0=DIFF_PM_G1, 1=DIFF_PM_G2, 2=DIFF_WEICKERT or 3=DIFF_CHARBONNIER.");
333 
334  RTABMAP_PARAM_STR(SuperPoint, ModelPath, "", "[Required] Path to pre-trained weights Torch file of SuperPoint (*.pt).");
335  RTABMAP_PARAM(SuperPoint, Threshold, float, 0.010, "Detector response threshold to accept keypoint.");
336  RTABMAP_PARAM(SuperPoint, NMS, bool, true, "If true, non-maximum suppression is applied to detected keypoints.");
337  RTABMAP_PARAM(SuperPoint, NMSRadius, int, 4, uFormat("[%s=true] Minimum distance (pixels) between keypoints.", kSuperPointNMS().c_str()));
338  RTABMAP_PARAM(SuperPoint, Cuda, bool, true, "Use Cuda device for Torch, otherwise CPU device is used by default.");
339 
340  RTABMAP_PARAM_STR(PyDetector, Path, "", "Path to python script file (see available ones in rtabmap/corelib/src/python/*). See the header to see where the script should be copied.");
341  RTABMAP_PARAM(PyDetector, Cuda, bool, true, "Use cuda.");
342 
343  // BayesFilter
344  RTABMAP_PARAM(Bayes, VirtualPlacePriorThr, float, 0.9, "Virtual place prior");
345  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, ...}.");
346  RTABMAP_PARAM(Bayes, FullPredictionUpdate, bool, false, "Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).");
347 
348  // Verify hypotheses
349  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()));
350  RTABMAP_PARAM(VhEp, MatchCountMin, int, 8, "Minimum of matching visual words pairs to accept the loop hypothesis.");
351  RTABMAP_PARAM(VhEp, RansacParam1, float, 3, "Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier.");
352  RTABMAP_PARAM(VhEp, RansacParam2, float, 0.99, "Fundamental matrix (see cvFindFundamentalMat()): Performance of RANSAC.");
353 
354  // RGB-D SLAM
355  RTABMAP_PARAM(RGBD, Enabled, bool, true, "Activate metric SLAM. If set to false, classic RTAB-Map loop closure detection is done using only images and without any metric information.");
356  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.");
357  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.");
358  RTABMAP_PARAM(RGBD, LinearSpeedUpdate, float, 0.0, "Maximum linear speed (m/s) to update the map (0 means not limit).");
359  RTABMAP_PARAM(RGBD, AngularSpeedUpdate, float, 0.0, "Maximum angular speed (rad/s) to update the map (0 means not limit).");
360  RTABMAP_PARAM(RGBD, AggressiveLoopThr, float, 0.05, uFormat("Loop closure threshold used (overriding %s) when a new mapping session is not yet linked to a map of the highest loop closure hypothesis. In localization mode, this threshold is used when there are no loop closure constraints with any map in the cache (%s). In all cases, the goal is to aggressively loop on a previous map in the database. Only used when %s is enabled. Set 1 to disable.", kRtabmapLoopThr().c_str(), kRGBDMaxOdomCacheSize().c_str(), kRGBDEnabled().c_str()));
361  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).");
362  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).");
363  RTABMAP_PARAM(RGBD, OptimizeMaxError, float, 3.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()));
364  RTABMAP_PARAM(RGBD, MaxLoopClosureDistance, float, 0.0, "Reject loop closures/localizations if the distance from the map is over this distance (0=disabled).");
365  RTABMAP_PARAM(RGBD, ForceOdom3DoF, bool, true, uFormat("Force odometry pose to be 3DoF if %s=true.", kRegForce3DoF().c_str()));
366  RTABMAP_PARAM(RGBD, StartAtOrigin, bool, false, uFormat("If true, rtabmap will assume the robot is starting from origin of the map. If false, rtabmap will assume the robot is restarting from the last saved localization pose from previous session (the place where it shut down previously). Used only in localization mode (%s=false).", kMemIncrementalMemory().c_str()));
367  RTABMAP_PARAM(RGBD, GoalReachedRadius, float, 0.5, "Goal reached radius (m).");
368  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.");
369  RTABMAP_PARAM(RGBD, PlanLinearVelocity, float, 0, "Linear velocity (m/sec) used to compute path weights.");
370  RTABMAP_PARAM(RGBD, PlanAngularVelocity, float, 0, "Angular velocity (rad/sec) used to compute path weights.");
371  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:#\".");
372  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).");
373  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.");
374  RTABMAP_PARAM(RGBD, LocalImmunizationRatio, float, 0.25, "Ratio of working memory for which local nodes are immunized from transfer.");
375  RTABMAP_PARAM(RGBD, ScanMatchingIdsSavedInLinks, bool, true, "Save scan matching IDs from one-to-many proximity detection in link's user data.");
376  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()));
377  RTABMAP_PARAM(RGBD, LoopClosureIdentityGuess, bool, false, uFormat("Use Identity matrix as guess when computing loop closure transform, otherwise no guess is used, thus assuming that registration strategy selected (%s) can deal with transformation estimation without guess.", kRegStrategy().c_str()));
378  RTABMAP_PARAM(RGBD, LoopClosureReextractFeatures, bool, false, "Extract features even if there are some already in the nodes. Raw features are not saved in database.");
379  RTABMAP_PARAM(RGBD, LocalBundleOnLoopClosure, bool, false, "Do local bundle adjustment with neighborhood of the loop closure.");
380  RTABMAP_PARAM(RGBD, InvertedReg, bool, false, "On loop closure, do registration from the target to reference instead of reference to target.");
381  RTABMAP_PARAM(RGBD, CreateOccupancyGrid, bool, false, "Create local occupancy grid maps. See \"Grid\" group for parameters.");
382  RTABMAP_PARAM(RGBD, MarkerDetection, bool, false, "Detect static markers to be added as landmarks for graph optimization. If input data have already landmarks, this will be ignored. See \"Marker\" group for parameters.");
383  RTABMAP_PARAM(RGBD, LoopCovLimited, bool, false, "Limit covariance of non-neighbor links to minimum covariance of neighbor links. In other words, if covariance of a loop closure link is smaller than the minimum covariance of odometry links, its covariance is set to minimum covariance of odometry links.");
384  RTABMAP_PARAM(RGBD, MaxOdomCacheSize, int, 10, uFormat("Maximum odometry cache size. Used only in localization mode (when %s=false). This is used to get smoother localizations and to verify localization transforms (when %s!=0) to make sure we don't teleport to a location very similar to one we previously localized on. Set 0 to disable caching.", kMemIncrementalMemory().c_str(), kRGBDOptimizeMaxError().c_str()));
385  RTABMAP_PARAM(RGBD, LocalizationSmoothing, bool, true, uFormat("Adjust localization constraints based on optimized odometry cache poses (when %s>0).", kRGBDMaxOdomCacheSize().c_str()));
386  RTABMAP_PARAM(RGBD, LocalizationPriorError, double, 0.001, uFormat("The corresponding variance (error x error) set to priors of the map's poses during localization (when %s>0).", kRGBDMaxOdomCacheSize().c_str()));
387 
388  // Local/Proximity loop closure detection
389  RTABMAP_PARAM(RGBD, ProximityByTime, bool, false, "Detection over all locations in STM.");
390  RTABMAP_PARAM(RGBD, ProximityBySpace, bool, true, "Detection over locations (in Working Memory) near in space.");
391  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.");
392  RTABMAP_PARAM(RGBD, ProximityMaxPaths, int, 3, "Maximum paths compared (from the most recent) for proximity detection. 0 means no limit.");
393  RTABMAP_PARAM(RGBD, ProximityPathFilteringRadius, float, 1, "Path filtering radius to reduce the number of nodes to compare in a path in one-to-many proximity detection. The nearest node in a path should be inside that radius to be considered for one-to-one proximity detection.");
394  RTABMAP_PARAM(RGBD, ProximityPathMaxNeighbors, int, 0, "Maximum neighbor nodes compared on each path for one-to-many proximity detection. Set to 0 to disable one-to-many proximity detection (by merging the laser scans).");
395  RTABMAP_PARAM(RGBD, ProximityPathRawPosesUsed, bool, true, "When comparing to a local path for one-to-many proximity detection, merge the scans using the odometry poses (with neighbor link optimizations) instead of the ones in the optimized local graph.");
396  RTABMAP_PARAM(RGBD, ProximityAngle, float, 45, "Maximum angle (degrees) for one-to-one proximity detection.");
397  RTABMAP_PARAM(RGBD, ProximityOdomGuess, bool, false, "Use odometry as motion guess for one-to-one proximity detection.");
398  RTABMAP_PARAM(RGBD, ProximityGlobalScanMap, bool, false, uFormat("Create a global assembled map from laser scans for one-to-many proximity detection, replacing the original one-to-many proximity detection (i.e., detection against local paths). Only used in localization mode (%s=false), otherwise original one-to-many proximity detection is done. Note also that if graph is modified (i.e., memory management is enabled or robot jumps from one disjoint session to another in same database), the global scan map is cleared and one-to-many proximity detection is reverted to original approach.", kMemIncrementalMemory().c_str()));
399  RTABMAP_PARAM(RGBD, ProximityMergedScanCovFactor, double, 100.0, uFormat("Covariance factor for one-to-many proximity detection (when %s>0 and scans are used).", kRGBDProximityPathMaxNeighbors().c_str()));
400 
401  // Graph optimization
402 #ifdef RTABMAP_GTSAM
403  RTABMAP_PARAM(Optimizer, Strategy, int, 2, "Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
404  RTABMAP_PARAM(Optimizer, Iterations, int, 20, "Optimization iterations.");
405  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.00001, "Stop optimizing when the error improvement is less than this value.");
406 #else
407 #ifdef RTABMAP_G2O
408  RTABMAP_PARAM(Optimizer, Strategy, int, 1, "Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
409  RTABMAP_PARAM(Optimizer, Iterations, int, 20, "Optimization iterations.");
410  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.0, "Stop optimizing when the error improvement is less than this value.");
411 #else
412 #ifdef RTABMAP_CERES
413  RTABMAP_PARAM(Optimizer, Strategy, int, 3, "Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
414  RTABMAP_PARAM(Optimizer, Iterations, int, 20, "Optimization iterations.");
415  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.000001, "Stop optimizing when the error improvement is less than this value.");
416 #else
417  RTABMAP_PARAM(Optimizer, Strategy, int, 0, "Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
418  RTABMAP_PARAM(Optimizer, Iterations, int, 100, "Optimization iterations.");
419  RTABMAP_PARAM(Optimizer, Epsilon, double, 0.00001, "Stop optimizing when the error improvement is less than this value.");
420 #endif
421 #endif
422 #endif
423  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.");
424  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()));
425  RTABMAP_PARAM(Optimizer, PriorsIgnored, bool, true, "Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this.");
426  RTABMAP_PARAM(Optimizer, LandmarksIgnored, bool, false, "Ignore landmark constraints while optimizing. Currently only g2o and gtsam optimization supports this.");
427 #if defined(RTABMAP_G2O) || defined(RTABMAP_GTSAM)
428  RTABMAP_PARAM(Optimizer, GravitySigma, float, 0.3, uFormat("Gravity sigma value (>=0, typically between 0.1 and 0.3). Optimization is done while preserving gravity orientation of the poses. This should be used only with visual/lidar inertial odometry approaches, for which we assume that all odometry poses are aligned with gravity. Set to 0 to disable gravity constraints. Currently supported only with g2o and GTSAM optimization strategies (see %s).", kOptimizerStrategy().c_str()));
429 #else
430  RTABMAP_PARAM(Optimizer, GravitySigma, float, 0.0, uFormat("Gravity sigma value (>=0, typically between 0.1 and 0.3). Optimization is done while preserving gravity orientation of the poses. This should be used only with visual/lidar inertial odometry approaches, for which we assume that all odometry poses are aligned with gravity. Set to 0 to disable gravity constraints. Currently supported only with g2o and GTSAM optimization strategies (see %s).", kOptimizerStrategy().c_str()));
431 #endif
432 
433 #ifdef RTABMAP_ORB_SLAM
434  RTABMAP_PARAM(g2o, Solver, int, 3, "0=csparse 1=pcg 2=cholmod 3=Eigen");
435 #else
436  RTABMAP_PARAM(g2o, Solver, int, 0, "0=csparse 1=pcg 2=cholmod 3=Eigen");
437 #endif
438  RTABMAP_PARAM(g2o, Optimizer, int, 0, "0=Levenberg 1=GaussNewton");
439  RTABMAP_PARAM(g2o, PixelVariance, double, 1.0, "Pixel variance used for bundle adjustment.");
440  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.");
441  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.");
442 
443  RTABMAP_PARAM(GTSAM, Optimizer, int, 1, "0=Levenberg 1=GaussNewton 2=Dogleg");
444  RTABMAP_PARAM(GTSAM, Incremental, bool, false, uFormat("Do graph optimization incrementally (iSAM2) to increase optimization speed on loop closures. Note that only GaussNewton and Dogleg optimization algorithms are supported (%s) in this mode.", kGTSAMOptimizer().c_str()));
445  RTABMAP_PARAM(GTSAM, IncRelinearizeThreshold, double, 0.01, "Only relinearize variables whose linear delta magnitude is greater than this threshold. See GTSAM::ISAM2 doc for more info.");
446  RTABMAP_PARAM(GTSAM, IncRelinearizeSkip, int, 1, "Only relinearize any variables every X calls to ISAM2::update(). See GTSAM::ISAM2 doc for more info.");
447 
448  // Odometry
449  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 9=VINS-Fusion 10=OpenVINS 11=FLOAM 12=Open3D");
450  RTABMAP_PARAM(Odom, ResetCountdown, int, 0, "Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).");
451  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)).");
452  RTABMAP_PARAM(Odom, FillInfoData, bool, true, "Fill info with data (inliers/outliers features).");
453  RTABMAP_PARAM(Odom, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).");
454  RTABMAP_PARAM(Odom, FilteringStrategy, int, 0, "0=No filtering 1=Kalman filtering 2=Particle filtering. This filter is used to smooth the odometry output.");
455  RTABMAP_PARAM(Odom, ParticleSize, unsigned int, 400, "Number of particles of the filter.");
456  RTABMAP_PARAM(Odom, ParticleNoiseT, float, 0.002, "Noise (m) of translation components (x,y,z).");
457  RTABMAP_PARAM(Odom, ParticleLambdaT, float, 100, "Lambda of translation components (x,y,z).");
458  RTABMAP_PARAM(Odom, ParticleNoiseR, float, 0.002, "Noise (rad) of rotational components (roll,pitch,yaw).");
459  RTABMAP_PARAM(Odom, ParticleLambdaR, float, 100, "Lambda of rotational components (roll,pitch,yaw).");
460  RTABMAP_PARAM(Odom, KalmanProcessNoise, float, 0.001, "Process noise covariance value.");
461  RTABMAP_PARAM(Odom, KalmanMeasurementNoise, float, 0.01, "Process measurement covariance value.");
462  RTABMAP_PARAM(Odom, GuessMotion, bool, true, "Guess next transformation from the last motion computed.");
463  RTABMAP_PARAM(Odom, GuessSmoothingDelay, float, 0, uFormat("Guess smoothing delay (s). Estimated velocity is averaged based on last transforms up to this maximum delay. This can help to get smoother velocity prediction. Last velocity computed is used directly if \"%s\" is set or the delay is below the odometry rate.", kOdomFilteringStrategy().c_str()));
464  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.");
465  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.");
466  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.");
467  RTABMAP_PARAM(Odom, ImageDecimation, unsigned int, 1, uFormat("Decimation of the RGB image before registration. If depth size is larger than decimated RGB size, depth is decimated to be always at most equal to RGB size. If %s is true and if depth is smaller than decimated RGB, depth may be interpolated to match RGB size for feature detection.", kVisDepthAsMask().c_str()));
468  RTABMAP_PARAM(Odom, AlignWithGround, bool, false, "Align odometry with the ground on initialization.");
469  RTABMAP_PARAM(Odom, Deskewing, bool, true, "Lidar deskewing. If input lidar has time channel, it will be deskewed with a constant motion model (with IMU orientation and/or guess if provided).");
470 
471  // Odometry Frame-to-Map
472  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.");
473  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.");
474  RTABMAP_PARAM(OdomF2M, ScanMaxSize, int, 2000, "[Geometry] Maximum local scan map size.");
475  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.");
476  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());
477  RTABMAP_PARAM(OdomF2M, ScanRange, float, 0, "[Geometry] Distance Range used to filter points of local map (when > 0). 0 means local map is updated using time and not range.");
478  RTABMAP_PARAM(OdomF2M, ValidDepthRatio, float, 0.75, "If a new frame has points without valid depth, they are added to local feature map only if points with valid depth on total points is over this ratio. Setting to 1 means no points without valid depth are added to local feature map.");
479 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
480  RTABMAP_PARAM(OdomF2M, BundleAdjustment, int, 1, "Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
481 #else
482  RTABMAP_PARAM(OdomF2M, BundleAdjustment, int, 0, "Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
483 #endif
484  RTABMAP_PARAM(OdomF2M, BundleAdjustmentMaxFrames, int, 10, "Maximum frames used for bundle adjustment (0=inf or all current frames in the local map).");
485 
486  // Odometry Mono
487  RTABMAP_PARAM(OdomMono, InitMinFlow, float, 100, "Minimum optical flow required for the initialization step.");
488  RTABMAP_PARAM(OdomMono, InitMinTranslation, float, 0.1, "Minimum translation required for the initialization step.");
489  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.");
490  RTABMAP_PARAM(OdomMono, MaxVariance, float, 0.01, "Maximum variance to add new points to local map.");
491 
492  // Odometry Fovis
493  RTABMAP_PARAM(OdomFovis, FeatureWindowSize, int, 9, "The size of the n x n image patch surrounding each feature, used for keypoint matching.");
494  RTABMAP_PARAM(OdomFovis, MaxPyramidLevel, int, 3, "The maximum Gaussian pyramid level to process the image at. Pyramid level 1 corresponds to the original image.");
495  RTABMAP_PARAM(OdomFovis, MinPyramidLevel, int, 0, "The minimum pyramid level.");
496  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.");
497  RTABMAP_PARAM(OdomFovis, FastThreshold, int, 20, "FAST threshold.");
498  RTABMAP_PARAM(OdomFovis, UseAdaptiveThreshold, bool, true, "Use FAST adaptive threshold.");
499  RTABMAP_PARAM(OdomFovis, FastThresholdAdaptiveGain, double, 0.005, "FAST threshold adaptive gain.");
500  RTABMAP_PARAM(OdomFovis, UseHomographyInitialization, bool, true, "Use homography initialization.");
501 
502  RTABMAP_PARAM(OdomFovis, UseBucketing, bool, true, "");
503  RTABMAP_PARAM(OdomFovis, BucketWidth, int, 80, "");
504  RTABMAP_PARAM(OdomFovis, BucketHeight, int, 80, "");
505  RTABMAP_PARAM(OdomFovis, MaxKeypointsPerBucket, int, 25, "");
506  RTABMAP_PARAM(OdomFovis, UseImageNormalization, bool, false, "");
507 
508  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.");
509  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.");
510  RTABMAP_PARAM(OdomFovis, MinFeaturesForEstimate, int, 20, "Minimum number of features in the inlier set for the motion estimate to be considered valid.");
511  RTABMAP_PARAM(OdomFovis, MaxMeanReprojectionError, double, 10.0, "Maximum mean reprojection error over the inlier feature matches for the motion estimate to be considered valid.");
512  RTABMAP_PARAM(OdomFovis, UseSubpixelRefinement, bool, true, "Specifies whether or not to refine feature matches to subpixel resolution.");
513  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.");
514  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.");
515 
516  RTABMAP_PARAM(OdomFovis, StereoRequireMutualMatch, bool, true, "");
517  RTABMAP_PARAM(OdomFovis, StereoMaxDistEpipolarLine, double, 1.5, "");
518  RTABMAP_PARAM(OdomFovis, StereoMaxRefinementDisplacement, double, 1.0, "");
519  RTABMAP_PARAM(OdomFovis, StereoMaxDisparity, int, 128, "");
520 
521  // Odometry viso2
522  RTABMAP_PARAM(OdomViso2, RansacIters, int, 200, "Number of RANSAC iterations.");
523  RTABMAP_PARAM(OdomViso2, InlierThreshold, double, 2.0, "Fundamental matrix inlier threshold.");
524  RTABMAP_PARAM(OdomViso2, Reweighting, bool, true, "Lower border weights (more robust to calibration errors).");
525  RTABMAP_PARAM(OdomViso2, MatchNmsN, int, 3, "Non-max-suppression: min. distance between maxima (in pixels).");
526  RTABMAP_PARAM(OdomViso2, MatchNmsTau, int, 50, "Non-max-suppression: interest point peakiness threshold.");
527  RTABMAP_PARAM(OdomViso2, MatchBinsize, int, 50, "Matching bin width/height (affects efficiency only).");
528  RTABMAP_PARAM(OdomViso2, MatchRadius, int, 200, "Matching radius (du/dv in pixels).");
529  RTABMAP_PARAM(OdomViso2, MatchDispTolerance, int, 2, "Disparity tolerance for stereo matches (in pixels).");
530  RTABMAP_PARAM(OdomViso2, MatchOutlierDispTolerance, int, 5, "Outlier removal: disparity tolerance (in pixels).");
531  RTABMAP_PARAM(OdomViso2, MatchOutlierFlowTolerance, int, 5, "Outlier removal: flow tolerance (in pixels).");
532  RTABMAP_PARAM(OdomViso2, MatchMultiStage, bool, true, "Multistage matching (denser and faster).");
533  RTABMAP_PARAM(OdomViso2, MatchHalfResolution, bool, true, "Match at half resolution, refine at full resolution.");
534  RTABMAP_PARAM(OdomViso2, MatchRefinement, int, 1, "Refinement (0=none,1=pixel,2=subpixel).");
535  RTABMAP_PARAM(OdomViso2, BucketMaxFeatures, int, 2, "Maximal number of features per bucket.");
536  RTABMAP_PARAM(OdomViso2, BucketWidth, double, 50, "Width of bucket.");
537  RTABMAP_PARAM(OdomViso2, BucketHeight, double, 50, "Height of bucket.");
538 
539  // Odometry ORB_SLAM2
540  RTABMAP_PARAM_STR(OdomORBSLAM, VocPath, "", "Path to ORB vocabulary (*.txt).");
541  RTABMAP_PARAM(OdomORBSLAM, Bf, double, 0.076, "Fake IR projector baseline (m) used only when stereo is not used.");
542  RTABMAP_PARAM(OdomORBSLAM, ThDepth, double, 40.0, "Close/Far threshold. Baseline times.");
543  RTABMAP_PARAM(OdomORBSLAM, Fps, float, 0.0, "Camera FPS (0 to estimate from input data).");
544  RTABMAP_PARAM(OdomORBSLAM, MaxFeatures, int, 1000, "Maximum ORB features extracted per frame.");
545  RTABMAP_PARAM(OdomORBSLAM, MapSize, int, 3000, "Maximum size of the feature map (0 means infinite). Only supported with ORB_SLAM2.");
546  RTABMAP_PARAM(OdomORBSLAM, Inertial, bool, false, "Enable IMU. Only supported with ORB_SLAM3.");
547  RTABMAP_PARAM(OdomORBSLAM, GyroNoise, double, 0.01, "IMU gyroscope \"white noise\".");
548  RTABMAP_PARAM(OdomORBSLAM, AccNoise, double, 0.1, "IMU accelerometer \"white noise\".");
549  RTABMAP_PARAM(OdomORBSLAM, GyroWalk, double, 0.000001, "IMU gyroscope \"random walk\".");
550  RTABMAP_PARAM(OdomORBSLAM, AccWalk, double, 0.0001, "IMU accelerometer \"random walk\".");
551  RTABMAP_PARAM(OdomORBSLAM, SamplingRate, double, 0, "IMU sampling rate (0 to estimate from input data).");
552 
553 
554  // Odometry OKVIS
555  RTABMAP_PARAM_STR(OdomOKVIS, ConfigPath, "", "Path of OKVIS config file.");
556 
557  // Odometry LOAM
558  RTABMAP_PARAM(OdomLOAM, Sensor, int, 2, "Velodyne sensor: 0=VLP-16, 1=HDL-32, 2=HDL-64E");
559  RTABMAP_PARAM(OdomLOAM, ScanPeriod, float, 0.1, "Scan period (s)");
560  RTABMAP_PARAM(OdomLOAM, Resolution, float, 0.2, "Map resolution");
561  RTABMAP_PARAM(OdomLOAM, LinVar, float, 0.01, "Linear output variance.");
562  RTABMAP_PARAM(OdomLOAM, AngVar, float, 0.01, "Angular output variance.");
563  RTABMAP_PARAM(OdomLOAM, LocalMapping, bool, true, "Local mapping. It adds more time to compute odometry, but accuracy is significantly improved.");
564 
565  // Odometry MSCKF_VIO
566  RTABMAP_PARAM(OdomMSCKF, GridRow, int, 4, "");
567  RTABMAP_PARAM(OdomMSCKF, GridCol, int, 5, "");
568  RTABMAP_PARAM(OdomMSCKF, GridMinFeatureNum, int, 3, "");
569  RTABMAP_PARAM(OdomMSCKF, GridMaxFeatureNum, int, 4, "");
570  RTABMAP_PARAM(OdomMSCKF, PyramidLevels, int, 3, "");
571  RTABMAP_PARAM(OdomMSCKF, PatchSize, int, 15, "");
572  RTABMAP_PARAM(OdomMSCKF, FastThreshold, int, 10, "");
573  RTABMAP_PARAM(OdomMSCKF, MaxIteration, int, 30, "");
574  RTABMAP_PARAM(OdomMSCKF, TrackPrecision, double, 0.01, "");
575  RTABMAP_PARAM(OdomMSCKF, RansacThreshold, double, 3, "");
576  RTABMAP_PARAM(OdomMSCKF, StereoThreshold, double, 5, "");
577  RTABMAP_PARAM(OdomMSCKF, PositionStdThreshold, double, 8.0, "");
578  RTABMAP_PARAM(OdomMSCKF, RotationThreshold, double, 0.2618, "");
579  RTABMAP_PARAM(OdomMSCKF, TranslationThreshold, double, 0.4, "");
580  RTABMAP_PARAM(OdomMSCKF, TrackingRateThreshold, double, 0.5, "");
581  RTABMAP_PARAM(OdomMSCKF, OptTranslationThreshold, double, 0, "");
582  RTABMAP_PARAM(OdomMSCKF, NoiseGyro, double, 0.005, "");
583  RTABMAP_PARAM(OdomMSCKF, NoiseAcc, double, 0.05, "");
584  RTABMAP_PARAM(OdomMSCKF, NoiseGyroBias, double, 0.001, "");
585  RTABMAP_PARAM(OdomMSCKF, NoiseAccBias, double, 0.01, "");
586  RTABMAP_PARAM(OdomMSCKF, NoiseFeature, double, 0.035, "");
587  RTABMAP_PARAM(OdomMSCKF, InitCovVel, double, 0.25, "");
588  RTABMAP_PARAM(OdomMSCKF, InitCovGyroBias, double, 0.01, "");
589  RTABMAP_PARAM(OdomMSCKF, InitCovAccBias, double, 0.01, "");
590  RTABMAP_PARAM(OdomMSCKF, InitCovExRot, double, 0.00030462, "");
591  RTABMAP_PARAM(OdomMSCKF, InitCovExTrans, double, 0.000025, "");
592  RTABMAP_PARAM(OdomMSCKF, MaxCamStateSize, int, 20, "");
593 
594  // Odometry VINS
595  RTABMAP_PARAM_STR(OdomVINS, ConfigPath, "", "Path of VINS config file.");
596 
597  // Odometry OpenVINS
598  RTABMAP_PARAM(OdomOpenVINS, UseStereo, bool, true, "If we have more than 1 camera, if we should try to track stereo constraints between pairs");
599  RTABMAP_PARAM(OdomOpenVINS, UseKLT, bool, true, "If true we will use KLT, otherwise use a ORB descriptor + robust matching");
600  RTABMAP_PARAM(OdomOpenVINS, NumPts, int, 200, "Number of points (per camera) we will extract and try to track");
601  RTABMAP_PARAM(OdomOpenVINS, MinPxDist, int, 15, "Eistance between features (features near each other provide less information)");
602  RTABMAP_PARAM(OdomOpenVINS, FiTriangulate1d, bool, false, "If we should perform 1d triangulation instead of 3d");
603  RTABMAP_PARAM(OdomOpenVINS, FiRefineFeatures, bool, true, "If we should perform Levenberg-Marquardt refinement");
604  RTABMAP_PARAM(OdomOpenVINS, FiMaxRuns, int, 5, "Max runs for Levenberg-Marquardt");
605  RTABMAP_PARAM(OdomOpenVINS, FiMaxBaseline, double, 40, "Max baseline ratio to accept triangulated features");
606  RTABMAP_PARAM(OdomOpenVINS, FiMaxCondNumber, double, 10000, "Max condition number of linear triangulation matrix accept triangulated features");
607 
608  RTABMAP_PARAM(OdomOpenVINS, UseFEJ, bool, true, "If first-estimate Jacobians should be used (enable for good consistency)");
609  RTABMAP_PARAM(OdomOpenVINS, Integration, int, 1, "0=discrete, 1=rk4, 2=analytical (if rk4 or analytical used then analytical covariance propagation is used)");
610  RTABMAP_PARAM(OdomOpenVINS, CalibCamExtrinsics, bool, false, "Bool to determine whether or not to calibrate imu-to-camera pose");
611  RTABMAP_PARAM(OdomOpenVINS, CalibCamIntrinsics, bool, false, "Bool to determine whether or not to calibrate camera intrinsics");
612  RTABMAP_PARAM(OdomOpenVINS, CalibCamTimeoffset, bool, false, "Bool to determine whether or not to calibrate camera to IMU time offset");
613  RTABMAP_PARAM(OdomOpenVINS, CalibIMUIntrinsics, bool, false, "Bool to determine whether or not to calibrate the IMU intrinsics");
614  RTABMAP_PARAM(OdomOpenVINS, CalibIMUGSensitivity, bool, false, "Bool to determine whether or not to calibrate the Gravity sensitivity");
615  RTABMAP_PARAM(OdomOpenVINS, MaxClones, int, 11, "Max clone size of sliding window");
616  RTABMAP_PARAM(OdomOpenVINS, MaxSLAM, int, 50, "Max number of estimated SLAM features");
617  RTABMAP_PARAM(OdomOpenVINS, MaxSLAMInUpdate, int, 25, "Max number of SLAM features we allow to be included in a single EKF update.");
618  RTABMAP_PARAM(OdomOpenVINS, MaxMSCKFInUpdate, int, 50, "Max number of MSCKF features we will use at a given image timestep.");
619  RTABMAP_PARAM(OdomOpenVINS, FeatRepMSCKF, int, 0, "What representation our features are in (msckf features)");
620  RTABMAP_PARAM(OdomOpenVINS, FeatRepSLAM, int, 4, "What representation our features are in (slam features)");
621  RTABMAP_PARAM(OdomOpenVINS, DtSLAMDelay, double, 0.0, "Delay, in seconds, that we should wait from init before we start estimating SLAM features");
622  RTABMAP_PARAM(OdomOpenVINS, GravityMag, double, 9.81, "Gravity magnitude in the global frame (i.e. should be 9.81 typically)");
623  RTABMAP_PARAM_STR(OdomOpenVINS, LeftMaskPath, "", "Mask for left image");
624  RTABMAP_PARAM_STR(OdomOpenVINS, RightMaskPath, "", "Mask for right image");
625 
626  RTABMAP_PARAM(OdomOpenVINS, InitWindowTime, double, 2.0, "Amount of time we will initialize over (seconds)");
627  RTABMAP_PARAM(OdomOpenVINS, InitIMUThresh, double, 1.0, "Variance threshold on our acceleration to be classified as moving");
628  RTABMAP_PARAM(OdomOpenVINS, InitMaxDisparity, double, 10.0, "Max disparity to consider the platform stationary (dependent on resolution)");
629  RTABMAP_PARAM(OdomOpenVINS, InitMaxFeatures, int, 50, "How many features to track during initialization (saves on computation)");
630  RTABMAP_PARAM(OdomOpenVINS, InitDynUse, bool, false, "If dynamic initialization should be used");
631  RTABMAP_PARAM(OdomOpenVINS, InitDynMLEOptCalib, bool, false, "If we should optimize calibration during intialization (not recommended)");
632  RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxIter, int, 50, "How many iterations the MLE refinement should use (zero to skip the MLE)");
633  RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxTime, double, 0.05, "How many seconds the MLE should be completed in");
634  RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxThreads, int, 6, "How many threads the MLE should use");
635  RTABMAP_PARAM(OdomOpenVINS, InitDynNumPose, int, 6, "Number of poses to use within our window time (evenly spaced)");
636  RTABMAP_PARAM(OdomOpenVINS, InitDynMinDeg, double, 10.0, "Orientation change needed to try to init");
637  RTABMAP_PARAM(OdomOpenVINS, InitDynInflationOri, double, 10.0, "What to inflate the recovered q_GtoI covariance by");
638  RTABMAP_PARAM(OdomOpenVINS, InitDynInflationVel, double, 100.0, "What to inflate the recovered v_IinG covariance by");
639  RTABMAP_PARAM(OdomOpenVINS, InitDynInflationBg, double, 10.0, "What to inflate the recovered bias_g covariance by");
640  RTABMAP_PARAM(OdomOpenVINS, InitDynInflationBa, double, 100.0, "What to inflate the recovered bias_a covariance by");
641  RTABMAP_PARAM(OdomOpenVINS, InitDynMinRecCond, double, 1e-15, "Reciprocal condition number thresh for info inversion");
642 
643  RTABMAP_PARAM(OdomOpenVINS, TryZUPT, bool, true, "If we should try to use zero velocity update");
644  RTABMAP_PARAM(OdomOpenVINS, ZUPTChi2Multiplier, double, 0.0, "Chi2 multiplier for zero velocity");
645  RTABMAP_PARAM(OdomOpenVINS, ZUPTMaxVelodicy, double, 0.1, "Max velocity we will consider to try to do a zupt (i.e. if above this, don't do zupt)");
646  RTABMAP_PARAM(OdomOpenVINS, ZUPTNoiseMultiplier, double, 10.0, "Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)");
647  RTABMAP_PARAM(OdomOpenVINS, ZUPTMaxDisparity, double, 0.5, "Max disparity we will consider to try to do a zupt (i.e. if above this, don't do zupt)");
648  RTABMAP_PARAM(OdomOpenVINS, ZUPTOnlyAtBeginning, bool, false, "If we should only use the zupt at the very beginning static initialization phase");
649 
650  RTABMAP_PARAM(OdomOpenVINS, AccelerometerNoiseDensity, double, 0.01, "[m/s^2/sqrt(Hz)] (accel \"white noise\")");
651  RTABMAP_PARAM(OdomOpenVINS, AccelerometerRandomWalk, double, 0.001, "[m/s^3/sqrt(Hz)] (accel bias diffusion)");
652  RTABMAP_PARAM(OdomOpenVINS, GyroscopeNoiseDensity, double, 0.001, "[rad/s/sqrt(Hz)] (gyro \"white noise\")");
653  RTABMAP_PARAM(OdomOpenVINS, GyroscopeRandomWalk, double, 0.0001, "[rad/s^2/sqrt(Hz)] (gyro bias diffusion)");
654  RTABMAP_PARAM(OdomOpenVINS, UpMSCKFSigmaPx, double, 1.0, "Pixel noise for MSCKF features");
655  RTABMAP_PARAM(OdomOpenVINS, UpMSCKFChi2Multiplier, double, 1.0, "Chi2 multiplier for MSCKF features");
656  RTABMAP_PARAM(OdomOpenVINS, UpSLAMSigmaPx, double, 1.0, "Pixel noise for SLAM features");
657  RTABMAP_PARAM(OdomOpenVINS, UpSLAMChi2Multiplier, double, 1.0, "Chi2 multiplier for SLAM features");
658 
659  // Odometry Open3D
660  RTABMAP_PARAM(OdomOpen3D, MaxDepth, float, 3.0, "Maximum depth.");
661  RTABMAP_PARAM(OdomOpen3D, Method, int, 0, "Registration method: 0=PointToPlane, 1=Intensity, 2=Hybrid.");
662 
663  // Common registration parameters
664  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.");
665  RTABMAP_PARAM(Reg, Strategy, int, 0, "0=Vis, 1=Icp, 2=VisIcp");
666  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.");
667 
668  // Visual registration parameters
669  RTABMAP_PARAM(Vis, EstimationType, int, 1, "Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP), 2:2D->2D (Epipolar Geometry)");
670  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).");
671  RTABMAP_PARAM(Vis, InlierDistance, float, 0.1, uFormat("[%s = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.", kVisEstimationType().c_str()));
672  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()));
673  RTABMAP_PARAM(Vis, PnPReprojError, float, 2, uFormat("[%s = 1] PnP reprojection error.", kVisEstimationType().c_str()));
674  RTABMAP_PARAM(Vis, PnPFlags, int, 0, uFormat("[%s = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P", kVisEstimationType().c_str()));
675 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
676  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()));
677 #else
678  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()));
679 #endif
680  RTABMAP_PARAM(Vis, PnPVarianceMedianRatio, int, 4, uFormat("[%s = 1] Ratio used to compute variance of the estimated transformation if 3D correspondences are provided (should be > 1). The higher it is, the smaller the covariance will be. With accurate depth estimation, this could be set to 2. For depth estimated by stereo, 4 or more maybe used to ignore large errors of very far points.", kVisEstimationType().c_str()));
681  RTABMAP_PARAM(Vis, PnPMaxVariance, float, 0.0, uFormat("[%s = 1] Max linear variance between 3D point correspondences after PnP. 0 means disabled.", kVisEstimationType().c_str()));
682  RTABMAP_PARAM(Vis, PnPSamplingPolicy, unsigned int, 1, uFormat("[%s = 1] Multi-camera random sampling policy: 0=AUTO, 1=ANY, 2=HOMOGENEOUS. With HOMOGENEOUS policy, RANSAC will be done uniformly against all cameras, so at least 2 matches per camera are required. With ANY policy, RANSAC is not constraint to sample on all cameras at the same time. AUTO policy will use HOMOGENEOUS if there are at least 2 matches per camera, otherwise it will fallback to ANY policy.", kVisEstimationType().c_str()).c_str());
683  RTABMAP_PARAM(Vis, PnPSplitLinearCovComponents, bool, false, uFormat("[%s = 1] Compute variance for each linear component instead of using the combined XYZ variance for all linear components.", kVisEstimationType().c_str()).c_str());
684 
685  RTABMAP_PARAM(Vis, EpipolarGeometryVar, float, 0.1, uFormat("[%s = 2] Epipolar geometry maximum variance to accept the transformation.", kVisEstimationType().c_str()));
686  RTABMAP_PARAM(Vis, MinInliers, int, 20, "Minimum feature correspondences to compute/accept the transformation.");
687  RTABMAP_PARAM(Vis, MeanInliersDistance, float, 0.0, "Maximum distance (m) of the mean distance of inliers from the camera to accept the transformation. 0 means disabled.");
688  RTABMAP_PARAM(Vis, MinInliersDistribution, float, 0.0, "Minimum distribution value of the inliers in the image to accept the transformation. The distribution is the second eigen value of the PCA (Principal Component Analysis) on the keypoints of the normalized image [-0.5, 0.5]. The value would be between 0 and 0.5. 0 means disabled.");
689 
690  RTABMAP_PARAM(Vis, Iterations, int, 300, "Maximum iterations to compute the transform.");
691 #if CV_MAJOR_VERSION > 2 && !defined(HAVE_OPENCV_XFEATURES2D)
692  // OpenCV>2 without xFeatures2D module doesn't have BRIEF
693  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 10=ORB-OCTREE 11=SuperPoint 12=SURF/FREAK 13=GFTT/DAISY 14=SURF/DAISY 15=PyDetector");
694 #else
695  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 10=ORB-OCTREE 11=SuperPoint 12=SURF/FREAK 13=GFTT/DAISY 14=SURF/DAISY 15=PyDetector");
696 #endif
697  RTABMAP_PARAM(Vis, MaxFeatures, int, 1000, "0 no limits.");
698  RTABMAP_PARAM(Vis, SSC, bool, false, "If true, SSC (Suppression via Square Covering) is applied to limit keypoints.");
699  RTABMAP_PARAM(Vis, MaxDepth, float, 0, "Max depth of the features (0 means no limit).");
700  RTABMAP_PARAM(Vis, MinDepth, float, 0, "Min depth of the features (0 means no limit).");
701  RTABMAP_PARAM(Vis, DepthAsMask, bool, true, "Use depth image as mask when extracting features.");
702  RTABMAP_PARAM_STR(Vis, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
703  RTABMAP_PARAM(Vis, SubPixWinSize, int, 3, "See cv::cornerSubPix().");
704  RTABMAP_PARAM(Vis, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.");
705  RTABMAP_PARAM(Vis, SubPixEps, float, 0.02, "See cv::cornerSubPix().");
706  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()));
707  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()));
708  RTABMAP_PARAM(Vis, CorType, int, 0, "Correspondences computation approach: 0=Features Matching, 1=Optical Flow");
709  RTABMAP_PARAM(Vis, CorNNType, int, 1, uFormat("[%s=0] kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4, BruteForceCrossCheck=5, SuperGlue=6, GMS=7. Used for features matching approach.", kVisCorType().c_str()));
710  RTABMAP_PARAM(Vis, CorNNDR, float, 0.8, uFormat("[%s=0] NNDR: nearest neighbor distance ratio. Used for knn features matching approach.", kVisCorType().c_str()));
711  RTABMAP_PARAM(Vis, CorGuessWinSize, int, 40, 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()));
712  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()));
713  RTABMAP_PARAM(Vis, CorFlowWinSize, int, 16, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
714  RTABMAP_PARAM(Vis, CorFlowIterations, int, 30, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
715  RTABMAP_PARAM(Vis, CorFlowEps, float, 0.01, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
716  RTABMAP_PARAM(Vis, CorFlowMaxLevel, int, 3, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()));
717 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
718  RTABMAP_PARAM(Vis, BundleAdjustment, int, 1, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
719 #else
720  RTABMAP_PARAM(Vis, BundleAdjustment, int, 0, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
721 #endif
722 
723  // Features matching approaches
724  RTABMAP_PARAM_STR(PyMatcher, Path, "", "Path to python script file (see available ones in rtabmap/corelib/src/python/*). See the header to see where the script should be copied.");
725  RTABMAP_PARAM(PyMatcher, Iterations, int, 20, "Sinkhorn iterations. Used by SuperGlue.");
726  RTABMAP_PARAM(PyMatcher, Threshold, float, 0.2, "Used by SuperGlue.");
727  RTABMAP_PARAM(PyMatcher, Cuda, bool, true, "Used by SuperGlue.");
728  RTABMAP_PARAM_STR(PyMatcher, Model, "indoor", "For SuperGlue, set only \"indoor\" or \"outdoor\". For OANet, set path to one of the pth file (e.g., \"OANet/model/gl3d/sift-4000/model_best.pth\").");
729 
730  RTABMAP_PARAM(GMS, WithRotation, bool, false, "Take rotation transformation into account.");
731  RTABMAP_PARAM(GMS, WithScale, bool, false, "Take scale transformation into account.");
732  RTABMAP_PARAM(GMS, ThresholdFactor, double, 6.0, "The higher, the less matches.");
733 
734  // Global descriptor approaches
735  RTABMAP_PARAM_STR(PyDescriptor, Path, "", "Path to python script file (see available ones in rtabmap/corelib/src/pydescriptor/*). See the header to see where the script should be used.");
736  RTABMAP_PARAM(PyDescriptor, Dim, int, 4096, "Descriptor dimension.");
737 
738  // ICP registration parameters
739 #ifdef RTABMAP_POINTMATCHER
740  RTABMAP_PARAM(Icp, Strategy, int, 1, "ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
741 #else
742  RTABMAP_PARAM(Icp, Strategy, int, 0, "ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
743 #endif
744  RTABMAP_PARAM(Icp, MaxTranslation, float, 0.2, "Maximum ICP translation correction accepted (m).");
745  RTABMAP_PARAM(Icp, MaxRotation, float, 0.78, "Maximum ICP rotation correction accepted (rad).");
746  RTABMAP_PARAM(Icp, VoxelSize, float, 0.05, "Uniform sampling voxel size (0=disabled).");
747  RTABMAP_PARAM(Icp, DownsamplingStep, int, 1, "Downsampling step size (1=no sampling). This is done before uniform sampling.");
748  RTABMAP_PARAM(Icp, RangeMin, float, 0, "Minimum range filtering (0=disabled).");
749  RTABMAP_PARAM(Icp, RangeMax, float, 0, "Maximum range filtering (0=disabled).");
750 #ifdef RTABMAP_POINTMATCHER
751  RTABMAP_PARAM(Icp, MaxCorrespondenceDistance, float, 0.1, "Max distance for point correspondences.");
752 #else
753  RTABMAP_PARAM(Icp, MaxCorrespondenceDistance, float, 0.05, "Max distance for point correspondences.");
754 #endif
755  RTABMAP_PARAM(Icp, ReciprocalCorrespondences, bool, true, "To be a valid correspondence, the corresponding point in target cloud to point in source cloud should be both their closest closest correspondence.");
756  RTABMAP_PARAM(Icp, Iterations, int, 30, "Max iterations.");
757  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.");
758  RTABMAP_PARAM(Icp, CorrespondenceRatio, float, 0.1, "Ratio of matching correspondences to accept the transform.");
759  RTABMAP_PARAM(Icp, Force4DoF, bool, false, uFormat("Limit ICP to x, y, z and yaw DoF. Available if %s > 0.", kIcpStrategy().c_str()));
760  RTABMAP_PARAM(Icp, FiltersEnabled, int, 3, "Flag to enable filters: 1=\"from\" cloud only, 2=\"to\" cloud only, 3=both.");
761 #ifdef RTABMAP_POINTMATCHER
762  RTABMAP_PARAM(Icp, PointToPlane, bool, true, "Use point to plane ICP.");
763 #else
764  RTABMAP_PARAM(Icp, PointToPlane, bool, false, "Use point to plane ICP.");
765 #endif
766  RTABMAP_PARAM(Icp, PointToPlaneK, int, 5, "Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals.");
767  RTABMAP_PARAM(Icp, PointToPlaneRadius, float, 0.0, "Search radius to compute normals for point to plane if the cloud doesn't have already normals.");
768  RTABMAP_PARAM(Icp, PointToPlaneGroundNormalsUp, float, 0.0, "Invert normals on ground if they are pointing down (useful for ring-like 3D LiDARs). 0 means disabled, 1 means only normals perfectly aligned with -z axis. This is only done with 3D scans.");
769  RTABMAP_PARAM(Icp, PointToPlaneMinComplexity, float, 0.02, uFormat("Minimum structural complexity (0.0=low, 1.0=high) of the scan to do PointToPlane registration, otherwise PointToPoint registration is done instead and strategy from %s is used. This check is done only when %s=true.", kIcpPointToPlaneLowComplexityStrategy().c_str(), kIcpPointToPlane().c_str()));
770  RTABMAP_PARAM(Icp, PointToPlaneLowComplexityStrategy, int, 1, uFormat("If structural complexity is below %s: set to 0 to so that the transform is automatically rejected, set to 1 to limit ICP correction in axes with most constraints (e.g., for a corridor-like environment, the resulting transform will be limited in y and yaw, x will taken from the guess), set to 2 to accept \"as is\" the transform computed by PointToPoint.", kIcpPointToPlaneMinComplexity().c_str()));
771  RTABMAP_PARAM(Icp, OutlierRatio, float, 0.85, uFormat("Outlier ratio used with %s>0. For libpointmatcher, this parameter set TrimmedDistOutlierFilter/ratio for convenience when configuration file is not set. For CCCoreLib, this parameter set the \"finalOverlapRatio\". The value should be between 0 and 1.", kIcpStrategy().c_str()));
772  RTABMAP_PARAM_STR(Icp, DebugExportFormat, "", "Export scans used for ICP in the specified format (a warning on terminal will be shown with the file paths used). Supported formats are \"pcd\", \"ply\" or \"vtk\". If logger level is debug, from and to scans will stamped, so previous files won't be overwritten.");
773 
774  // libpointmatcher
775  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());
776  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.");
777  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.");
778  RTABMAP_PARAM(Icp, PMMatcherIntensity, bool, false, uFormat("KDTreeMatcher: among nearest neighbors, keep only the one with the most similar intensity. This only work with %s>1.", kIcpPMMatcherKnn().c_str()));
779 
780  RTABMAP_PARAM(Icp, CCSamplingLimit, unsigned int, 50000, "Maximum number of points per cloud (they are randomly resampled below this limit otherwise).");
781  RTABMAP_PARAM(Icp, CCFilterOutFarthestPoints, bool, false, "If true, the algorithm will automatically ignore farthest points from the reference, for better convergence.");
782  RTABMAP_PARAM(Icp, CCMaxFinalRMS, float, 0.2, "Maximum final RMS error.");
783 
784  // Stereo disparity
785  RTABMAP_PARAM(Stereo, WinWidth, int, 15, "Window width.");
786  RTABMAP_PARAM(Stereo, WinHeight, int, 3, "Window height.");
787  RTABMAP_PARAM(Stereo, Iterations, int, 30, "Maximum iterations.");
788  RTABMAP_PARAM(Stereo, MaxLevel, int, 5, "Maximum pyramid level.");
789  RTABMAP_PARAM(Stereo, MinDisparity, float, 0.5, "Minimum disparity.");
790  RTABMAP_PARAM(Stereo, MaxDisparity, float, 128.0, "Maximum disparity.");
791  RTABMAP_PARAM(Stereo, OpticalFlow, bool, true, "Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.");
792  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()));
793  RTABMAP_PARAM(Stereo, Eps, double, 0.01, uFormat("[%s=true] Epsilon stop criterion.", kStereoOpticalFlow().c_str()));
794 
795  RTABMAP_PARAM(Stereo, DenseStrategy, int, 0, "0=cv::StereoBM, 1=cv::StereoSGBM");
796 
797  RTABMAP_PARAM(StereoBM, BlockSize, int, 15, "See cv::StereoBM");
798  RTABMAP_PARAM(StereoBM, MinDisparity, int, 0, "See cv::StereoBM");
799  RTABMAP_PARAM(StereoBM, NumDisparities, int, 128, "See cv::StereoBM");
800  RTABMAP_PARAM(StereoBM, PreFilterSize, int, 9, "See cv::StereoBM");
801  RTABMAP_PARAM(StereoBM, PreFilterCap, int, 31, "See cv::StereoBM");
802  RTABMAP_PARAM(StereoBM, UniquenessRatio, int, 15, "See cv::StereoBM");
803  RTABMAP_PARAM(StereoBM, TextureThreshold, int, 10, "See cv::StereoBM");
804  RTABMAP_PARAM(StereoBM, SpeckleWindowSize, int, 100, "See cv::StereoBM");
805  RTABMAP_PARAM(StereoBM, SpeckleRange, int, 4, "See cv::StereoBM");
806  RTABMAP_PARAM(StereoBM, Disp12MaxDiff, int, -1, "See cv::StereoBM");
807 
808  RTABMAP_PARAM(StereoSGBM, BlockSize, int, 15, "See cv::StereoSGBM");
809  RTABMAP_PARAM(StereoSGBM, MinDisparity, int, 0, "See cv::StereoSGBM");
810  RTABMAP_PARAM(StereoSGBM, NumDisparities, int, 128, "See cv::StereoSGBM");
811  RTABMAP_PARAM(StereoSGBM, PreFilterCap, int, 31, "See cv::StereoSGBM");
812  RTABMAP_PARAM(StereoSGBM, UniquenessRatio, int, 20, "See cv::StereoSGBM");
813  RTABMAP_PARAM(StereoSGBM, SpeckleWindowSize, int, 100, "See cv::StereoSGBM");
814  RTABMAP_PARAM(StereoSGBM, SpeckleRange, int, 4, "See cv::StereoSGBM");
815  RTABMAP_PARAM(StereoSGBM, Disp12MaxDiff, int, 1, "See cv::StereoSGBM");
816  RTABMAP_PARAM(StereoSGBM, P1, int, 2, "See cv::StereoSGBM");
817  RTABMAP_PARAM(StereoSGBM, P2, int, 5, "See cv::StereoSGBM");
818 #if CV_MAJOR_VERSION < 3
819  RTABMAP_PARAM(StereoSGBM, Mode, int, 0, "See cv::StereoSGBM");
820 #else
821  RTABMAP_PARAM(StereoSGBM, Mode, int, 2, "See cv::StereoSGBM");
822 #endif
823 
824  // Occupancy Grid
825  RTABMAP_PARAM(Grid, Sensor, int, 1, "Create occupancy grid from selected sensor: 0=laser scan, 1=depth image(s) or 2=both laser scan and depth image(s).");
826  RTABMAP_PARAM(Grid, DepthDecimation, unsigned int, 4, uFormat("[%s=true] Decimation of the depth image before creating cloud.", kGridDepthDecimation().c_str()));
827  RTABMAP_PARAM(Grid, RangeMin, float, 0.0, "Minimum range from sensor.");
828  RTABMAP_PARAM(Grid, RangeMax, float, 5.0, "Maximum range from sensor. 0=inf.");
829  RTABMAP_PARAM_STR(Grid, DepthRoiRatios, "0.0 0.0 0.0 0.0", uFormat("[%s>=1] Region of interest ratios [left, right, top, bottom].", kGridSensor().c_str()));
830  RTABMAP_PARAM(Grid, FootprintLength, float, 0.0, "Footprint length used to filter points over the footprint of the robot.");
831  RTABMAP_PARAM(Grid, FootprintWidth, float, 0.0, "Footprint width used to filter points over the footprint of the robot. Footprint length should be set.");
832  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.");
833  RTABMAP_PARAM(Grid, ScanDecimation, int, 1, uFormat("[%s=0 or 2] Decimation of the laser scan before creating cloud.", kGridSensor().c_str()));
834  RTABMAP_PARAM(Grid, CellSize, float, 0.05, "Resolution of the occupancy grid.");
835  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()));
836  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.");
837  RTABMAP_PARAM(Grid, NormalsSegmentation, bool, true, "Segment ground from obstacles using point normals, otherwise a fast passthrough is used.");
838  RTABMAP_PARAM(Grid, MaxObstacleHeight, float, 0.0, "Maximum obstacles height (0=disabled).");
839  RTABMAP_PARAM(Grid, MinGroundHeight, float, 0.0, "Minimum ground height (0=disabled).");
840  RTABMAP_PARAM(Grid, MaxGroundHeight, float, 0.0, uFormat("Maximum ground height (0=disabled). Should be set if \"%s\" is false.", kGridNormalsSegmentation().c_str()));
841  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()));
842  RTABMAP_PARAM(Grid, NormalK, int, 20, uFormat("[%s=true] K neighbors to compute normals.", kGridNormalsSegmentation().c_str()));
843  RTABMAP_PARAM(Grid, ClusterRadius, float, 0.1, uFormat("[%s=true] Cluster maximum radius.", kGridNormalsSegmentation().c_str()));
844  RTABMAP_PARAM(Grid, MinClusterSize, int, 10, uFormat("[%s=true] Minimum cluster size to project the points.", kGridNormalsSegmentation().c_str()));
845  RTABMAP_PARAM(Grid, FlatObstacleDetected, bool, true, uFormat("[%s=true] Flat obstacles detected.", kGridNormalsSegmentation().c_str()));
846 #ifdef RTABMAP_OCTOMAP
847  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 0.", kGridSensor().c_str()));
848 #else
849  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 0.", kGridSensor().c_str()));
850 #endif
851  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()));
852  RTABMAP_PARAM(Grid, NoiseFilteringRadius, float, 0.0, "Noise filtering radius (0=disabled). Done after segmentation.");
853  RTABMAP_PARAM(Grid, NoiseFilteringMinNeighbors, int, 5, "Noise filtering minimum neighbors.");
854  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()));
855  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()));
856  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.");
857  RTABMAP_PARAM(GridGlobal, FootprintRadius, float, 0.0, "Footprint radius (m) used to clear all obstacles under the graph.");
858  RTABMAP_PARAM(GridGlobal, MinSize, float, 0.0, "Minimum map size (m).");
859  RTABMAP_PARAM(GridGlobal, Eroded, bool, false, "Erode obstacle cells.");
860  RTABMAP_PARAM(GridGlobal, MaxNodes, int, 0, "Maximum nodes assembled in the map starting from the last node (0=unlimited).");
861  RTABMAP_PARAM(GridGlobal, AltitudeDelta, float, 0, "Assemble only nodes that have the same altitude of +-delta meters of the current pose (0=disabled). This is used to generate 2D occupancy grid based on the current altitude (e.g., multi-floor building).");
862  RTABMAP_PARAM(GridGlobal, OccupancyThr, float, 0.5, "Occupancy threshold (value between 0 and 1).");
863  RTABMAP_PARAM(GridGlobal, ProbHit, float, 0.7, "Probability of a hit (value between 0.5 and 1).");
864  RTABMAP_PARAM(GridGlobal, ProbMiss, float, 0.4, "Probability of a miss (value between 0 and 0.5).");
865  RTABMAP_PARAM(GridGlobal, ProbClampingMin, float, 0.1192, "Probability clamping minimum (value between 0 and 1).");
866  RTABMAP_PARAM(GridGlobal, ProbClampingMax, float, 0.971, "Probability clamping maximum (value between 0 and 1).");
867  RTABMAP_PARAM(GridGlobal, FloodFillDepth, unsigned int, 0, "Flood fill filter (0=disabled), used to remove empty cells outside the map. The flood fill is done at the specified depth (between 1 and 16) of the OctoMap.");
868 
869  RTABMAP_PARAM(Marker, Dictionary, int, 0, "Dictionary to use: DICT_ARUCO_4X4_50=0, DICT_ARUCO_4X4_100=1, DICT_ARUCO_4X4_250=2, DICT_ARUCO_4X4_1000=3, DICT_ARUCO_5X5_50=4, DICT_ARUCO_5X5_100=5, DICT_ARUCO_5X5_250=6, DICT_ARUCO_5X5_1000=7, DICT_ARUCO_6X6_50=8, DICT_ARUCO_6X6_100=9, DICT_ARUCO_6X6_250=10, DICT_ARUCO_6X6_1000=11, DICT_ARUCO_7X7_50=12, DICT_ARUCO_7X7_100=13, DICT_ARUCO_7X7_250=14, DICT_ARUCO_7X7_1000=15, DICT_ARUCO_ORIGINAL = 16, DICT_APRILTAG_16h5=17, DICT_APRILTAG_25h9=18, DICT_APRILTAG_36h10=19, DICT_APRILTAG_36h11=20");
870  RTABMAP_PARAM(Marker, Length, float, 0, "The length (m) of the markers' side. 0 means automatic marker length estimation using the depth image (the camera should look at the marker perpendicularly for initialization).");
871  RTABMAP_PARAM(Marker, MaxDepthError, float, 0.01, uFormat("Maximum depth error between all corners of a marker when estimating the marker length (when %s is 0). The smaller it is, the more perpendicular the camera should be toward the marker to initialize the length.", kMarkerLength().c_str()));
872  RTABMAP_PARAM(Marker, VarianceLinear, float, 0.001, "Linear variance to set on marker detections.");
873  RTABMAP_PARAM(Marker, VarianceAngular, float, 0.01, "Angular variance to set on marker detections. Set to >=9999 to use only position (xyz) constraint in graph optimization.");
874  RTABMAP_PARAM(Marker, CornerRefinementMethod, int, 0, "Corner refinement method (0: None, 1: Subpixel, 2:contour, 3: AprilTag2). For OpenCV <3.3.0, this is \"doCornerRefinement\" parameter: set 0 for false and 1 for true.");
875  RTABMAP_PARAM(Marker, MaxRange, float, 0.0, "Maximum range in which markers will be detected. <=0 for unlimited range.");
876  RTABMAP_PARAM(Marker, MinRange, float, 0.0, "Miniminum range in which markers will be detected. <=0 for unlimited range.");
877  RTABMAP_PARAM_STR(Marker, Priors, "", "World prior locations of the markers. The map will be transformed in marker's world frame when a tag is detected. Format is the marker's ID followed by its position (angles in rad), markers are separated by vertical line (\"id1 x y z roll pitch yaw|id2 x y z roll pitch yaw\"). Example: \"1 0 0 1 0 0 0|2 1 0 1 0 0 1.57\" (marker 2 is 1 meter forward than marker 1 with 90 deg yaw rotation).");
878  RTABMAP_PARAM(Marker, PriorsVarianceLinear, float, 0.001, "Linear variance to set on marker priors.");
879  RTABMAP_PARAM(Marker, PriorsVarianceAngular, float, 0.001, "Angular variance to set on marker priors.");
880 
881  RTABMAP_PARAM(ImuFilter, MadgwickGain, double, 0.1, "Gain of the filter. Higher values lead to faster convergence but more noise. Lower values lead to slower convergence but smoother signal, belongs in [0, 1].");
882  RTABMAP_PARAM(ImuFilter, MadgwickZeta, double, 0.0, "Gyro drift gain (approx. rad/s), belongs in [-1, 1].");
883 
884  RTABMAP_PARAM(ImuFilter, ComplementaryGainAcc, double, 0.01, "Gain parameter for the complementary filter, belongs in [0, 1].");
885  RTABMAP_PARAM(ImuFilter, ComplementaryBiasAlpha, double, 0.01, "Bias estimation gain parameter, belongs in [0, 1].");
886  RTABMAP_PARAM(ImuFilter, ComplementaryDoBiasEstimation, bool, true, "Parameter whether to do bias estimation or not.");
887  RTABMAP_PARAM(ImuFilter, ComplementaryDoAdpativeGain, bool, true, "Parameter whether to do adaptive gain or not.");
888 
889 public:
890  virtual ~Parameters();
891 
897  {
898  return parameters_;
899  }
900 
905  static std::string getType(const std::string & paramKey);
906 
911  static std::string getDescription(const std::string & paramKey);
912 
913  static bool parse(const ParametersMap & parameters, const std::string & key, bool & value);
914  static bool parse(const ParametersMap & parameters, const std::string & key, int & value);
915  static bool parse(const ParametersMap & parameters, const std::string & key, unsigned int & value);
916  static bool parse(const ParametersMap & parameters, const std::string & key, float & value);
917  static bool parse(const ParametersMap & parameters, const std::string & key, double & value);
918  static bool parse(const ParametersMap & parameters, const std::string & key, std::string & value);
919  static void parse(const ParametersMap & parameters, ParametersMap & parametersOut);
920 
921  static const char * showUsage();
922  static ParametersMap parseArguments(int argc, char * argv[], bool onlyParameters = false);
923 
924  static std::string getVersion();
925  static std::string getDefaultDatabaseName();
926 
927  static std::string serialize(const ParametersMap & parameters);
928  static ParametersMap deserialize(const std::string & parameters);
929 
930  static bool isFeatureParameter(const std::string & param);
931  static ParametersMap getDefaultOdometryParameters(bool stereo = false, bool vis = true, bool icp = false);
932  static ParametersMap getDefaultParameters(const std::string & group);
937  static ParametersMap filterParameters(const ParametersMap & parameters, const std::string & group, bool remove = false);
938 
939  static void readINI(const std::string & configFile, ParametersMap & parameters, bool modifiedOnly = false);
940  static void readINIStr(const std::string & configContent, ParametersMap & parameters, bool modifiedOnly = false);
941  static void writeINI(const std::string & configFile, const ParametersMap & parameters);
942 
947  static const std::map<std::string, std::pair<bool, std::string> > & getRemovedParameters();
948 
952  static const ParametersMap & getBackwardCompatibilityMap();
953 
954  static std::string createDefaultWorkingDirectory();
955 
956 private:
957  Parameters();
958 
959 private:
964 
965  static std::map<std::string, std::pair<bool, std::string> > removedParameters_;
967 };
968 
969 }
970 
971 #endif /* PARAMETERS_H_ */
rtabmap::ParametersPair
std::pair< std::string, std::string > ParametersPair
Definition: Parameters.h:44
rtabmap::StereoSGBM
Definition: StereoSGBM.h:37
rtabmap::Parameters::parameters_
static ParametersMap parameters_
Definition: Parameters.h:960
D
MatrixXcd D
rtabmap::FAST
Definition: Features2d.h:334
Model
noiseModel::Isotropic::shared_ptr Model
rtabmap::Optimizer
Definition: Optimizer.h:61
Mem
Definition: sqlite3.c:13566
rtabmap::Stereo
Definition: Stereo.h:38
rtabmap::SURF
Definition: Features2d.h:252
rtabmap::BRISK
Definition: Features2d.h:513
rtabmap::StereoBM
Definition: StereoBM.h:37
rtabmap::Parameters::parametersType_
static ParametersMap parametersType_
Definition: Parameters.h:961
rtabmap::ParametersMap
std::map< std::string, std::string > ParametersMap
Definition: Parameters.h:43
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:896
eigen_extensions::deserialize
void deserialize(std::istream &strm, Eigen::Matrix< S, T, U > *mat)
Definition: eigen_extensions.h:78
rtabmap::PyDetector
Definition: PyDetector.h:20
UConversion.h
Some conversion functions.
rtabmap::SIFT
Definition: Features2d.h:279
g2o
Definition: edge_se3_xyzprior.h:34
eigen_extensions::serialize
void serialize(const Eigen::Matrix< S, T, U > &mat, std::ostream &strm)
Definition: eigen_extensions.h:66
rtabmap_netvlad.argv
argv
Definition: rtabmap_netvlad.py:15
rtabmap::SuperPoint
Definition: SuperPoint.h:22
rtabmap::Parameters
Definition: Parameters.h:170
Db
Definition: sqlite3.c:10055
uFormat
std::string UTILITE_EXPORT uFormat(const char *fmt,...)
Definition: UConversion.cpp:365
K
K
showUsage
void showUsage()
Definition: examples/BOWMapping/main.cpp:34
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
parse
def parse(input_path, output_path, quiet=False, generate_xml_flag=True)
RTABMAP_PARAM
#define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION)
Definition: Parameters.h:64
rtabmap::GFTT
Definition: Features2d.h:411
rtabmap::PyDescriptor
Definition: PyDescriptor.h:16
rtabmap::Parameters::descriptions_
static ParametersMap descriptions_
Definition: Parameters.h:962
c_str
const char * c_str(Args &&...args)
rtabmap::Parameters::backwardCompatibilityMap_
static ParametersMap backwardCompatibilityMap_
Definition: Parameters.h:966
icp
rtabmap::util2d::NMS
void RTABMAP_CORE_EXPORT NMS(const std::vector< cv::KeyPoint > &ptsIn, const cv::Mat &descriptorsIn, std::vector< cv::KeyPoint > &ptsOut, cv::Mat &descriptorsOut, int border, int dist_thresh, int img_width, int img_height)
Definition: util2d.cpp:2096
rtabmap::util2d::SSC
std::vector< int > RTABMAP_CORE_EXPORT SSC(const std::vector< cv::KeyPoint > &keypoints, int maxKeypoints, float tolerance, int cols, int rows)
Definition: util2d.cpp:2205
rtabmap::Parameters::removedParameters_
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
Definition: Parameters.h:965
rtabmap::Rtabmap
Definition: Rtabmap.h:54
rtabmap::ORB
Definition: Features2d.h:303
Length
Length
RTABMAP_PARAM_STR
#define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION)
Definition: Parameters.h:98
rtabmap
Definition: CameraARCore.cpp:35
rtabmap::PyMatcher
Definition: PyMatcher.h:19
rtabmap::KAZE
Definition: Features2d.h:535
rtabmap::Parameters::instance_
static Parameters instance_
Definition: Parameters.h:963


rtabmap
Author(s): Mathieu Labbe
autogenerated on Thu Jul 25 2024 02:50:14