32 #include "rtabmap/core/rtabmap_core_export.h"
33 #include "rtabmap/core/Version.h"
35 #include <opencv2/core/version.hpp>
36 #include <opencv2/opencv_modules.hpp>
64 #define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION) \
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);} \
70 class Dummy##PREFIX##NAME { \
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));} \
76 Dummy##PREFIX##NAME dummy##PREFIX##NAME
98 #define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION) \
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");} \
104 class Dummy##PREFIX##NAME { \
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));} \
110 Dummy##PREFIX##NAME dummy##PREFIX##NAME
131 #define RTABMAP_PARAM_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
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);} \
137 class Dummy##PREFIX##NAME { \
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));} \
143 Dummy##PREFIX##NAME dummy##PREFIX##NAME
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.");
184 RTABMAP_PARAM(
Rtabmap, CreateIntermediateNodes,
bool,
false,
uFormat(
"Create intermediate nodes between loop closure detection. Only used when %s>0.", kRtabmapDetectionRate().
c_str()));
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.");
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()));
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)");
203 RTABMAP_PARAM(
Mem, RehearsalSimilarity,
float, 0.6,
"Rehearsal similarity.");
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_STR(
Mem, DepthCompressionFormat,
".rvl",
"Depth image compression format for 16UC1 depth type. It should be \".png\" or \".rvl\". If depth type is 32FC1, \".png\" is used.");
214 RTABMAP_PARAM(
Mem, IncrementalMemory,
bool,
true,
"SLAM mode, otherwise it is Localization mode.");
215 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());
216 RTABMAP_PARAM(
Mem, ReduceGraph,
bool,
false,
"Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set).");
217 RTABMAP_PARAM(
Mem, RecentWmRatio,
float, 0.2,
"Ratio of locations after the last loop closure in WM that cannot be transferred.");
218 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.");
219 RTABMAP_PARAM(
Mem, RehearsalIdUpdatedToNewOne,
bool,
false,
"On merge, update to new id. When false, no copy.");
220 RTABMAP_PARAM(
Mem, RehearsalWeightIgnoredWhileMoving,
bool,
false,
"When the robot is moving, weights are not updated on rehearsal.");
221 RTABMAP_PARAM(
Mem, GenerateIds,
bool,
true,
"True=Generate location IDs, False=use input image IDs.");
222 RTABMAP_PARAM(
Mem, BadSignaturesIgnored,
bool,
false,
"Bad signatures are ignored.");
223 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.");
224 RTABMAP_PARAM(
Mem, DepthAsMask,
bool,
true,
"Use depth image as mask when extracting features for vocabulary.");
225 RTABMAP_PARAM(
Mem, DepthMaskFloorThr,
float, 0.0,
uFormat(
"Filter floor from depth mask below specified threshold (m) before extracting features. 0 means disabled, negative means remove all objects above the floor threshold instead. Ignored if %s is false.", kMemDepthAsMask().
c_str()));
226 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()));
227 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()));
228 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()));
229 RTABMAP_PARAM(
Mem, CompressionParallelized,
bool,
true,
"Compression of sensor data is multi-threaded.");
230 RTABMAP_PARAM(
Mem, LaserScanDownsampleStepSize,
int, 1,
"If > 1, downsample the laser scans when creating a signature.");
231 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()));
232 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.");
233 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.");
234 RTABMAP_PARAM(
Mem, UseOdomFeatures,
bool,
true,
"Use odometry features instead of regenerating them.");
235 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()));
236 RTABMAP_PARAM(
Mem, CovOffDiagIgnored,
bool,
true,
"Ignore off diagonal values of the covariance matrix.");
237 RTABMAP_PARAM(
Mem, GlobalDescriptorStrategy,
int, 0,
"Extract global descriptor from sensor data. 0=disabled, 1=PyDescriptor");
238 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.");
241 RTABMAP_PARAM(Kp, NNStrategy,
int, 1,
"kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
243 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()));
244 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()));
245 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()));
246 RTABMAP_PARAM(Kp, MaxDepth,
float, 0,
"Filter extracted keypoints by depth (0=inf).");
247 RTABMAP_PARAM(Kp, MinDepth,
float, 0,
"Filter extracted keypoints by depth.");
248 RTABMAP_PARAM(Kp, MaxFeatures,
int, 500,
"Maximum features extracted from the images (0 means not bounded, <0 means no extraction).");
249 RTABMAP_PARAM(Kp,
SSC,
bool,
false,
"If true, SSC (Suppression via Square Covering) is applied to limit keypoints.");
250 RTABMAP_PARAM(Kp, BadSignRatio,
float, 0.5,
"Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).");
251 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.)");
252 #if CV_MAJOR_VERSION > 2 && !defined(HAVE_OPENCV_XFEATURES2D)
254 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");
256 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");
258 RTABMAP_PARAM(Kp, TfIdfLikelihoodUsed,
bool,
true,
"Use of the td-idf strategy to compute the likelihood.");
259 RTABMAP_PARAM(Kp, Parallelized,
bool,
true,
"If the dictionary update and signature creation were parallelized.");
260 RTABMAP_PARAM_STR(Kp, RoiRatios,
"0.0 0.0 0.0 0.0",
"Region of interest ratios [left, right, top, bottom].");
261 RTABMAP_PARAM_STR(Kp, DictionaryPath,
"",
"Path of the pre-computed dictionary");
262 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).");
263 RTABMAP_PARAM(Kp, SubPixWinSize,
int, 3,
"See cv::cornerSubPix().");
264 RTABMAP_PARAM(Kp, SubPixIterations,
int, 0,
"See cv::cornerSubPix(). 0 disables sub pixel refining.");
265 RTABMAP_PARAM(Kp, SubPixEps,
double, 0.02,
"See cv::cornerSubPix().");
266 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()));
267 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()));
270 RTABMAP_PARAM(DbSqlite3, InMemory,
bool,
false,
"Using database in the memory instead of a file on the hard disk.");
271 RTABMAP_PARAM(DbSqlite3, CacheSize,
unsigned int, 10000,
"Sqlite cache size (default is 2000).");
272 RTABMAP_PARAM(DbSqlite3, JournalMode,
int, 3,
"0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")");
273 RTABMAP_PARAM(DbSqlite3, Synchronous,
int, 0,
"0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")");
274 RTABMAP_PARAM(DbSqlite3, TempStore,
int, 2,
"0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")");
275 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).");
278 RTABMAP_PARAM(
SURF, Extended,
bool,
false,
"Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
279 RTABMAP_PARAM(
SURF, HessianThreshold,
float, 500,
"Threshold for hessian keypoint detector used in SURF.");
280 RTABMAP_PARAM(
SURF, Octaves,
int, 4,
"Number of pyramid octaves the keypoint detector will use.");
281 RTABMAP_PARAM(
SURF, OctaveLayers,
int, 2,
"Number of octave layers within each octave.");
282 RTABMAP_PARAM(
SURF, Upright,
bool,
false,
"Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
283 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.");
286 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. Not used by CudaSift, the number of octaves is still computed automatically.");
287 RTABMAP_PARAM(
SIFT, ContrastThreshold,
double, 0.04,
uFormat(
"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. Not used by CudaSift (see %s instead).", kSIFTGaussianThreshold().
c_str()));
288 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).");
289 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.");
290 RTABMAP_PARAM(
SIFT, PreciseUpscale,
bool,
false,
"Whether to enable precise upscaling in the scale pyramid (OpenCV >= 4.8).");
291 RTABMAP_PARAM(
SIFT, RootSIFT,
bool,
false,
"Apply RootSIFT normalization of the descriptors.");
292 RTABMAP_PARAM(
SIFT, Gpu,
bool,
false,
"CudaSift: Use GPU version of SIFT. This option is enabled only if RTAB-Map is built with CudaSift dependency and GPUs are detected.");
293 RTABMAP_PARAM(
SIFT, GaussianThreshold,
float, 2.0,
"CudaSift: Threshold on difference of Gaussians for feature pruning. The higher the threshold, the less features are produced by the detector.");
294 RTABMAP_PARAM(
SIFT, Upscale,
bool,
false,
"CudaSift: Whether to enable upscaling.");
296 RTABMAP_PARAM(BRIEF, Bytes,
int, 32,
"Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
298 RTABMAP_PARAM(
FAST, Threshold,
int, 20,
"Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
299 RTABMAP_PARAM(
FAST, NonmaxSuppression,
bool,
true,
"If true, non-maximum suppression is applied to detected corners (keypoints).");
300 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.");
302 RTABMAP_PARAM(
FAST, MinThreshold,
int, 7,
"Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
303 RTABMAP_PARAM(
FAST, MaxThreshold,
int, 200,
"Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
304 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.");
305 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.");
306 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.");
313 RTABMAP_PARAM(
GFTT, Gpu,
bool,
false,
"GPU-GFTT: Use GPU version of GFTT. This option is enabled only if OpenCV>=3 is built with CUDA and GPUs are detected.");
315 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.");
316 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).");
317 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.");
318 RTABMAP_PARAM(
ORB, FirstLevel,
int, 0,
"It should be 0 in the current implementation.");
319 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).");
320 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.");
321 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.");
322 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.");
324 RTABMAP_PARAM(FREAK, OrientationNormalized,
bool,
true,
"Enable orientation normalization.");
325 RTABMAP_PARAM(FREAK, ScaleNormalized,
bool,
true,
"Enable scale normalization.");
326 RTABMAP_PARAM(FREAK, PatternScale,
float, 22,
"Scaling of the description pattern.");
327 RTABMAP_PARAM(FREAK, NOctaves,
int, 4,
"Number of octaves covered by the detected keypoints.");
330 RTABMAP_PARAM(
BRISK, Octaves,
int, 3,
"Detection octaves. Use 0 to do single scale.");
331 RTABMAP_PARAM(
BRISK, PatternScale,
float, 1,
"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
333 RTABMAP_PARAM(
KAZE, Extended,
bool,
false,
"Set to enable extraction of extended (128-byte) descriptor.");
334 RTABMAP_PARAM(
KAZE, Upright,
bool,
false,
"Set to enable use of upright descriptors (non rotation-invariant).");
335 RTABMAP_PARAM(
KAZE, Threshold,
float, 0.001,
"Detector response threshold to accept keypoint.");
337 RTABMAP_PARAM(
KAZE, NOctaveLayers,
int, 4,
"Default number of sublevels per scale level.");
338 RTABMAP_PARAM(
KAZE, Diffusivity,
int, 1,
"Diffusivity type: 0=DIFF_PM_G1, 1=DIFF_PM_G2, 2=DIFF_WEICKERT or 3=DIFF_CHARBONNIER.");
344 RTABMAP_PARAM(
SuperPoint, Cuda,
bool,
true,
"Use Cuda device for Torch, otherwise CPU device is used by default.");
346 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.");
350 RTABMAP_PARAM(Bayes, VirtualPlacePriorThr,
float, 0.9,
"Virtual place prior");
351 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, ...}.");
352 RTABMAP_PARAM(Bayes, FullPredictionUpdate,
bool,
false,
"Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).");
355 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()));
356 RTABMAP_PARAM(VhEp, MatchCountMin,
int, 8,
"Minimum of matching visual words pairs to accept the loop hypothesis.");
357 RTABMAP_PARAM(VhEp, RansacParam1,
float, 3,
"Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier.");
358 RTABMAP_PARAM(VhEp, RansacParam2,
float, 0.99,
"Fundamental matrix (see cvFindFundamentalMat()): Performance of RANSAC.");
361 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.");
362 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.");
363 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.");
364 RTABMAP_PARAM(RGBD, LinearSpeedUpdate,
float, 0.0,
"Maximum linear speed (m/s) to update the map (0 means not limit).");
365 RTABMAP_PARAM(RGBD, AngularSpeedUpdate,
float, 0.0,
"Maximum angular speed (rad/s) to update the map (0 means not limit).");
366 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()));
367 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).");
368 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).");
369 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()));
370 RTABMAP_PARAM(RGBD, MaxLoopClosureDistance,
float, 0.0,
"Reject loop closures/localizations if the distance from the map is over this distance (0=disabled).");
371 RTABMAP_PARAM(RGBD, ForceOdom3DoF,
bool,
true,
uFormat(
"Force odometry pose to be 3DoF if %s=true.", kRegForce3DoF().
c_str()));
372 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()));
373 RTABMAP_PARAM(RGBD, GoalReachedRadius,
float, 0.5,
"Goal reached radius (m).");
374 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.");
375 RTABMAP_PARAM(RGBD, PlanLinearVelocity,
float, 0,
"Linear velocity (m/sec) used to compute path weights.");
376 RTABMAP_PARAM(RGBD, PlanAngularVelocity,
float, 0,
"Angular velocity (rad/sec) used to compute path weights.");
377 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:#\".");
378 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).");
379 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.");
380 RTABMAP_PARAM(RGBD, LocalImmunizationRatio,
float, 0.25,
"Ratio of working memory for which local nodes are immunized from transfer.");
381 RTABMAP_PARAM(RGBD, ScanMatchingIdsSavedInLinks,
bool,
true,
"Save scan matching IDs from one-to-many proximity detection in link's user data.");
382 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()));
383 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()));
384 RTABMAP_PARAM(RGBD, LoopClosureReextractFeatures,
bool,
false,
"Extract features even if there are some already in the nodes. Raw features are not saved in database.");
385 RTABMAP_PARAM(RGBD, LocalBundleOnLoopClosure,
bool,
false,
"Do local bundle adjustment with neighborhood of the loop closure.");
386 RTABMAP_PARAM(RGBD, InvertedReg,
bool,
false,
"On loop closure, do registration from the target to reference instead of reference to target.");
387 RTABMAP_PARAM(RGBD, CreateOccupancyGrid,
bool,
false,
"Create local occupancy grid maps. See \"Grid\" group for parameters.");
388 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.");
389 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.");
390 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()));
391 RTABMAP_PARAM(RGBD, LocalizationSmoothing,
bool,
true,
uFormat(
"Adjust localization constraints based on optimized odometry cache poses (when %s>0).", kRGBDMaxOdomCacheSize().
c_str()));
392 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()));
395 RTABMAP_PARAM(RGBD, ProximityByTime,
bool,
false,
"Detection over all locations in STM.");
396 RTABMAP_PARAM(RGBD, ProximityBySpace,
bool,
true,
"Detection over locations (in Working Memory) near in space.");
397 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.");
398 RTABMAP_PARAM(RGBD, ProximityMaxPaths,
int, 3,
"Maximum paths compared (from the most recent) for proximity detection. 0 means no limit.");
399 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.");
400 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).");
401 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.");
402 RTABMAP_PARAM(RGBD, ProximityAngle,
float, 45,
"Maximum angle (degrees) for one-to-one proximity detection.");
403 RTABMAP_PARAM(RGBD, ProximityOdomGuess,
bool,
false,
"Use odometry as motion guess for one-to-one proximity detection.");
404 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()));
405 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()));
409 RTABMAP_PARAM(
Optimizer, Strategy,
int, 2,
"Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
411 RTABMAP_PARAM(
Optimizer, Epsilon,
double, 0.00001,
"Stop optimizing when the error improvement is less than this value.");
414 RTABMAP_PARAM(
Optimizer, Strategy,
int, 1,
"Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
416 RTABMAP_PARAM(
Optimizer, Epsilon,
double, 0.0,
"Stop optimizing when the error improvement is less than this value.");
419 RTABMAP_PARAM(
Optimizer, Strategy,
int, 3,
"Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
421 RTABMAP_PARAM(
Optimizer, Epsilon,
double, 0.000001,
"Stop optimizing when the error improvement is less than this value.");
423 RTABMAP_PARAM(
Optimizer, Strategy,
int, 0,
"Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.");
425 RTABMAP_PARAM(
Optimizer, Epsilon,
double, 0.00001,
"Stop optimizing when the error improvement is less than this value.");
429 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.");
430 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()));
431 RTABMAP_PARAM(
Optimizer, PriorsIgnored,
bool,
true,
"Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this.");
432 RTABMAP_PARAM(
Optimizer, LandmarksIgnored,
bool,
false,
"Ignore landmark constraints while optimizing. Currently only g2o and gtsam optimization supports this.");
433 #if defined(RTABMAP_G2O) || defined(RTABMAP_GTSAM)
434 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()));
436 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()));
439 #ifdef RTABMAP_ORB_SLAM
445 RTABMAP_PARAM(
g2o, PixelVariance,
double, 1.0,
"Pixel variance used for bundle adjustment.");
446 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.");
447 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.");
450 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()));
451 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.");
452 RTABMAP_PARAM(GTSAM, IncRelinearizeSkip,
int, 1,
"Only relinearize any variables every X calls to ISAM2::update(). See GTSAM::ISAM2 doc for more info.");
455 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");
456 RTABMAP_PARAM(Odom, ResetCountdown,
int, 0,
"Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).");
457 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)).");
458 RTABMAP_PARAM(Odom, FillInfoData,
bool,
true,
"Fill info with data (inliers/outliers features).");
459 RTABMAP_PARAM(Odom, ImageBufferSize,
unsigned int, 1,
"Data buffer size (0 min inf).");
460 RTABMAP_PARAM(Odom, FilteringStrategy,
int, 0,
"0=No filtering 1=Kalman filtering 2=Particle filtering. This filter is used to smooth the odometry output.");
461 RTABMAP_PARAM(Odom, ParticleSize,
unsigned int, 400,
"Number of particles of the filter.");
462 RTABMAP_PARAM(Odom, ParticleNoiseT,
float, 0.002,
"Noise (m) of translation components (x,y,z).");
463 RTABMAP_PARAM(Odom, ParticleLambdaT,
float, 100,
"Lambda of translation components (x,y,z).");
464 RTABMAP_PARAM(Odom, ParticleNoiseR,
float, 0.002,
"Noise (rad) of rotational components (roll,pitch,yaw).");
465 RTABMAP_PARAM(Odom, ParticleLambdaR,
float, 100,
"Lambda of rotational components (roll,pitch,yaw).");
466 RTABMAP_PARAM(Odom, KalmanProcessNoise,
float, 0.001,
"Process noise covariance value.");
467 RTABMAP_PARAM(Odom, KalmanMeasurementNoise,
float, 0.01,
"Process measurement covariance value.");
468 RTABMAP_PARAM(Odom, GuessMotion,
bool,
true,
"Guess next transformation from the last motion computed.");
469 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()));
470 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.");
471 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.");
472 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.");
473 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()));
474 RTABMAP_PARAM(Odom, AlignWithGround,
bool,
false,
"Align odometry with the ground on initialization.");
475 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).");
478 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.");
479 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.");
480 RTABMAP_PARAM(OdomF2M, ScanMaxSize,
int, 2000,
"[Geometry] Maximum local scan map size.");
481 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.");
482 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());
483 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.");
484 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.");
485 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
486 RTABMAP_PARAM(OdomF2M, BundleAdjustment,
int, 1,
"Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
488 RTABMAP_PARAM(OdomF2M, BundleAdjustment,
int, 0,
"Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
490 RTABMAP_PARAM(OdomF2M, BundleAdjustmentMaxFrames,
int, 10,
"Maximum frames used for bundle adjustment (0=inf or all current frames in the local map).");
493 RTABMAP_PARAM(OdomMono, InitMinFlow,
float, 100,
"Minimum optical flow required for the initialization step.");
494 RTABMAP_PARAM(OdomMono, InitMinTranslation,
float, 0.1,
"Minimum translation required for the initialization step.");
495 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.");
496 RTABMAP_PARAM(OdomMono, MaxVariance,
float, 0.01,
"Maximum variance to add new points to local map.");
499 RTABMAP_PARAM(OdomFovis, FeatureWindowSize,
int, 9,
"The size of the n x n image patch surrounding each feature, used for keypoint matching.");
500 RTABMAP_PARAM(OdomFovis, MaxPyramidLevel,
int, 3,
"The maximum Gaussian pyramid level to process the image at. Pyramid level 1 corresponds to the original image.");
501 RTABMAP_PARAM(OdomFovis, MinPyramidLevel,
int, 0,
"The minimum pyramid level.");
502 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.");
503 RTABMAP_PARAM(OdomFovis, FastThreshold,
int, 20,
"FAST threshold.");
504 RTABMAP_PARAM(OdomFovis, UseAdaptiveThreshold,
bool,
true,
"Use FAST adaptive threshold.");
505 RTABMAP_PARAM(OdomFovis, FastThresholdAdaptiveGain,
double, 0.005,
"FAST threshold adaptive gain.");
506 RTABMAP_PARAM(OdomFovis, UseHomographyInitialization,
bool,
true,
"Use homography initialization.");
511 RTABMAP_PARAM(OdomFovis, MaxKeypointsPerBucket,
int, 25,
"");
512 RTABMAP_PARAM(OdomFovis, UseImageNormalization,
bool,
false,
"");
514 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.");
515 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.");
516 RTABMAP_PARAM(OdomFovis, MinFeaturesForEstimate,
int, 20,
"Minimum number of features in the inlier set for the motion estimate to be considered valid.");
517 RTABMAP_PARAM(OdomFovis, MaxMeanReprojectionError,
double, 10.0,
"Maximum mean reprojection error over the inlier feature matches for the motion estimate to be considered valid.");
518 RTABMAP_PARAM(OdomFovis, UseSubpixelRefinement,
bool,
true,
"Specifies whether or not to refine feature matches to subpixel resolution.");
519 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.");
520 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.");
522 RTABMAP_PARAM(OdomFovis, StereoRequireMutualMatch,
bool,
true,
"");
523 RTABMAP_PARAM(OdomFovis, StereoMaxDistEpipolarLine,
double, 1.5,
"");
524 RTABMAP_PARAM(OdomFovis, StereoMaxRefinementDisplacement,
double, 1.0,
"");
528 RTABMAP_PARAM(OdomViso2, RansacIters,
int, 200,
"Number of RANSAC iterations.");
529 RTABMAP_PARAM(OdomViso2, InlierThreshold,
double, 2.0,
"Fundamental matrix inlier threshold.");
530 RTABMAP_PARAM(OdomViso2, Reweighting,
bool,
true,
"Lower border weights (more robust to calibration errors).");
531 RTABMAP_PARAM(OdomViso2, MatchNmsN,
int, 3,
"Non-max-suppression: min. distance between maxima (in pixels).");
532 RTABMAP_PARAM(OdomViso2, MatchNmsTau,
int, 50,
"Non-max-suppression: interest point peakiness threshold.");
533 RTABMAP_PARAM(OdomViso2, MatchBinsize,
int, 50,
"Matching bin width/height (affects efficiency only).");
534 RTABMAP_PARAM(OdomViso2, MatchRadius,
int, 200,
"Matching radius (du/dv in pixels).");
535 RTABMAP_PARAM(OdomViso2, MatchDispTolerance,
int, 2,
"Disparity tolerance for stereo matches (in pixels).");
536 RTABMAP_PARAM(OdomViso2, MatchOutlierDispTolerance,
int, 5,
"Outlier removal: disparity tolerance (in pixels).");
537 RTABMAP_PARAM(OdomViso2, MatchOutlierFlowTolerance,
int, 5,
"Outlier removal: flow tolerance (in pixels).");
538 RTABMAP_PARAM(OdomViso2, MatchMultiStage,
bool,
true,
"Multistage matching (denser and faster).");
539 RTABMAP_PARAM(OdomViso2, MatchHalfResolution,
bool,
true,
"Match at half resolution, refine at full resolution.");
540 RTABMAP_PARAM(OdomViso2, MatchRefinement,
int, 1,
"Refinement (0=none,1=pixel,2=subpixel).");
541 RTABMAP_PARAM(OdomViso2, BucketMaxFeatures,
int, 2,
"Maximal number of features per bucket.");
542 RTABMAP_PARAM(OdomViso2, BucketWidth,
double, 50,
"Width of bucket.");
543 RTABMAP_PARAM(OdomViso2, BucketHeight,
double, 50,
"Height of bucket.");
547 RTABMAP_PARAM(OdomORBSLAM, Bf,
double, 0.076,
"Fake IR projector baseline (m) used only when stereo is not used.");
548 RTABMAP_PARAM(OdomORBSLAM, ThDepth,
double, 40.0,
"Close/Far threshold. Baseline times.");
549 RTABMAP_PARAM(OdomORBSLAM, Fps,
float, 0.0,
"Camera FPS (0 to estimate from input data).");
550 RTABMAP_PARAM(OdomORBSLAM, MaxFeatures,
int, 1000,
"Maximum ORB features extracted per frame.");
551 RTABMAP_PARAM(OdomORBSLAM, MapSize,
int, 3000,
"Maximum size of the feature map (0 means infinite). Only supported with ORB_SLAM2.");
552 RTABMAP_PARAM(OdomORBSLAM, Inertial,
bool,
false,
"Enable IMU. Only supported with ORB_SLAM3.");
553 RTABMAP_PARAM(OdomORBSLAM, GyroNoise,
double, 0.01,
"IMU gyroscope \"white noise\".");
554 RTABMAP_PARAM(OdomORBSLAM, AccNoise,
double, 0.1,
"IMU accelerometer \"white noise\".");
555 RTABMAP_PARAM(OdomORBSLAM, GyroWalk,
double, 0.000001,
"IMU gyroscope \"random walk\".");
556 RTABMAP_PARAM(OdomORBSLAM, AccWalk,
double, 0.0001,
"IMU accelerometer \"random walk\".");
557 RTABMAP_PARAM(OdomORBSLAM, SamplingRate,
double, 0,
"IMU sampling rate (0 to estimate from input data).");
564 RTABMAP_PARAM(OdomLOAM, Sensor,
int, 2,
"Velodyne sensor: 0=VLP-16, 1=HDL-32, 2=HDL-64E");
565 RTABMAP_PARAM(OdomLOAM, ScanPeriod,
float, 0.1,
"Scan period (s)");
566 RTABMAP_PARAM(OdomLOAM, Resolution,
float, 0.2,
"Map resolution");
567 RTABMAP_PARAM(OdomLOAM, LinVar,
float, 0.01,
"Linear output variance.");
568 RTABMAP_PARAM(OdomLOAM, AngVar,
float, 0.01,
"Angular output variance.");
569 RTABMAP_PARAM(OdomLOAM, LocalMapping,
bool,
true,
"Local mapping. It adds more time to compute odometry, but accuracy is significantly improved.");
583 RTABMAP_PARAM(OdomMSCKF, PositionStdThreshold,
double, 8.0,
"");
584 RTABMAP_PARAM(OdomMSCKF, RotationThreshold,
double, 0.2618,
"");
585 RTABMAP_PARAM(OdomMSCKF, TranslationThreshold,
double, 0.4,
"");
586 RTABMAP_PARAM(OdomMSCKF, TrackingRateThreshold,
double, 0.5,
"");
587 RTABMAP_PARAM(OdomMSCKF, OptTranslationThreshold,
double, 0,
"");
596 RTABMAP_PARAM(OdomMSCKF, InitCovExRot,
double, 0.00030462,
"");
597 RTABMAP_PARAM(OdomMSCKF, InitCovExTrans,
double, 0.000025,
"");
604 RTABMAP_PARAM(OdomOpenVINS, UseStereo,
bool,
true,
"If we have more than 1 camera, if we should try to track stereo constraints between pairs");
605 RTABMAP_PARAM(OdomOpenVINS, UseKLT,
bool,
true,
"If true we will use KLT, otherwise use a ORB descriptor + robust matching");
606 RTABMAP_PARAM(OdomOpenVINS, NumPts,
int, 200,
"Number of points (per camera) we will extract and try to track");
607 RTABMAP_PARAM(OdomOpenVINS, MinPxDist,
int, 15,
"Eistance between features (features near each other provide less information)");
608 RTABMAP_PARAM(OdomOpenVINS, FiTriangulate1d,
bool,
false,
"If we should perform 1d triangulation instead of 3d");
609 RTABMAP_PARAM(OdomOpenVINS, FiRefineFeatures,
bool,
true,
"If we should perform Levenberg-Marquardt refinement");
610 RTABMAP_PARAM(OdomOpenVINS, FiMaxRuns,
int, 5,
"Max runs for Levenberg-Marquardt");
611 RTABMAP_PARAM(OdomOpenVINS, FiMaxBaseline,
double, 40,
"Max baseline ratio to accept triangulated features");
612 RTABMAP_PARAM(OdomOpenVINS, FiMaxCondNumber,
double, 10000,
"Max condition number of linear triangulation matrix accept triangulated features");
614 RTABMAP_PARAM(OdomOpenVINS, UseFEJ,
bool,
true,
"If first-estimate Jacobians should be used (enable for good consistency)");
615 RTABMAP_PARAM(OdomOpenVINS, Integration,
int, 1,
"0=discrete, 1=rk4, 2=analytical (if rk4 or analytical used then analytical covariance propagation is used)");
616 RTABMAP_PARAM(OdomOpenVINS, CalibCamExtrinsics,
bool,
false,
"Bool to determine whether or not to calibrate imu-to-camera pose");
617 RTABMAP_PARAM(OdomOpenVINS, CalibCamIntrinsics,
bool,
false,
"Bool to determine whether or not to calibrate camera intrinsics");
618 RTABMAP_PARAM(OdomOpenVINS, CalibCamTimeoffset,
bool,
false,
"Bool to determine whether or not to calibrate camera to IMU time offset");
619 RTABMAP_PARAM(OdomOpenVINS, CalibIMUIntrinsics,
bool,
false,
"Bool to determine whether or not to calibrate the IMU intrinsics");
620 RTABMAP_PARAM(OdomOpenVINS, CalibIMUGSensitivity,
bool,
false,
"Bool to determine whether or not to calibrate the Gravity sensitivity");
621 RTABMAP_PARAM(OdomOpenVINS, MaxClones,
int, 11,
"Max clone size of sliding window");
622 RTABMAP_PARAM(OdomOpenVINS, MaxSLAM,
int, 50,
"Max number of estimated SLAM features");
623 RTABMAP_PARAM(OdomOpenVINS, MaxSLAMInUpdate,
int, 25,
"Max number of SLAM features we allow to be included in a single EKF update.");
624 RTABMAP_PARAM(OdomOpenVINS, MaxMSCKFInUpdate,
int, 50,
"Max number of MSCKF features we will use at a given image timestep.");
625 RTABMAP_PARAM(OdomOpenVINS, FeatRepMSCKF,
int, 0,
"What representation our features are in (msckf features)");
626 RTABMAP_PARAM(OdomOpenVINS, FeatRepSLAM,
int, 4,
"What representation our features are in (slam features)");
627 RTABMAP_PARAM(OdomOpenVINS, DtSLAMDelay,
double, 0.0,
"Delay, in seconds, that we should wait from init before we start estimating SLAM features");
628 RTABMAP_PARAM(OdomOpenVINS, GravityMag,
double, 9.81,
"Gravity magnitude in the global frame (i.e. should be 9.81 typically)");
632 RTABMAP_PARAM(OdomOpenVINS, InitWindowTime,
double, 2.0,
"Amount of time we will initialize over (seconds)");
633 RTABMAP_PARAM(OdomOpenVINS, InitIMUThresh,
double, 1.0,
"Variance threshold on our acceleration to be classified as moving");
634 RTABMAP_PARAM(OdomOpenVINS, InitMaxDisparity,
double, 10.0,
"Max disparity to consider the platform stationary (dependent on resolution)");
635 RTABMAP_PARAM(OdomOpenVINS, InitMaxFeatures,
int, 50,
"How many features to track during initialization (saves on computation)");
636 RTABMAP_PARAM(OdomOpenVINS, InitDynUse,
bool,
false,
"If dynamic initialization should be used");
637 RTABMAP_PARAM(OdomOpenVINS, InitDynMLEOptCalib,
bool,
false,
"If we should optimize calibration during intialization (not recommended)");
638 RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxIter,
int, 50,
"How many iterations the MLE refinement should use (zero to skip the MLE)");
639 RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxTime,
double, 0.05,
"How many seconds the MLE should be completed in");
640 RTABMAP_PARAM(OdomOpenVINS, InitDynMLEMaxThreads,
int, 6,
"How many threads the MLE should use");
641 RTABMAP_PARAM(OdomOpenVINS, InitDynNumPose,
int, 6,
"Number of poses to use within our window time (evenly spaced)");
642 RTABMAP_PARAM(OdomOpenVINS, InitDynMinDeg,
double, 10.0,
"Orientation change needed to try to init");
643 RTABMAP_PARAM(OdomOpenVINS, InitDynInflationOri,
double, 10.0,
"What to inflate the recovered q_GtoI covariance by");
644 RTABMAP_PARAM(OdomOpenVINS, InitDynInflationVel,
double, 100.0,
"What to inflate the recovered v_IinG covariance by");
645 RTABMAP_PARAM(OdomOpenVINS, InitDynInflationBg,
double, 10.0,
"What to inflate the recovered bias_g covariance by");
646 RTABMAP_PARAM(OdomOpenVINS, InitDynInflationBa,
double, 100.0,
"What to inflate the recovered bias_a covariance by");
647 RTABMAP_PARAM(OdomOpenVINS, InitDynMinRecCond,
double, 1
e-15,
"Reciprocal condition number thresh for info inversion");
649 RTABMAP_PARAM(OdomOpenVINS, TryZUPT,
bool,
true,
"If we should try to use zero velocity update");
650 RTABMAP_PARAM(OdomOpenVINS, ZUPTChi2Multiplier,
double, 0.0,
"Chi2 multiplier for zero velocity");
651 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)");
652 RTABMAP_PARAM(OdomOpenVINS, ZUPTNoiseMultiplier,
double, 10.0,
"Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)");
653 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)");
654 RTABMAP_PARAM(OdomOpenVINS, ZUPTOnlyAtBeginning,
bool,
false,
"If we should only use the zupt at the very beginning static initialization phase");
656 RTABMAP_PARAM(OdomOpenVINS, AccelerometerNoiseDensity,
double, 0.01,
"[m/s^2/sqrt(Hz)] (accel \"white noise\")");
657 RTABMAP_PARAM(OdomOpenVINS, AccelerometerRandomWalk,
double, 0.001,
"[m/s^3/sqrt(Hz)] (accel bias diffusion)");
658 RTABMAP_PARAM(OdomOpenVINS, GyroscopeNoiseDensity,
double, 0.001,
"[rad/s/sqrt(Hz)] (gyro \"white noise\")");
659 RTABMAP_PARAM(OdomOpenVINS, GyroscopeRandomWalk,
double, 0.0001,
"[rad/s^2/sqrt(Hz)] (gyro bias diffusion)");
660 RTABMAP_PARAM(OdomOpenVINS, UpMSCKFSigmaPx,
double, 1.0,
"Pixel noise for MSCKF features");
661 RTABMAP_PARAM(OdomOpenVINS, UpMSCKFChi2Multiplier,
double, 1.0,
"Chi2 multiplier for MSCKF features");
662 RTABMAP_PARAM(OdomOpenVINS, UpSLAMSigmaPx,
double, 1.0,
"Pixel noise for SLAM features");
663 RTABMAP_PARAM(OdomOpenVINS, UpSLAMChi2Multiplier,
double, 1.0,
"Chi2 multiplier for SLAM features");
666 RTABMAP_PARAM(OdomOpen3D, MaxDepth,
float, 3.0,
"Maximum depth.");
667 RTABMAP_PARAM(OdomOpen3D, Method,
int, 0,
"Registration method: 0=PointToPlane, 1=Intensity, 2=Hybrid.");
670 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.");
671 RTABMAP_PARAM(Reg, Strategy,
int, 0,
"0=Vis, 1=Icp, 2=VisIcp");
672 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.");
675 RTABMAP_PARAM(Vis, EstimationType,
int, 1,
"Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP), 2:2D->2D (Epipolar Geometry)");
676 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).");
677 RTABMAP_PARAM(Vis, InlierDistance,
float, 0.1,
uFormat(
"[%s = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.", kVisEstimationType().
c_str()));
678 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()));
680 RTABMAP_PARAM(Vis, PnPFlags,
int, 0,
uFormat(
"[%s = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P", kVisEstimationType().
c_str()));
681 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
682 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()));
684 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()));
686 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()));
687 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()));
688 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());
689 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());
691 RTABMAP_PARAM(Vis, EpipolarGeometryVar,
float, 0.1,
uFormat(
"[%s = 2] Epipolar geometry maximum variance to accept the transformation.", kVisEstimationType().
c_str()));
692 RTABMAP_PARAM(Vis, MinInliers,
int, 20,
"Minimum feature correspondences to compute/accept the transformation.");
693 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.");
694 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.");
696 RTABMAP_PARAM(Vis, Iterations,
int, 300,
"Maximum iterations to compute the transform.");
697 #if CV_MAJOR_VERSION > 2 && !defined(HAVE_OPENCV_XFEATURES2D)
699 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");
701 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");
704 RTABMAP_PARAM(Vis,
SSC,
bool,
false,
"If true, SSC (Suppression via Square Covering) is applied to limit keypoints.");
705 RTABMAP_PARAM(Vis, MaxDepth,
float, 0,
"Max depth of the features (0 means no limit).");
706 RTABMAP_PARAM(Vis, MinDepth,
float, 0,
"Min depth of the features (0 means no limit).");
707 RTABMAP_PARAM(Vis, DepthAsMask,
bool,
true,
"Use depth image as mask when extracting features.");
708 RTABMAP_PARAM(Vis, DepthMaskFloorThr,
float, 0.0,
uFormat(
"Filter floor from depth mask below specified threshold (m) before extracting features. 0 means disabled, negative means remove all objects above the floor threshold instead. Ignored if %s is false.", kVisDepthAsMask().
c_str()));
709 RTABMAP_PARAM_STR(Vis, RoiRatios,
"0.0 0.0 0.0 0.0",
"Region of interest ratios [left, right, top, bottom].");
710 RTABMAP_PARAM(Vis, SubPixWinSize,
int, 3,
"See cv::cornerSubPix().");
711 RTABMAP_PARAM(Vis, SubPixIterations,
int, 0,
"See cv::cornerSubPix(). 0 disables sub pixel refining.");
712 RTABMAP_PARAM(Vis, SubPixEps,
float, 0.02,
"See cv::cornerSubPix().");
713 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()));
714 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()));
715 RTABMAP_PARAM(Vis, CorType,
int, 0,
"Correspondences computation approach: 0=Features Matching, 1=Optical Flow");
716 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()));
717 RTABMAP_PARAM(Vis, CorNNDR,
float, 0.8,
uFormat(
"[%s=0] NNDR: nearest neighbor distance ratio. Used for knn features matching approach.", kVisCorType().
c_str()));
718 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()));
719 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()));
720 RTABMAP_PARAM(Vis, CorFlowWinSize,
int, 16,
uFormat(
"[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().
c_str()));
721 RTABMAP_PARAM(Vis, CorFlowIterations,
int, 30,
uFormat(
"[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().
c_str()));
722 RTABMAP_PARAM(Vis, CorFlowEps,
float, 0.01,
uFormat(
"[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().
c_str()));
723 RTABMAP_PARAM(Vis, CorFlowMaxLevel,
int, 3,
uFormat(
"[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().
c_str()));
724 RTABMAP_PARAM(Vis, CorFlowGpu,
bool,
false,
uFormat(
"[%s=1] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA).", kVisCorType().
c_str()));
725 #if defined(RTABMAP_G2O) || defined(RTABMAP_ORB_SLAM)
726 RTABMAP_PARAM(Vis, BundleAdjustment,
int, 1,
"Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
728 RTABMAP_PARAM(Vis, BundleAdjustment,
int, 0,
"Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.");
732 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.");
736 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\").");
738 RTABMAP_PARAM(GMS, WithRotation,
bool,
false,
"Take rotation transformation into account.");
739 RTABMAP_PARAM(GMS, WithScale,
bool,
false,
"Take scale transformation into account.");
740 RTABMAP_PARAM(GMS, ThresholdFactor,
double, 6.0,
"The higher, the less matches.");
743 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.");
747 #ifdef RTABMAP_POINTMATCHER
748 RTABMAP_PARAM(Icp, Strategy,
int, 1,
"ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
750 RTABMAP_PARAM(Icp, Strategy,
int, 0,
"ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).");
752 RTABMAP_PARAM(Icp, MaxTranslation,
float, 0.2,
"Maximum ICP translation correction accepted (m).");
753 RTABMAP_PARAM(Icp, MaxRotation,
float, 0.78,
"Maximum ICP rotation correction accepted (rad).");
754 RTABMAP_PARAM(Icp, VoxelSize,
float, 0.05,
"Uniform sampling voxel size (0=disabled).");
755 RTABMAP_PARAM(Icp, DownsamplingStep,
int, 1,
"Downsampling step size (1=no sampling). This is done before uniform sampling.");
756 RTABMAP_PARAM(Icp, RangeMin,
float, 0,
"Minimum range filtering (0=disabled).");
757 RTABMAP_PARAM(Icp, RangeMax,
float, 0,
"Maximum range filtering (0=disabled).");
758 #ifdef RTABMAP_POINTMATCHER
759 RTABMAP_PARAM(Icp, MaxCorrespondenceDistance,
float, 0.1,
"Max distance for point correspondences.");
761 RTABMAP_PARAM(Icp, MaxCorrespondenceDistance,
float, 0.05,
"Max distance for point correspondences.");
763 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.");
765 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.");
766 RTABMAP_PARAM(Icp, CorrespondenceRatio,
float, 0.1,
"Ratio of matching correspondences to accept the transform.");
767 RTABMAP_PARAM(Icp, Force4DoF,
bool,
false,
uFormat(
"Limit ICP to x, y, z and yaw DoF. Available if %s > 0.", kIcpStrategy().
c_str()));
768 RTABMAP_PARAM(Icp, FiltersEnabled,
int, 3,
"Flag to enable filters: 1=\"from\" cloud only, 2=\"to\" cloud only, 3=both.");
769 #ifdef RTABMAP_POINTMATCHER
770 RTABMAP_PARAM(Icp, PointToPlane,
bool,
true,
"Use point to plane ICP.");
772 RTABMAP_PARAM(Icp, PointToPlane,
bool,
false,
"Use point to plane ICP.");
774 RTABMAP_PARAM(Icp, PointToPlaneK,
int, 5,
"Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals.");
775 RTABMAP_PARAM(Icp, PointToPlaneRadius,
float, 0.0,
"Search radius to compute normals for point to plane if the cloud doesn't have already normals.");
776 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.");
777 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()));
778 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()));
779 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()));
780 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.");
783 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());
784 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.");
785 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.");
786 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()));
788 RTABMAP_PARAM(Icp, CCSamplingLimit,
unsigned int, 50000,
"Maximum number of points per cloud (they are randomly resampled below this limit otherwise).");
789 RTABMAP_PARAM(Icp, CCFilterOutFarthestPoints,
bool,
false,
"If true, the algorithm will automatically ignore farthest points from the reference, for better convergence.");
790 RTABMAP_PARAM(Icp, CCMaxFinalRMS,
float, 0.2,
"Maximum final RMS error.");
799 RTABMAP_PARAM(
Stereo, OpticalFlow,
bool,
true,
"Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.");
800 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()));
802 RTABMAP_PARAM(
Stereo, Gpu,
bool,
false,
uFormat(
"[%s=true] Enable GPU version of the optical flow approach (only available if OpenCV is built with CUDA).", kStereoOpticalFlow().
c_str()));
827 #if CV_MAJOR_VERSION < 3
834 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).");
835 RTABMAP_PARAM(Grid, DepthDecimation,
unsigned int, 4,
uFormat(
"[%s=true] Decimation of the depth image before creating cloud.", kGridDepthDecimation().
c_str()));
836 RTABMAP_PARAM(Grid, RangeMin,
float, 0.0,
"Minimum range from sensor.");
837 RTABMAP_PARAM(Grid, RangeMax,
float, 5.0,
"Maximum range from sensor. 0=inf.");
838 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()));
839 RTABMAP_PARAM(Grid, FootprintLength,
float, 0.0,
"Footprint length used to filter points over the footprint of the robot.");
840 RTABMAP_PARAM(Grid, FootprintWidth,
float, 0.0,
"Footprint width used to filter points over the footprint of the robot. Footprint length should be set.");
841 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.");
842 RTABMAP_PARAM(Grid, ScanDecimation,
int, 1,
uFormat(
"[%s=0 or 2] Decimation of the laser scan before creating cloud.", kGridSensor().
c_str()));
843 RTABMAP_PARAM(Grid, CellSize,
float, 0.05,
"Resolution of the occupancy grid.");
844 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()));
845 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.");
846 RTABMAP_PARAM(Grid, NormalsSegmentation,
bool,
true,
"Segment ground from obstacles using point normals, otherwise a fast passthrough is used.");
847 RTABMAP_PARAM(Grid, MaxObstacleHeight,
float, 0.0,
"Maximum obstacles height (0=disabled).");
848 RTABMAP_PARAM(Grid, MinGroundHeight,
float, 0.0,
"Minimum ground height (0=disabled).");
849 RTABMAP_PARAM(Grid, MaxGroundHeight,
float, 0.0,
uFormat(
"Maximum ground height (0=disabled). Should be set if \"%s\" is false.", kGridNormalsSegmentation().
c_str()));
850 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()));
851 RTABMAP_PARAM(Grid, NormalK,
int, 20,
uFormat(
"[%s=true] K neighbors to compute normals.", kGridNormalsSegmentation().
c_str()));
852 RTABMAP_PARAM(Grid, ClusterRadius,
float, 0.1,
uFormat(
"[%s=true] Cluster maximum radius.", kGridNormalsSegmentation().
c_str()));
853 RTABMAP_PARAM(Grid, MinClusterSize,
int, 10,
uFormat(
"[%s=true] Minimum cluster size to project the points.", kGridNormalsSegmentation().
c_str()));
854 RTABMAP_PARAM(Grid, FlatObstacleDetected,
bool,
true,
uFormat(
"[%s=true] Flat obstacles detected.", kGridNormalsSegmentation().
c_str()));
855 #ifdef RTABMAP_OCTOMAP
856 RTABMAP_PARAM(Grid, 3
D,
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()));
858 RTABMAP_PARAM(Grid, 3
D,
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()));
860 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()));
861 RTABMAP_PARAM(Grid, NoiseFilteringRadius,
float, 0.0,
"Noise filtering radius (0=disabled). Done after segmentation.");
862 RTABMAP_PARAM(Grid, NoiseFilteringMinNeighbors,
int, 5,
"Noise filtering minimum neighbors.");
863 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()));
864 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()));
865 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.");
866 RTABMAP_PARAM(GridGlobal, FootprintRadius,
float, 0.0,
"Footprint radius (m) used to clear all obstacles under the graph.");
867 RTABMAP_PARAM(GridGlobal, MinSize,
float, 0.0,
"Minimum map size (m).");
868 RTABMAP_PARAM(GridGlobal, Eroded,
bool,
false,
"Erode obstacle cells.");
869 RTABMAP_PARAM(GridGlobal, MaxNodes,
int, 0,
"Maximum nodes assembled in the map starting from the last node (0=unlimited).");
870 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).");
871 RTABMAP_PARAM(GridGlobal, OccupancyThr,
float, 0.5,
"Occupancy threshold (value between 0 and 1).");
872 RTABMAP_PARAM(GridGlobal, ProbHit,
float, 0.7,
"Probability of a hit (value between 0.5 and 1).");
873 RTABMAP_PARAM(GridGlobal, ProbMiss,
float, 0.4,
"Probability of a miss (value between 0 and 0.5).");
874 RTABMAP_PARAM(GridGlobal, ProbClampingMin,
float, 0.1192,
"Probability clamping minimum (value between 0 and 1).");
875 RTABMAP_PARAM(GridGlobal, ProbClampingMax,
float, 0.971,
"Probability clamping maximum (value between 0 and 1).");
876 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.");
878 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");
879 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).");
880 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()));
881 RTABMAP_PARAM(Marker, VarianceLinear,
float, 0.001,
"Linear variance to set on marker detections.");
882 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.");
883 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.");
884 RTABMAP_PARAM(Marker, MaxRange,
float, 0.0,
"Maximum range in which markers will be detected. <=0 for unlimited range.");
885 RTABMAP_PARAM(Marker, MinRange,
float, 0.0,
"Miniminum range in which markers will be detected. <=0 for unlimited range.");
886 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).");
887 RTABMAP_PARAM(Marker, PriorsVarianceLinear,
float, 0.001,
"Linear variance to set on marker priors.");
888 RTABMAP_PARAM(Marker, PriorsVarianceAngular,
float, 0.001,
"Angular variance to set on marker priors.");
890 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].");
891 RTABMAP_PARAM(ImuFilter, MadgwickZeta,
double, 0.0,
"Gyro drift gain (approx. rad/s), belongs in [-1, 1].");
893 RTABMAP_PARAM(ImuFilter, ComplementaryGainAcc,
double, 0.01,
"Gain parameter for the complementary filter, belongs in [0, 1].");
894 RTABMAP_PARAM(ImuFilter, ComplementaryBiasAlpha,
double, 0.01,
"Bias estimation gain parameter, belongs in [0, 1].");
895 RTABMAP_PARAM(ImuFilter, ComplementaryDoBiasEstimation,
bool,
true,
"Parameter whether to do bias estimation or not.");
896 RTABMAP_PARAM(ImuFilter, ComplementaryDoAdpativeGain,
bool,
true,
"Parameter whether to do adaptive gain or not.");
914 static std::string getType(
const std::string & paramKey);
920 static std::string getDescription(
const std::string & paramKey);
922 static bool parse(
const ParametersMap & parameters,
const std::string & key,
bool & value);
923 static bool parse(
const ParametersMap & parameters,
const std::string & key,
int & value);
924 static bool parse(
const ParametersMap & parameters,
const std::string & key,
unsigned int & value);
925 static bool parse(
const ParametersMap & parameters,
const std::string & key,
float & value);
926 static bool parse(
const ParametersMap & parameters,
const std::string & key,
double & value);
927 static bool parse(
const ParametersMap & parameters,
const std::string & key, std::string & value);
933 static std::string getVersion();
934 static std::string getDefaultDatabaseName();
939 static bool isFeatureParameter(
const std::string & param);
940 static ParametersMap getDefaultOdometryParameters(
bool stereo =
false,
bool vis =
true,
bool icp =
false);
941 static ParametersMap getDefaultParameters(
const std::string & group);
948 static void readINI(
const std::string & configFile,
ParametersMap & parameters,
bool modifiedOnly =
false);
949 static void readINIStr(
const std::string & configContent,
ParametersMap & parameters,
bool modifiedOnly =
false);
950 static void writeINI(
const std::string & configFile,
const ParametersMap & parameters);
956 static const std::map<std::string, std::pair<bool, std::string> > & getRemovedParameters();
963 static std::string createDefaultWorkingDirectory();