Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Attributes | List of all members
rtabmap::Parameters Class Reference

#include <Parameters.h>

Public Member Functions

virtual ~Parameters ()
 

Static Public Member Functions

static std::string createDefaultWorkingDirectory ()
 
static ParametersMap deserialize (const std::string &parameters)
 
static ParametersMap filterParameters (const ParametersMap &parameters, const std::string &group, bool remove=false)
 
static const ParametersMapgetBackwardCompatibilityMap ()
 
static std::string getDefaultDatabaseName ()
 
static ParametersMap getDefaultOdometryParameters (bool stereo=false, bool vis=true, bool icp=false)
 
static const ParametersMapgetDefaultParameters ()
 
static ParametersMap getDefaultParameters (const std::string &group)
 
static std::string getDescription (const std::string &paramKey)
 
static const std::map< std::string, std::pair< bool, std::string > > & getRemovedParameters ()
 
static std::string getType (const std::string &paramKey)
 
static std::string getVersion ()
 
static bool isFeatureParameter (const std::string &param)
 
static bool parse (const ParametersMap &parameters, const std::string &key, bool &value)
 
static bool parse (const ParametersMap &parameters, const std::string &key, double &value)
 
static bool parse (const ParametersMap &parameters, const std::string &key, float &value)
 
static bool parse (const ParametersMap &parameters, const std::string &key, int &value)
 
static bool parse (const ParametersMap &parameters, const std::string &key, std::string &value)
 
static bool parse (const ParametersMap &parameters, const std::string &key, unsigned int &value)
 
static void parse (const ParametersMap &parameters, ParametersMap &parametersOut)
 
static ParametersMap parseArguments (int argc, char *argv[], bool onlyParameters=false)
 
static void readINI (const std::string &configFile, ParametersMap &parameters, bool modifiedOnly=false)
 
static void readINIStr (const std::string &configContent, ParametersMap &parameters, bool modifiedOnly=false)
 
static std::string serialize (const ParametersMap &parameters)
 
static const char * showUsage ()
 
static void writeINI (const std::string &configFile, const ParametersMap &parameters)
 

Private Member Functions

 Parameters ()
 
 RTABMAP_PARAM (Bayes, FullPredictionUpdate, bool, false, "Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).")
 
 RTABMAP_PARAM (Bayes, VirtualPlacePriorThr, float, 0.9, "Virtual place prior")
 
 RTABMAP_PARAM (BRIEF, Bytes, int, 32, "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.")
 
 RTABMAP_PARAM (BRISK, Octaves, int, 3, "Detection octaves. Use 0 to do single scale.")
 
 RTABMAP_PARAM (BRISK, PatternScale, float, 1,"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.")
 
 RTABMAP_PARAM (BRISK, Thresh, int, 30, "FAST/AGAST detection threshold score.")
 
 RTABMAP_PARAM (DbSqlite3, CacheSize, unsigned int, 10000, "Sqlite cache size (default is 2000).")
 
 RTABMAP_PARAM (DbSqlite3, InMemory, bool, false, "Using database in the memory instead of a file on the hard disk.")
 
 RTABMAP_PARAM (DbSqlite3, JournalMode, int, 3, "0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")")
 
 RTABMAP_PARAM (DbSqlite3, Synchronous, int, 0, "0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")")
 
 RTABMAP_PARAM (DbSqlite3, TempStore, int, 2, "0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (FAST, GpuKeypointsRatio, double, 0.05, "Used with FAST GPU.")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (FAST, MaxThreshold, int, 200, "Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set.")
 
 RTABMAP_PARAM (FAST, MinThreshold, int, 7, "Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set.")
 
 RTABMAP_PARAM (FAST, NonmaxSuppression, bool, true, "If true, non-maximum suppression is applied to detected corners (keypoints).")
 
 RTABMAP_PARAM (FAST, Threshold, int, 20, "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.")
 
 RTABMAP_PARAM (FREAK, NOctaves, int, 4, "Number of octaves covered by the detected keypoints.")
 
 RTABMAP_PARAM (FREAK, OrientationNormalized, bool, true, "Enable orientation normalization.")
 
 RTABMAP_PARAM (FREAK, PatternScale, float, 22, "Scaling of the description pattern.")
 
 RTABMAP_PARAM (FREAK, ScaleNormalized, bool, true, "Enable scale normalization.")
 
 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.")
 
 RTABMAP_PARAM (g2o, Optimizer, int, 0, "0=Levenberg 1=GaussNewton")
 
 RTABMAP_PARAM (g2o, PixelVariance, double, 1.0, "Pixel variance used for bundle adjustment.")
 
 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.")
 
 RTABMAP_PARAM (g2o, Solver, int, 0, "0=csparse 1=pcg 2=cholmod 3=Eigen")
 
 RTABMAP_PARAM (GFTT, BlockSize, int, 3, "")
 
 RTABMAP_PARAM (GFTT, K, double, 0.04, "")
 
 RTABMAP_PARAM (GFTT, MinDistance, double, 7, "")
 
 RTABMAP_PARAM (GFTT, QualityLevel, double, 0.001, "")
 
 RTABMAP_PARAM (GFTT, UseHarrisDetector, bool, false, "")
 
 RTABMAP_PARAM (GMS, ThresholdFactor, double, 6.0, "The higher, the less matches.")
 
 RTABMAP_PARAM (GMS, WithRotation, bool, false, "Take rotation transformation into account.")
 
 RTABMAP_PARAM (GMS, WithScale, bool, false, "Take scale transformation into account.")
 
 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()))
 
 RTABMAP_PARAM (Grid, CellSize, float, 0.05, "Resolution of the occupancy grid.")
 
 RTABMAP_PARAM (Grid, ClusterRadius, float, 0.1, uFormat("[%s=true] Cluster maximum radius.", kGridNormalsSegmentation().c_str()))
 
 RTABMAP_PARAM (Grid, DepthDecimation, unsigned int, 4, uFormat("[%s=true] Decimation of the depth image before creating cloud.", kGridDepthDecimation().c_str()))
 
 RTABMAP_PARAM (Grid, FlatObstacleDetected, bool, true, uFormat("[%s=true] Flat obstacles detected.", kGridNormalsSegmentation().c_str()))
 
 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.")
 
 RTABMAP_PARAM (Grid, FootprintLength, float, 0.0, "Footprint length used to filter points over the footprint of the robot.")
 
 RTABMAP_PARAM (Grid, FootprintWidth, float, 0.0, "Footprint width used to filter points over the footprint of the robot. Footprint length should be set.")
 
 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()))
 
 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.")
 
 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()))
 
 RTABMAP_PARAM (Grid, MaxGroundHeight, float, 0.0, uFormat("Maximum ground height (0=disabled). Should be set if \"%s\" is false.", kGridNormalsSegmentation().c_str()))
 
 RTABMAP_PARAM (Grid, MaxObstacleHeight, float, 0.0, "Maximum obstacles height (0=disabled).")
 
 RTABMAP_PARAM (Grid, MinClusterSize, int, 10, uFormat("[%s=true] Minimum cluster size to project the points.", kGridNormalsSegmentation().c_str()))
 
 RTABMAP_PARAM (Grid, MinGroundHeight, float, 0.0, "Minimum ground height (0=disabled).")
 
 RTABMAP_PARAM (Grid, NoiseFilteringMinNeighbors, int, 5, "Noise filtering minimum neighbors.")
 
 RTABMAP_PARAM (Grid, NoiseFilteringRadius, float, 0.0, "Noise filtering radius (0=disabled). Done after segmentation.")
 
 RTABMAP_PARAM (Grid, NormalK, int, 20, uFormat("[%s=true] K neighbors to compute normals.", kGridNormalsSegmentation().c_str()))
 
 RTABMAP_PARAM (Grid, NormalsSegmentation, bool, true, "Segment ground from obstacles using point normals, otherwise a fast passthrough is used.")
 
 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()))
 
 RTABMAP_PARAM (Grid, RangeMax, float, 5.0, "Maximum range from sensor. 0=inf.")
 
 RTABMAP_PARAM (Grid, RangeMin, float, 0.0, "Minimum range from sensor.")
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Grid, ScanDecimation, int, 1, uFormat("[%s=0 or 2] Decimation of the laser scan before creating cloud.", kGridSensor().c_str()))
 
 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).")
 
 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).")
 
 RTABMAP_PARAM (GridGlobal, Eroded, bool, false, "Erode obstacle cells.")
 
 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.")
 
 RTABMAP_PARAM (GridGlobal, FootprintRadius, float, 0.0, "Footprint radius (m) used to clear all obstacles under the graph.")
 
 RTABMAP_PARAM (GridGlobal, MaxNodes, int, 0, "Maximum nodes assembled in the map starting from the last node (0=unlimited).")
 
 RTABMAP_PARAM (GridGlobal, MinSize, float, 0.0, "Minimum map size (m).")
 
 RTABMAP_PARAM (GridGlobal, OccupancyThr, float, 0.5, "Occupancy threshold (value between 0 and 1).")
 
 RTABMAP_PARAM (GridGlobal, ProbClampingMax, float, 0.971, "Probability clamping maximum (value between 0 and 1).")
 
 RTABMAP_PARAM (GridGlobal, ProbClampingMin, float, 0.1192, "Probability clamping minimum (value between 0 and 1).")
 
 RTABMAP_PARAM (GridGlobal, ProbHit, float, 0.7, "Probability of a hit (value between 0.5 and 1).")
 
 RTABMAP_PARAM (GridGlobal, ProbMiss, float, 0.4, "Probability of a miss (value between 0 and 0.5).")
 
 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.")
 
 RTABMAP_PARAM (GTSAM, IncRelinearizeSkip, int, 1, "Only relinearize any variables every X calls to ISAM2::update(). See GTSAM::ISAM2 doc for more info.")
 
 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.")
 
 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()))
 
 RTABMAP_PARAM (GTSAM, Optimizer, int, 1, "0=Levenberg 1=GaussNewton 2=Dogleg")
 
 RTABMAP_PARAM (Icp, CCFilterOutFarthestPoints, bool, false, "If true, the algorithm will automatically ignore farthest points from the reference, for better convergence.")
 
 RTABMAP_PARAM (Icp, CCMaxFinalRMS, float, 0.2, "Maximum final RMS error.")
 
 RTABMAP_PARAM (Icp, CCSamplingLimit, unsigned int, 50000, "Maximum number of points per cloud (they are randomly resampled below this limit otherwise).")
 
 RTABMAP_PARAM (Icp, CorrespondenceRatio, float, 0.1, "Ratio of matching correspondences to accept the transform.")
 
 RTABMAP_PARAM (Icp, DownsamplingStep, int, 1, "Downsampling step size (1=no sampling). This is done before uniform sampling.")
 
 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.")
 
 RTABMAP_PARAM (Icp, FiltersEnabled, int, 3, "Flag to enable filters: 1=\"from\" cloud only, 2=\"to\" cloud only, 3=both.")
 
 RTABMAP_PARAM (Icp, Force4DoF, bool, false, uFormat("Limit ICP to x, y, z and yaw DoF. Available if %s > 0.", kIcpStrategy().c_str()))
 
 RTABMAP_PARAM (Icp, Iterations, int, 30, "Max iterations.")
 
 RTABMAP_PARAM (Icp, MaxCorrespondenceDistance, float, 0.05, "Max distance for point correspondences.")
 
 RTABMAP_PARAM (Icp, MaxRotation, float, 0.78, "Maximum ICP rotation correction accepted (rad).")
 
 RTABMAP_PARAM (Icp, MaxTranslation, float, 0.2, "Maximum ICP translation correction accepted (m).")
 
 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()))
 
 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.")
 
 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()))
 
 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.")
 
 RTABMAP_PARAM (Icp, PointToPlane, bool, false, "Use point to plane ICP.")
 
 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.")
 
 RTABMAP_PARAM (Icp, PointToPlaneK, int, 5, "Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals.")
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Icp, PointToPlaneRadius, float, 0.0, "Search radius to compute normals for point to plane if the cloud doesn't have already normals.")
 
 RTABMAP_PARAM (Icp, RangeMax, float, 0, "Maximum range filtering (0=disabled).")
 
 RTABMAP_PARAM (Icp, RangeMin, float, 0, "Minimum range filtering (0=disabled).")
 
 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.")
 
 RTABMAP_PARAM (Icp, Strategy, int, 0, "ICP implementation: 0=Point Cloud Library, 1=libpointmatcher, 2=CCCoreLib (CloudCompare).")
 
 RTABMAP_PARAM (Icp, VoxelSize, float, 0.05, "Uniform sampling voxel size (0=disabled).")
 
 RTABMAP_PARAM (ImuFilter, ComplementaryBiasAlpha, double, 0.01, "Bias estimation gain parameter, belongs in [0, 1].")
 
 RTABMAP_PARAM (ImuFilter, ComplementaryDoAdpativeGain, bool, true, "Parameter whether to do adaptive gain or not.")
 
 RTABMAP_PARAM (ImuFilter, ComplementaryDoBiasEstimation, bool, true, "Parameter whether to do bias estimation or not.")
 
 RTABMAP_PARAM (ImuFilter, ComplementaryGainAcc, double, 0.01, "Gain parameter for the complementary filter, belongs in [0, 1].")
 
 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].")
 
 RTABMAP_PARAM (ImuFilter, MadgwickZeta, double, 0.0, "Gyro drift gain (approx. rad/s), belongs in [-1, 1].")
 
 RTABMAP_PARAM (KAZE, Diffusivity, int, 1, "Diffusivity type: 0=DIFF_PM_G1, 1=DIFF_PM_G2, 2=DIFF_WEICKERT or 3=DIFF_CHARBONNIER.")
 
 RTABMAP_PARAM (KAZE, Extended, bool, false, "Set to enable extraction of extended (128-byte) descriptor.")
 
 RTABMAP_PARAM (KAZE, NOctaveLayers, int, 4, "Default number of sublevels per scale level.")
 
 RTABMAP_PARAM (KAZE, NOctaves, int, 4, "Maximum octave evolution of the image.")
 
 RTABMAP_PARAM (KAZE, Threshold, float, 0.001, "Detector response threshold to accept keypoint.")
 
 RTABMAP_PARAM (KAZE, Upright, bool, false, "Set to enable use of upright descriptors (non rotation-invariant).")
 
 RTABMAP_PARAM (Kp, BadSignRatio, float, 0.5, "Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).")
 
 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()))
 
 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")
 
 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()))
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Kp, IncrementalDictionary, bool, true, "")
 
 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()))
 
 RTABMAP_PARAM (Kp, MaxDepth, float, 0, "Filter extracted keypoints by depth (0=inf).")
 
 RTABMAP_PARAM (Kp, MaxFeatures, int, 500, "Maximum features extracted from the images (0 means not bounded, <0 means no extraction).")
 
 RTABMAP_PARAM (Kp, MinDepth, float, 0, "Filter extracted keypoints by depth.")
 
 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).")
 
 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.)")
 
 RTABMAP_PARAM (Kp, NNStrategy, int, 1, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4")
 
 RTABMAP_PARAM (Kp, Parallelized, bool, true, "If the dictionary update and signature creation were parallelized.")
 
 RTABMAP_PARAM (Kp, SSC, bool, false, "If true, SSC (Suppression via Square Covering) is applied to limit keypoints.")
 
 RTABMAP_PARAM (Kp, SubPixEps, double, 0.02, "See cv::cornerSubPix().")
 
 RTABMAP_PARAM (Kp, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.")
 
 RTABMAP_PARAM (Kp, SubPixWinSize, int, 3, "See cv::cornerSubPix().")
 
 RTABMAP_PARAM (Kp, TfIdfLikelihoodUsed, bool, true, "Use of the td-idf strategy to compute the likelihood.")
 
 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.")
 
 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")
 
 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).")
 
 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()))
 
 RTABMAP_PARAM (Marker, MaxRange, float, 0.0, "Maximum range in which markers will be detected. <=0 for unlimited range.")
 
 RTABMAP_PARAM (Marker, MinRange, float, 0.0, "Miniminum range in which markers will be detected. <=0 for unlimited range.")
 
 RTABMAP_PARAM (Marker, PriorsVarianceAngular, float, 0.001, "Angular variance to set on marker priors.")
 
 RTABMAP_PARAM (Marker, PriorsVarianceLinear, float, 0.001, "Linear variance to set on marker priors.")
 
 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.")
 
 RTABMAP_PARAM (Marker, VarianceLinear, float, 0.001, "Linear variance to set on marker detections.")
 
 RTABMAP_PARAM (Mem, BadSignaturesIgnored, bool, false, "Bad signatures are ignored.")
 
 RTABMAP_PARAM (Mem, BinDataKept, bool, true, "Keep binary data in db.")
 
 RTABMAP_PARAM (Mem, CompressionParallelized, bool, true, "Compression of sensor data is multi-threaded.")
 
 RTABMAP_PARAM (Mem, CovOffDiagIgnored, bool, true, "Ignore off diagonal values of the covariance matrix.")
 
 RTABMAP_PARAM (Mem, DepthAsMask, bool, true, "Use depth image as mask when extracting features for vocabulary.")
 
 RTABMAP_PARAM (Mem, GenerateIds, bool, true, "True=Generate location IDs, False=use input image IDs.")
 
 RTABMAP_PARAM (Mem, GlobalDescriptorStrategy, int, 0, "Extract global descriptor from sensor data. 0=disabled, 1=PyDescriptor")
 
 RTABMAP_PARAM (Mem, ImageKept, bool, false, "Keep raw images in RAM.")
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Mem, IncrementalMemory, bool, true, "SLAM mode, otherwise it is Localization mode.")
 
 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.")
 
 RTABMAP_PARAM (Mem, IntermediateNodeDataKept, bool, false, "Keep intermediate node data in db.")
 
 RTABMAP_PARAM (Mem, LaserScanDownsampleStepSize, int, 1, "If > 1, downsample the laser scans when creating a signature.")
 
 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.")
 
 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.")
 
 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()))
 
 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())
 
 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.")
 
 RTABMAP_PARAM (Mem, NotLinkedNodesKept, bool, true, "Keep not linked nodes in db (rehearsed nodes and deleted nodes).")
 
 RTABMAP_PARAM (Mem, RawDescriptorsKept, bool, true, "Raw descriptors kept in memory.")
 
 RTABMAP_PARAM (Mem, RecentWmRatio, float, 0.2, "Ratio of locations after the last loop closure in WM that cannot be transferred.")
 
 RTABMAP_PARAM (Mem, ReduceGraph, bool, false, "Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set).")
 
 RTABMAP_PARAM (Mem, RehearsalIdUpdatedToNewOne, bool, false, "On merge, update to new id. When false, no copy.")
 
 RTABMAP_PARAM (Mem, RehearsalSimilarity, float, 0.6, "Rehearsal similarity.")
 
 RTABMAP_PARAM (Mem, RehearsalWeightIgnoredWhileMoving, bool, false, "When the robot is moving, weights are not updated on rehearsal.")
 
 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.")
 
 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).")
 
 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()))
 
 RTABMAP_PARAM (Mem, STMSize, unsigned int, 10, "Short-term memory size.")
 
 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.")
 
 RTABMAP_PARAM (Mem, UseOdomFeatures, bool, true, "Use odometry features instead of regenerating them.")
 
 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()))
 
 RTABMAP_PARAM (Odom, AlignWithGround, bool, false, "Align odometry with the ground on initialization.")
 
 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).")
 
 RTABMAP_PARAM (Odom, FillInfoData, bool, true, "Fill info with data (inliers/outliers features).")
 
 RTABMAP_PARAM (Odom, FilteringStrategy, int, 0, "0=No filtering 1=Kalman filtering 2=Particle filtering. This filter is used to smooth the odometry output.")
 
 RTABMAP_PARAM (Odom, GuessMotion, bool, true, "Guess next transformation from the last motion computed.")
 
 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()))
 
 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)).")
 
 RTABMAP_PARAM (Odom, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).")
 
 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()))
 
 RTABMAP_PARAM (Odom, KalmanMeasurementNoise, float, 0.01, "Process measurement covariance value.")
 
 RTABMAP_PARAM (Odom, KalmanProcessNoise, float, 0.001, "Process noise covariance value.")
 
 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.")
 
 RTABMAP_PARAM (Odom, ParticleLambdaR, float, 100, "Lambda of rotational components (roll,pitch,yaw).")
 
 RTABMAP_PARAM (Odom, ParticleLambdaT, float, 100, "Lambda of translation components (x,y,z).")
 
 RTABMAP_PARAM (Odom, ParticleNoiseR, float, 0.002, "Noise (rad) of rotational components (roll,pitch,yaw).")
 
 RTABMAP_PARAM (Odom, ParticleNoiseT, float, 0.002, "Noise (m) of translation components (x,y,z).")
 
 RTABMAP_PARAM (Odom, ParticleSize, unsigned int, 400, "Number of particles of the filter.")
 
 RTABMAP_PARAM (Odom, ResetCountdown, int, 0, "Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).")
 
 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.")
 
 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")
 
 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.")
 
 RTABMAP_PARAM (OdomF2M, BundleAdjustment, int, 0, "Local bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.")
 
 RTABMAP_PARAM (OdomF2M, BundleAdjustmentMaxFrames, int, 10, "Maximum frames used for bundle adjustment (0=inf or all current frames in the local map).")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (OdomF2M, ScanMaxSize, int, 2000, "[Geometry] Maximum local scan map size.")
 
 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.")
 
 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())
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (OdomFovis, BucketHeight, int, 80, "")
 
 RTABMAP_PARAM (OdomFovis, BucketWidth, int, 80, "")
 
 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.")
 
 RTABMAP_PARAM (OdomFovis, FastThreshold, int, 20, "FAST threshold.")
 
 RTABMAP_PARAM (OdomFovis, FastThresholdAdaptiveGain, double, 0.005, "FAST threshold adaptive gain.")
 
 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.")
 
 RTABMAP_PARAM (OdomFovis, FeatureWindowSize, int, 9, "The size of the n x n image patch surrounding each feature, used for keypoint matching.")
 
 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.")
 
 RTABMAP_PARAM (OdomFovis, MaxKeypointsPerBucket, int, 25, "")
 
 RTABMAP_PARAM (OdomFovis, MaxMeanReprojectionError, double, 10.0, "Maximum mean reprojection error over the inlier feature matches for the motion estimate to be considered valid.")
 
 RTABMAP_PARAM (OdomFovis, MaxPyramidLevel, int, 3, "The maximum Gaussian pyramid level to process the image at. Pyramid level 1 corresponds to the original image.")
 
 RTABMAP_PARAM (OdomFovis, MinFeaturesForEstimate, int, 20, "Minimum number of features in the inlier set for the motion estimate to be considered valid.")
 
 RTABMAP_PARAM (OdomFovis, MinPyramidLevel, int, 0, "The minimum pyramid level.")
 
 RTABMAP_PARAM (OdomFovis, StereoMaxDisparity, int, 128, "")
 
 RTABMAP_PARAM (OdomFovis, StereoMaxDistEpipolarLine, double, 1.5, "")
 
 RTABMAP_PARAM (OdomFovis, StereoMaxRefinementDisplacement, double, 1.0, "")
 
 RTABMAP_PARAM (OdomFovis, StereoRequireMutualMatch, bool, true, "")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (OdomFovis, UseAdaptiveThreshold, bool, true, "Use FAST adaptive threshold.")
 
 RTABMAP_PARAM (OdomFovis, UseBucketing, bool, true, "")
 
 RTABMAP_PARAM (OdomFovis, UseHomographyInitialization, bool, true, "Use homography initialization.")
 
 RTABMAP_PARAM (OdomFovis, UseImageNormalization, bool, false, "")
 
 RTABMAP_PARAM (OdomFovis, UseSubpixelRefinement, bool, true, "Specifies whether or not to refine feature matches to subpixel resolution.")
 
 RTABMAP_PARAM (OdomLOAM, AngVar, float, 0.01, "Angular output variance.")
 
 RTABMAP_PARAM (OdomLOAM, LinVar, float, 0.01, "Linear output variance.")
 
 RTABMAP_PARAM (OdomLOAM, LocalMapping, bool, true, "Local mapping. It adds more time to compute odometry, but accuracy is significantly improved.")
 
 RTABMAP_PARAM (OdomLOAM, Resolution, float, 0.2, "Map resolution")
 
 RTABMAP_PARAM (OdomLOAM, ScanPeriod, float, 0.1, "Scan period (s)")
 
 RTABMAP_PARAM (OdomLOAM, Sensor, int, 2, "Velodyne sensor: 0=VLP-16, 1=HDL-32, 2=HDL-64E")
 
 RTABMAP_PARAM (OdomMono, InitMinFlow, float, 100, "Minimum optical flow required for the initialization step.")
 
 RTABMAP_PARAM (OdomMono, InitMinTranslation, float, 0.1, "Minimum translation required for the initialization step.")
 
 RTABMAP_PARAM (OdomMono, MaxVariance, float, 0.01, "Maximum variance to add new points to local map.")
 
 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.")
 
 RTABMAP_PARAM (OdomMSCKF, FastThreshold, int, 10, "")
 
 RTABMAP_PARAM (OdomMSCKF, GridCol, int, 5, "")
 
 RTABMAP_PARAM (OdomMSCKF, GridMaxFeatureNum, int, 4, "")
 
 RTABMAP_PARAM (OdomMSCKF, GridMinFeatureNum, int, 3, "")
 
 RTABMAP_PARAM (OdomMSCKF, GridRow, int, 4, "")
 
 RTABMAP_PARAM (OdomMSCKF, InitCovAccBias, double, 0.01, "")
 
 RTABMAP_PARAM (OdomMSCKF, InitCovExRot, double, 0.00030462, "")
 
 RTABMAP_PARAM (OdomMSCKF, InitCovExTrans, double, 0.000025, "")
 
 RTABMAP_PARAM (OdomMSCKF, InitCovGyroBias, double, 0.01, "")
 
 RTABMAP_PARAM (OdomMSCKF, InitCovVel, double, 0.25, "")
 
 RTABMAP_PARAM (OdomMSCKF, MaxCamStateSize, int, 20, "")
 
 RTABMAP_PARAM (OdomMSCKF, MaxIteration, int, 30, "")
 
 RTABMAP_PARAM (OdomMSCKF, NoiseAcc, double, 0.05, "")
 
 RTABMAP_PARAM (OdomMSCKF, NoiseAccBias, double, 0.01, "")
 
 RTABMAP_PARAM (OdomMSCKF, NoiseFeature, double, 0.035, "")
 
 RTABMAP_PARAM (OdomMSCKF, NoiseGyro, double, 0.005, "")
 
 RTABMAP_PARAM (OdomMSCKF, NoiseGyroBias, double, 0.001, "")
 
 RTABMAP_PARAM (OdomMSCKF, OptTranslationThreshold, double, 0, "")
 
 RTABMAP_PARAM (OdomMSCKF, PatchSize, int, 15, "")
 
 RTABMAP_PARAM (OdomMSCKF, PositionStdThreshold, double, 8.0, "")
 
 RTABMAP_PARAM (OdomMSCKF, PyramidLevels, int, 3, "")
 
 RTABMAP_PARAM (OdomMSCKF, RansacThreshold, double, 3, "")
 
 RTABMAP_PARAM (OdomMSCKF, RotationThreshold, double, 0.2618, "")
 
 RTABMAP_PARAM (OdomMSCKF, StereoThreshold, double, 5, "")
 
 RTABMAP_PARAM (OdomMSCKF, TrackingRateThreshold, double, 0.5, "")
 
 RTABMAP_PARAM (OdomMSCKF, TrackPrecision, double, 0.01, "")
 
 RTABMAP_PARAM (OdomMSCKF, TranslationThreshold, double, 0.4, "")
 
 RTABMAP_PARAM (OdomOpen3D, MaxDepth, float, 3.0, "Maximum depth.")
 
 RTABMAP_PARAM (OdomOpen3D, Method, int, 0, "Registration method: 0=PointToPlane, 1=Intensity, 2=Hybrid.")
 
 RTABMAP_PARAM (OdomOpenVINS, AccelerometerNoiseDensity, double, 0.01, "[m/s^2/sqrt(Hz)] (accel \"white noise\")")
 
 RTABMAP_PARAM (OdomOpenVINS, AccelerometerRandomWalk, double, 0.001, "[m/s^3/sqrt(Hz)] (accel bias diffusion)")
 
 RTABMAP_PARAM (OdomOpenVINS, CalibCamExtrinsics, bool, false, "Bool to determine whether or not to calibrate imu-to-camera pose")
 
 RTABMAP_PARAM (OdomOpenVINS, CalibCamIntrinsics, bool, false, "Bool to determine whether or not to calibrate camera intrinsics")
 
 RTABMAP_PARAM (OdomOpenVINS, CalibCamTimeoffset, bool, false, "Bool to determine whether or not to calibrate camera to IMU time offset")
 
 RTABMAP_PARAM (OdomOpenVINS, CalibIMUGSensitivity, bool, false, "Bool to determine whether or not to calibrate the Gravity sensitivity")
 
 RTABMAP_PARAM (OdomOpenVINS, CalibIMUIntrinsics, bool, false, "Bool to determine whether or not to calibrate the IMU intrinsics")
 
 RTABMAP_PARAM (OdomOpenVINS, DtSLAMDelay, double, 0.0, "Delay, in seconds, that we should wait from init before we start estimating SLAM features")
 
 RTABMAP_PARAM (OdomOpenVINS, FeatRepMSCKF, int, 0, "What representation our features are in (msckf features)")
 
 RTABMAP_PARAM (OdomOpenVINS, FeatRepSLAM, int, 4, "What representation our features are in (slam features)")
 
 RTABMAP_PARAM (OdomOpenVINS, FiMaxBaseline, double, 40, "Max baseline ratio to accept triangulated features")
 
 RTABMAP_PARAM (OdomOpenVINS, FiMaxCondNumber, double, 10000, "Max condition number of linear triangulation matrix accept triangulated features")
 
 RTABMAP_PARAM (OdomOpenVINS, FiMaxRuns, int, 5, "Max runs for Levenberg-Marquardt")
 
 RTABMAP_PARAM (OdomOpenVINS, FiRefineFeatures, bool, true, "If we should perform Levenberg-Marquardt refinement")
 
 RTABMAP_PARAM (OdomOpenVINS, FiTriangulate1d, bool, false, "If we should perform 1d triangulation instead of 3d")
 
 RTABMAP_PARAM (OdomOpenVINS, GravityMag, double, 9.81, "Gravity magnitude in the global frame (i.e. should be 9.81 typically)")
 
 RTABMAP_PARAM (OdomOpenVINS, GyroscopeNoiseDensity, double, 0.001, "[rad/s/sqrt(Hz)] (gyro \"white noise\")")
 
 RTABMAP_PARAM (OdomOpenVINS, GyroscopeRandomWalk, double, 0.0001, "[rad/s^2/sqrt(Hz)] (gyro bias diffusion)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynInflationBa, double, 100.0, "What to inflate the recovered bias_a covariance by")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynInflationBg, double, 10.0, "What to inflate the recovered bias_g covariance by")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynInflationOri, double, 10.0, "What to inflate the recovered q_GtoI covariance by")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynInflationVel, double, 100.0, "What to inflate the recovered v_IinG covariance by")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMinDeg, double, 10.0, "Orientation change needed to try to init")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMinRecCond, double, 1e-15, "Reciprocal condition number thresh for info inversion")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMLEMaxIter, int, 50, "How many iterations the MLE refinement should use (zero to skip the MLE)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMLEMaxThreads, int, 6, "How many threads the MLE should use")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMLEMaxTime, double, 0.05, "How many seconds the MLE should be completed in")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynMLEOptCalib, bool, false, "If we should optimize calibration during intialization (not recommended)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynNumPose, int, 6, "Number of poses to use within our window time (evenly spaced)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitDynUse, bool, false, "If dynamic initialization should be used")
 
 RTABMAP_PARAM (OdomOpenVINS, InitIMUThresh, double, 1.0, "Variance threshold on our acceleration to be classified as moving")
 
 RTABMAP_PARAM (OdomOpenVINS, InitMaxDisparity, double, 10.0, "Max disparity to consider the platform stationary (dependent on resolution)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitMaxFeatures, int, 50, "How many features to track during initialization (saves on computation)")
 
 RTABMAP_PARAM (OdomOpenVINS, InitWindowTime, double, 2.0, "Amount of time we will initialize over (seconds)")
 
 RTABMAP_PARAM (OdomOpenVINS, Integration, int, 1, "0=discrete, 1=rk4, 2=analytical (if rk4 or analytical used then analytical covariance propagation is used)")
 
 RTABMAP_PARAM (OdomOpenVINS, MaxClones, int, 11, "Max clone size of sliding window")
 
 RTABMAP_PARAM (OdomOpenVINS, MaxMSCKFInUpdate, int, 50, "Max number of MSCKF features we will use at a given image timestep.")
 
 RTABMAP_PARAM (OdomOpenVINS, MaxSLAM, int, 50, "Max number of estimated SLAM features")
 
 RTABMAP_PARAM (OdomOpenVINS, MaxSLAMInUpdate, int, 25, "Max number of SLAM features we allow to be included in a single EKF update.")
 
 RTABMAP_PARAM (OdomOpenVINS, MinPxDist, int, 15, "Eistance between features (features near each other provide less information)")
 
 RTABMAP_PARAM (OdomOpenVINS, NumPts, int, 200, "Number of points (per camera) we will extract and try to track")
 
 RTABMAP_PARAM (OdomOpenVINS, TryZUPT, bool, true, "If we should try to use zero velocity update")
 
 RTABMAP_PARAM (OdomOpenVINS, UpMSCKFChi2Multiplier, double, 1.0, "Chi2 multiplier for MSCKF features")
 
 RTABMAP_PARAM (OdomOpenVINS, UpMSCKFSigmaPx, double, 1.0, "Pixel noise for MSCKF features")
 
 RTABMAP_PARAM (OdomOpenVINS, UpSLAMChi2Multiplier, double, 1.0, "Chi2 multiplier for SLAM features")
 
 RTABMAP_PARAM (OdomOpenVINS, UpSLAMSigmaPx, double, 1.0, "Pixel noise for SLAM features")
 
 RTABMAP_PARAM (OdomOpenVINS, UseFEJ, bool, true, "If first-estimate Jacobians should be used (enable for good consistency)")
 
 RTABMAP_PARAM (OdomOpenVINS, UseKLT, bool, true, "If true we will use KLT, otherwise use a ORB descriptor + robust matching")
 
 RTABMAP_PARAM (OdomOpenVINS, UseStereo, bool, true, "If we have more than 1 camera, if we should try to track stereo constraints between pairs")
 
 RTABMAP_PARAM (OdomOpenVINS, ZUPTChi2Multiplier, double, 0.0, "Chi2 multiplier for zero velocity")
 
 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)")
 
 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)")
 
 RTABMAP_PARAM (OdomOpenVINS, ZUPTNoiseMultiplier, double, 10.0, "Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)")
 
 RTABMAP_PARAM (OdomOpenVINS, ZUPTOnlyAtBeginning, bool, false, "If we should only use the zupt at the very beginning static initialization phase")
 
 RTABMAP_PARAM (OdomORBSLAM, AccNoise, double, 0.1, "IMU accelerometer \"white noise\".")
 
 RTABMAP_PARAM (OdomORBSLAM, AccWalk, double, 0.0001, "IMU accelerometer \"random walk\".")
 
 RTABMAP_PARAM (OdomORBSLAM, Bf, double, 0.076, "Fake IR projector baseline (m) used only when stereo is not used.")
 
 RTABMAP_PARAM (OdomORBSLAM, Fps, float, 0.0, "Camera FPS (0 to estimate from input data).")
 
 RTABMAP_PARAM (OdomORBSLAM, GyroNoise, double, 0.01, "IMU gyroscope \"white noise\".")
 
 RTABMAP_PARAM (OdomORBSLAM, GyroWalk, double, 0.000001, "IMU gyroscope \"random walk\".")
 
 RTABMAP_PARAM (OdomORBSLAM, Inertial, bool, false, "Enable IMU. Only supported with ORB_SLAM3.")
 
 RTABMAP_PARAM (OdomORBSLAM, MapSize, int, 3000, "Maximum size of the feature map (0 means infinite). Only supported with ORB_SLAM2.")
 
 RTABMAP_PARAM (OdomORBSLAM, MaxFeatures, int, 1000, "Maximum ORB features extracted per frame.")
 
 RTABMAP_PARAM (OdomORBSLAM, SamplingRate, double, 0, "IMU sampling rate (0 to estimate from input data).")
 
 RTABMAP_PARAM (OdomORBSLAM, ThDepth, double, 40.0, "Close/Far threshold. Baseline times.")
 
 RTABMAP_PARAM (OdomViso2, BucketHeight, double, 50, "Height of bucket.")
 
 RTABMAP_PARAM (OdomViso2, BucketMaxFeatures, int, 2, "Maximal number of features per bucket.")
 
 RTABMAP_PARAM (OdomViso2, BucketWidth, double, 50, "Width of bucket.")
 
 RTABMAP_PARAM (OdomViso2, InlierThreshold, double, 2.0, "Fundamental matrix inlier threshold.")
 
 RTABMAP_PARAM (OdomViso2, MatchBinsize, int, 50, "Matching bin width/height (affects efficiency only).")
 
 RTABMAP_PARAM (OdomViso2, MatchDispTolerance, int, 2, "Disparity tolerance for stereo matches (in pixels).")
 
 RTABMAP_PARAM (OdomViso2, MatchHalfResolution, bool, true, "Match at half resolution, refine at full resolution.")
 
 RTABMAP_PARAM (OdomViso2, MatchMultiStage, bool, true, "Multistage matching (denser and faster).")
 
 RTABMAP_PARAM (OdomViso2, MatchNmsN, int, 3, "Non-max-suppression: min. distance between maxima (in pixels).")
 
 RTABMAP_PARAM (OdomViso2, MatchNmsTau, int, 50, "Non-max-suppression: interest point peakiness threshold.")
 
 RTABMAP_PARAM (OdomViso2, MatchOutlierDispTolerance, int, 5, "Outlier removal: disparity tolerance (in pixels).")
 
 RTABMAP_PARAM (OdomViso2, MatchOutlierFlowTolerance, int, 5, "Outlier removal: flow tolerance (in pixels).")
 
 RTABMAP_PARAM (OdomViso2, MatchRadius, int, 200, "Matching radius (du/dv in pixels).")
 
 RTABMAP_PARAM (OdomViso2, MatchRefinement, int, 1, "Refinement (0=none,1=pixel,2=subpixel).")
 
 RTABMAP_PARAM (OdomViso2, RansacIters, int, 200, "Number of RANSAC iterations.")
 
 RTABMAP_PARAM (OdomViso2, Reweighting, bool, true, "Lower border weights (more robust to calibration errors).")
 
 RTABMAP_PARAM (Optimizer, Epsilon, double, 0.00001, "Stop optimizing when the error improvement is less than this value.")
 
 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()))
 
 RTABMAP_PARAM (Optimizer, Iterations, int, 100, "Optimization iterations.")
 
 RTABMAP_PARAM (Optimizer, LandmarksIgnored, bool, false, "Ignore landmark constraints while optimizing. Currently only g2o and gtsam optimization supports this.")
 
 RTABMAP_PARAM (Optimizer, PriorsIgnored, bool, true, "Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this.")
 
 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()))
 
 RTABMAP_PARAM (Optimizer, Strategy, int, 0, "Graph optimization strategy: 0=TORO, 1=g2o, 2=GTSAM and 3=Ceres.")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (ORB, FirstLevel, int, 0, "It should be 0 in the current implementation.")
 
 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.")
 
 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).")
 
 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.")
 
 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.")
 
 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.")
 
 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).")
 
 RTABMAP_PARAM (PyDescriptor, Dim, int, 4096, "Descriptor dimension.")
 
 RTABMAP_PARAM (PyDetector, Cuda, bool, true, "Use cuda.")
 
 RTABMAP_PARAM (PyMatcher, Cuda, bool, true, "Used by SuperGlue.")
 
 RTABMAP_PARAM (PyMatcher, Iterations, int, 20, "Sinkhorn iterations. Used by SuperGlue.")
 
 RTABMAP_PARAM (PyMatcher, Threshold, float, 0.2, "Used by SuperGlue.")
 
 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.")
 
 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.")
 
 RTABMAP_PARAM (Reg, Strategy, int, 0, "0=Vis, 1=Icp, 2=VisIcp")
 
 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()))
 
 RTABMAP_PARAM (RGBD, AngularSpeedUpdate, float, 0.0, "Maximum angular speed (rad/s) to update the map (0 means not limit).")
 
 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.")
 
 RTABMAP_PARAM (RGBD, CreateOccupancyGrid, bool, false, "Create local occupancy grid maps. See \"Grid\" group for parameters.")
 
 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.")
 
 RTABMAP_PARAM (RGBD, ForceOdom3DoF, bool, true, uFormat("Force odometry pose to be 3DoF if %s=true.", kRegForce3DoF().c_str()))
 
 RTABMAP_PARAM (RGBD, GoalReachedRadius, float, 0.5, "Goal reached radius (m).")
 
 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:#\".")
 
 RTABMAP_PARAM (RGBD, InvertedReg, bool, false, "On loop closure, do registration from the target to reference instead of reference to target.")
 
 RTABMAP_PARAM (RGBD, LinearSpeedUpdate, float, 0.0, "Maximum linear speed (m/s) to update the map (0 means not limit).")
 
 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.")
 
 RTABMAP_PARAM (RGBD, LocalBundleOnLoopClosure, bool, false, "Do local bundle adjustment with neighborhood of the loop closure.")
 
 RTABMAP_PARAM (RGBD, LocalImmunizationRatio, float, 0.25, "Ratio of working memory for which local nodes are immunized from transfer.")
 
 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()))
 
 RTABMAP_PARAM (RGBD, LocalizationSmoothing, bool, true, uFormat("Adjust localization constraints based on optimized odometry cache poses (when %s>0).", kRGBDMaxOdomCacheSize().c_str()))
 
 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.")
 
 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()))
 
 RTABMAP_PARAM (RGBD, LoopClosureReextractFeatures, bool, false, "Extract features even if there are some already in the nodes. Raw features are not saved in database.")
 
 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.")
 
 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.")
 
 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).")
 
 RTABMAP_PARAM (RGBD, MaxLoopClosureDistance, float, 0.0, "Reject loop closures/localizations if the distance from the map is over this distance (0=disabled).")
 
 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()))
 
 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()))
 
 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).")
 
 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).")
 
 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()))
 
 RTABMAP_PARAM (RGBD, PlanAngularVelocity, float, 0, "Angular velocity (rad/sec) used to compute path weights.")
 
 RTABMAP_PARAM (RGBD, PlanLinearVelocity, float, 0, "Linear velocity (m/sec) used to compute path weights.")
 
 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.")
 
 RTABMAP_PARAM (RGBD, ProximityAngle, float, 45, "Maximum angle (degrees) for one-to-one proximity detection.")
 
 RTABMAP_PARAM (RGBD, ProximityBySpace, bool, true, "Detection over locations (in Working Memory) near in space.")
 
 RTABMAP_PARAM (RGBD, ProximityByTime, bool, false, "Detection over all locations in STM.")
 
 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()))
 
 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.")
 
 RTABMAP_PARAM (RGBD, ProximityMaxPaths, int, 3, "Maximum paths compared (from the most recent) for proximity detection. 0 means no limit.")
 
 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()))
 
 RTABMAP_PARAM (RGBD, ProximityOdomGuess, bool, false, "Use odometry as motion guess for one-to-one proximity detection.")
 
 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.")
 
 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).")
 
 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.")
 
 RTABMAP_PARAM (RGBD, ScanMatchingIdsSavedInLinks, bool, true, "Save scan matching IDs from one-to-many proximity detection in link's user data.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, ComputeRMSE, bool, true, "Compute root mean square error (RMSE) and publish it in statistics, if ground truth is provided.")
 
 RTABMAP_PARAM (Rtabmap, CreateIntermediateNodes, bool, false, uFormat("Create intermediate nodes between loop closure detection. Only used when %s>0.", kRtabmapDetectionRate().c_str()))
 
 RTABMAP_PARAM (Rtabmap, DetectionRate, float, 1, "Detection rate (Hz). RTAB-Map will filter input images to satisfy this rate.")
 
 RTABMAP_PARAM (Rtabmap, ImageBufferSize, unsigned int, 1, "Data buffer size (0 min inf).")
 
 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.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, LoopRatio, float, 0, "The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.")
 
 RTABMAP_PARAM (Rtabmap, LoopThr, float, 0.11, "Loop closing threshold.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, MaxRetrieved, unsigned int, 2, "Maximum nodes retrieved at the same time from LTM.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, PublishLastSignature, bool, true, "Publishing last signature.")
 
 RTABMAP_PARAM (Rtabmap, PublishLikelihood, bool, true, "Publishing likelihood.")
 
 RTABMAP_PARAM (Rtabmap, PublishPdf, bool, true, "Publishing pdf.")
 
 RTABMAP_PARAM (Rtabmap, PublishRAMUsage, bool, false, "Publishing RAM usage in statistics (may add a small overhead to get info from the system).")
 
 RTABMAP_PARAM (Rtabmap, PublishStats, bool, true, "Publishing statistics.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, SaveWMState, bool, false, "Save working memory state after each update in statistics.")
 
 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()))
 
 RTABMAP_PARAM (Rtabmap, StartNewMapOnLoopClosure, bool, false, "Start a new map only if there is a global loop closure with a previous map.")
 
 RTABMAP_PARAM (Rtabmap, StatisticLogged, bool, false, "Logging enabled.")
 
 RTABMAP_PARAM (Rtabmap, StatisticLoggedHeaders, bool, true, "Add column header description to log files.")
 
 RTABMAP_PARAM (Rtabmap, StatisticLogsBufferedInRAM, bool, true, "Statistic logs buffered in RAM instead of written to hard drive after each iteration.")
 
 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.")
 
 RTABMAP_PARAM (Rtabmap, VirtualPlaceLikelihoodRatio, int, 0, "Likelihood ratio for virtual place (for no loop closure hypothesis): 0=Mean / StdDev, 1=StdDev / (Max-Mean)")
 
 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.")
 
 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).")
 
 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).")
 
 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.")
 
 RTABMAP_PARAM (SIFT, RootSIFT, bool, false, "Apply RootSIFT normalization of the descriptors.")
 
 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.")
 
 RTABMAP_PARAM (Stereo, DenseStrategy, int, 0, "0=cv::StereoBM, 1=cv::StereoSGBM")
 
 RTABMAP_PARAM (Stereo, Eps, double, 0.01, uFormat("[%s=true] Epsilon stop criterion.", kStereoOpticalFlow().c_str()))
 
 RTABMAP_PARAM (Stereo, Iterations, int, 30, "Maximum iterations.")
 
 RTABMAP_PARAM (Stereo, MaxDisparity, float, 128.0, "Maximum disparity.")
 
 RTABMAP_PARAM (Stereo, MaxLevel, int, 5, "Maximum pyramid level.")
 
 RTABMAP_PARAM (Stereo, MinDisparity, float, 0.5, "Minimum disparity.")
 
 RTABMAP_PARAM (Stereo, OpticalFlow, bool, true, "Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.")
 
 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()))
 
 RTABMAP_PARAM (Stereo, WinHeight, int, 3, "Window height.")
 
 RTABMAP_PARAM (Stereo, WinWidth, int, 15, "Window width.")
 
 RTABMAP_PARAM (StereoBM, BlockSize, int, 15, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, Disp12MaxDiff, int, -1, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, MinDisparity, int, 0, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, NumDisparities, int, 128, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, PreFilterCap, int, 31, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, PreFilterSize, int, 9, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, SpeckleRange, int, 4, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, SpeckleWindowSize, int, 100, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, TextureThreshold, int, 10, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoBM, UniquenessRatio, int, 15, "See cv::StereoBM")
 
 RTABMAP_PARAM (StereoSGBM, BlockSize, int, 15, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, Disp12MaxDiff, int, 1, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, MinDisparity, int, 0, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, Mode, int, 0, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, NumDisparities, int, 128, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, P1, int, 2, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, P2, int, 5, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, PreFilterCap, int, 31, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, SpeckleRange, int, 4, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, SpeckleWindowSize, int, 100, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (StereoSGBM, UniquenessRatio, int, 20, "See cv::StereoSGBM")
 
 RTABMAP_PARAM (SuperPoint, Cuda, bool, true, "Use Cuda device for Torch, otherwise CPU device is used by default.")
 
 RTABMAP_PARAM (SuperPoint, NMS, bool, true, "If true, non-maximum suppression is applied to detected keypoints.")
 
 RTABMAP_PARAM (SuperPoint, NMSRadius, int, 4, uFormat("[%s=true] Minimum distance (pixels) between keypoints.", kSuperPointNMS().c_str()))
 
 RTABMAP_PARAM (SuperPoint, Threshold, float, 0.010, "Detector response threshold to accept keypoint.")
 
 RTABMAP_PARAM (SURF, Extended, bool, false, "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).")
 
 RTABMAP_PARAM (SURF, GpuKeypointsRatio, float, 0.01, "Used with SURF GPU.")
 
 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.")
 
 RTABMAP_PARAM (SURF, HessianThreshold, float, 500, "Threshold for hessian keypoint detector used in SURF.")
 
 RTABMAP_PARAM (SURF, OctaveLayers, int, 2, "Number of octave layers within each octave.")
 
 RTABMAP_PARAM (SURF, Octaves, int, 4, "Number of pyramid octaves the keypoint detector will use.")
 
 RTABMAP_PARAM (SURF, Upright, bool, false, "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).")
 
 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()))
 
 RTABMAP_PARAM (VhEp, MatchCountMin, int, 8, "Minimum of matching visual words pairs to accept the loop hypothesis.")
 
 RTABMAP_PARAM (VhEp, RansacParam1, float, 3, "Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier.")
 
 RTABMAP_PARAM (VhEp, RansacParam2, float, 0.99, "Fundamental matrix (see cvFindFundamentalMat()): Performance of RANSAC.")
 
 RTABMAP_PARAM (Vis, BundleAdjustment, int, 0, "Optimization with bundle adjustment: 0=disabled, 1=g2o, 2=cvsba, 3=Ceres.")
 
 RTABMAP_PARAM (Vis, CorFlowEps, float, 0.01, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()))
 
 RTABMAP_PARAM (Vis, CorFlowIterations, int, 30, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()))
 
 RTABMAP_PARAM (Vis, CorFlowMaxLevel, int, 3, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()))
 
 RTABMAP_PARAM (Vis, CorFlowWinSize, int, 16, uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str()))
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Vis, CorNNDR, float, 0.8, uFormat("[%s=0] NNDR: nearest neighbor distance ratio. Used for knn features matching approach.", kVisCorType().c_str()))
 
 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()))
 
 RTABMAP_PARAM (Vis, CorType, int, 0, "Correspondences computation approach: 0=Features Matching, 1=Optical Flow")
 
 RTABMAP_PARAM (Vis, DepthAsMask, bool, true, "Use depth image as mask when extracting features.")
 
 RTABMAP_PARAM (Vis, EpipolarGeometryVar, float, 0.1, uFormat("[%s = 2] Epipolar geometry maximum variance to accept the transformation.", kVisEstimationType().c_str()))
 
 RTABMAP_PARAM (Vis, EstimationType, int, 1, "Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP), 2:2D->2D (Epipolar Geometry)")
 
 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")
 
 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).")
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Vis, InlierDistance, float, 0.1, uFormat("[%s = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.", kVisEstimationType().c_str()))
 
 RTABMAP_PARAM (Vis, Iterations, int, 300, "Maximum iterations to compute the transform.")
 
 RTABMAP_PARAM (Vis, MaxDepth, float, 0, "Max depth of the features (0 means no limit).")
 
 RTABMAP_PARAM (Vis, MaxFeatures, int, 1000, "0 no limits.")
 
 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.")
 
 RTABMAP_PARAM (Vis, MinDepth, float, 0, "Min depth of the features (0 means no limit).")
 
 RTABMAP_PARAM (Vis, MinInliers, int, 20, "Minimum feature correspondences to compute/accept the transformation.")
 
 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.")
 
 RTABMAP_PARAM (Vis, PnPFlags, int, 0, uFormat("[%s = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P", kVisEstimationType().c_str()))
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Vis, PnPReprojError, float, 2, uFormat("[%s = 1] PnP reprojection error.", kVisEstimationType().c_str()))
 
 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())
 
 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())
 
 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()))
 
 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()))
 
 RTABMAP_PARAM (Vis, SSC, bool, false, "If true, SSC (Suppression via Square Covering) is applied to limit keypoints.")
 
 RTABMAP_PARAM (Vis, SubPixEps, float, 0.02, "See cv::cornerSubPix().")
 
 RTABMAP_PARAM (Vis, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.")
 
 RTABMAP_PARAM (Vis, SubPixWinSize, int, 3, "See cv::cornerSubPix().")
 
 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, ...}.")
 
 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).")
 
 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()))
 
 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.")
 
 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())
 
 RTABMAP_PARAM_STR (Kp, DictionaryPath, "", "Path of the pre-computed dictionary")
 
 RTABMAP_PARAM_STR (Kp, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].")
 
 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).")
 
 RTABMAP_PARAM_STR (Mem, ImageCompressionFormat, ".jpg", "RGB image compression format. It should be \".jpg\" or \".png\".")
 
 RTABMAP_PARAM_STR (OdomOKVIS, ConfigPath, "", "Path of OKVIS config file.")
 
 RTABMAP_PARAM_STR (OdomOpenVINS, LeftMaskPath, "", "Mask for left image")
 
 RTABMAP_PARAM_STR (OdomOpenVINS, RightMaskPath, "", "Mask for right image")
 
 RTABMAP_PARAM_STR (OdomORBSLAM, VocPath, "", "Path to ORB vocabulary (*.txt).")
 
 RTABMAP_PARAM_STR (OdomVINS, ConfigPath, "", "Path of VINS config file.")
 
 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.")
 
 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.")
 
 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\").")
 
 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.")
 
 RTABMAP_PARAM_STR (Rtabmap, WorkingDirectory, "", "Working directory.")
 
 RTABMAP_PARAM_STR (SuperPoint, ModelPath, "", "[Required] Path to pre-trained weights Torch file of SuperPoint (*.pt).")
 
 RTABMAP_PARAM_STR (Vis, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].")
 

Static Private Attributes

static ParametersMap backwardCompatibilityMap_
 
static ParametersMap descriptions_
 
static Parameters instance_
 
static ParametersMap parameters_
 
static ParametersMap parametersType_
 
static std::map< std::string, std::pair< bool, std::string > > removedParameters_
 

Detailed Description

Class Parameters. This class is used to manage all custom parameters we want in the application. It was designed to be very easy to add a new parameter (just by adding one line of code). The macro PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE) is used to create a parameter in this class. A parameter can be accessed after by Parameters::defaultPARAMETERNAME() for the default value, Parameters::kPARAMETERNAME for his key (parameter name). The class provides also a general map containing all the parameter's key and default value. This map can be accessed anywhere in the application by Parameters::getDefaultParameters(); Example:

//Defining a parameter in this class with the macro PARAM:
PARAM(Video, ImageWidth, int, 640);
// Now from anywhere in the application (Parameters is a singleton)
int width = Parameters::defaultVideoImageWidth(); // theDefaultValue = 640
std::string theKey = Parameters::kVideoImageWidth(); // theKey = "Video/ImageWidth"
std::string strValue = Util::value(Parameters::getDefaultParameters(), theKey); // strValue = "640"
See also
getDefaultParameters() TODO Add a detailed example with simple classes

Definition at line 170 of file Parameters.h.

Constructor & Destructor Documentation

◆ ~Parameters()

rtabmap::Parameters::~Parameters ( )
virtual

Definition at line 62 of file Parameters.cpp.

◆ Parameters()

rtabmap::Parameters::Parameters ( )
private

Definition at line 58 of file Parameters.cpp.

Member Function Documentation

◆ createDefaultWorkingDirectory()

std::string rtabmap::Parameters::createDefaultWorkingDirectory ( )
static

Definition at line 66 of file Parameters.cpp.

◆ deserialize()

ParametersMap rtabmap::Parameters::deserialize ( const std::string parameters)
static

Definition at line 109 of file Parameters.cpp.

◆ filterParameters()

ParametersMap rtabmap::Parameters::filterParameters ( const ParametersMap parameters,
const std::string group,
bool  remove = false 
)
static

If remove=false: keep only parameters of the specified group. If remove=true: remove parameters of the specified group.

Definition at line 217 of file Parameters.cpp.

◆ getBackwardCompatibilityMap()

const ParametersMap & rtabmap::Parameters::getBackwardCompatibilityMap ( )
static

<NewKeyName, OldKeyName>

Definition at line 450 of file Parameters.cpp.

◆ getDefaultDatabaseName()

std::string rtabmap::Parameters::getDefaultDatabaseName ( )
static

Definition at line 88 of file Parameters.cpp.

◆ getDefaultOdometryParameters()

rtabmap::ParametersMap rtabmap::Parameters::getDefaultOdometryParameters ( bool  stereo = false,
bool  vis = true,
bool  icp = false 
)
static

Definition at line 174 of file Parameters.cpp.

◆ getDefaultParameters() [1/2]

static const ParametersMap& rtabmap::Parameters::getDefaultParameters ( )
inlinestatic

Get default parameters

Definition at line 896 of file Parameters.h.

◆ getDefaultParameters() [2/2]

ParametersMap rtabmap::Parameters::getDefaultParameters ( const std::string group)
static

Definition at line 200 of file Parameters.cpp.

◆ getDescription()

std::string rtabmap::Parameters::getDescription ( const std::string paramKey)
static

Get parameter description

Definition at line 485 of file Parameters.cpp.

◆ getRemovedParameters()

const std::map< std::string, std::pair< bool, std::string > > & rtabmap::Parameters::getRemovedParameters ( )
static

Get removed parameters (backward compatibility) <OldKeyName, <isEqual, NewKeyName> >, when isEqual=true, the old value can be safely copied to new parameter

Definition at line 233 of file Parameters.cpp.

◆ getType()

std::string rtabmap::Parameters::getType ( const std::string paramKey)
static

Get parameter type

Definition at line 470 of file Parameters.cpp.

◆ getVersion()

std::string rtabmap::Parameters::getVersion ( )
static

Definition at line 82 of file Parameters.cpp.

◆ isFeatureParameter()

bool rtabmap::Parameters::isFeatureParameter ( const std::string param)
static

Definition at line 158 of file Parameters.cpp.

◆ parse() [1/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
bool &  value 
)
static

Definition at line 500 of file Parameters.cpp.

◆ parse() [2/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
double &  value 
)
static

Definition at line 540 of file Parameters.cpp.

◆ parse() [3/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
float value 
)
static

Definition at line 530 of file Parameters.cpp.

◆ parse() [4/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
int value 
)
static

Definition at line 510 of file Parameters.cpp.

◆ parse() [5/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
std::string value 
)
static

Definition at line 550 of file Parameters.cpp.

◆ parse() [6/7]

bool rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string key,
unsigned int value 
)
static

Definition at line 520 of file Parameters.cpp.

◆ parse() [7/7]

void rtabmap::Parameters::parse ( const ParametersMap parameters,
ParametersMap parametersOut 
)
static

Definition at line 560 of file Parameters.cpp.

◆ parseArguments()

ParametersMap rtabmap::Parameters::parseArguments ( int  argc,
char *  argv[],
bool  onlyParameters = false 
)
static

Definition at line 599 of file Parameters.cpp.

◆ readINI()

void rtabmap::Parameters::readINI ( const std::string configFile,
ParametersMap parameters,
bool  modifiedOnly = false 
)
static

Definition at line 1273 of file Parameters.cpp.

◆ readINIStr()

void rtabmap::Parameters::readINIStr ( const std::string configContent,
ParametersMap parameters,
bool  modifiedOnly = false 
)
static

Definition at line 1280 of file Parameters.cpp.

◆ RTABMAP_PARAM() [1/536]

rtabmap::Parameters::RTABMAP_PARAM ( Bayes  ,
FullPredictionUpdate  ,
bool  ,
false  ,
"Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated)."   
)
private

◆ RTABMAP_PARAM() [2/536]

rtabmap::Parameters::RTABMAP_PARAM ( Bayes  ,
VirtualPlacePriorThr  ,
float  ,
0.  9,
"Virtual place prior  
)
private

◆ RTABMAP_PARAM() [3/536]

rtabmap::Parameters::RTABMAP_PARAM ( BRIEF  ,
Bytes  ,
int  ,
32  ,
"Bytes is a length of descriptor in bytes. It can be equal  16,
32 or 64 bytes."   
)
private

◆ RTABMAP_PARAM() [4/536]

rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
Octaves  ,
int  ,
,
"Detection octaves. Use 0 to do single scale."   
)
private

◆ RTABMAP_PARAM() [5/536]

rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
PatternScale  ,
float  ,
,
"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint."   
)
private

◆ RTABMAP_PARAM() [6/536]

rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
Thresh  ,
int  ,
30  ,
"FAST/AGAST detection threshold score."   
)
private

◆ RTABMAP_PARAM() [7/536]

rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
CacheSize  ,
unsigned int  ,
10000  ,
"Sqlite cache size (default is 2000)."   
)
private

◆ RTABMAP_PARAM() [8/536]

rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
InMemory  ,
bool  ,
false  ,
"Using database in the memory instead of a file on the hard disk."   
)
private

◆ RTABMAP_PARAM() [9/536]

rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
JournalMode  ,
int  ,
,
0 = DELETE,
= TRUNCATE,
= PERSIST,
= MEMORY 
)
private

◆ RTABMAP_PARAM() [10/536]

rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
Synchronous  ,
int  ,
,
0 = OFF,
= NORMAL 
)
private

◆ RTABMAP_PARAM() [11/536]

rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
TempStore  ,
int  ,
,
0 = DEFAULT,
= FILE 
)
private

◆ RTABMAP_PARAM() [12/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
CV  ,
int  ,
,
"Enable FastCV implementation if non-zero (and RTAB-Map is built with FastCV support). Values should be 9 and 10."   
)
private

◆ RTABMAP_PARAM() [13/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [14/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
GpuKeypointsRatio  ,
double  ,
0.  05,
"Used with FAST GPU."   
)
private

◆ RTABMAP_PARAM() [15/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
GridCols  ,
int  ,
,
"Grid cols (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell."   
)
private

◆ RTABMAP_PARAM() [16/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
GridRows  ,
int  ,
,
"Grid rows (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell."   
)
private

◆ RTABMAP_PARAM() [17/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
MaxThreshold  ,
int  ,
200  ,
"Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set."   
)
private

◆ RTABMAP_PARAM() [18/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
MinThreshold  ,
int  ,
,
"Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set."   
)
private

◆ RTABMAP_PARAM() [19/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
NonmaxSuppression  ,
bool  ,
true  ,
"If  true,
non-maximum suppression is applied to detected corners(keypoints)."   
)
private

◆ RTABMAP_PARAM() [20/536]

rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
Threshold  ,
int  ,
20  ,
"Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel."   
)
private

◆ RTABMAP_PARAM() [21/536]

rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
NOctaves  ,
int  ,
,
"Number of octaves covered by the detected keypoints."   
)
private

◆ RTABMAP_PARAM() [22/536]

rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
OrientationNormalized  ,
bool  ,
true  ,
"Enable orientation normalization."   
)
private

◆ RTABMAP_PARAM() [23/536]

rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
PatternScale  ,
float  ,
22  ,
"Scaling of the description pattern."   
)
private

◆ RTABMAP_PARAM() [24/536]

rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
ScaleNormalized  ,
bool  ,
true  ,
"Enable scale normalization."   
)
private

◆ RTABMAP_PARAM() [25/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [26/536]

rtabmap::Parameters::RTABMAP_PARAM ( g2o  ,
Optimizer  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [27/536]

rtabmap::Parameters::RTABMAP_PARAM ( g2o  ,
PixelVariance  ,
double  ,
1.  0,
"Pixel variance used for bundle adjustment."   
)
private

◆ RTABMAP_PARAM() [28/536]

rtabmap::Parameters::RTABMAP_PARAM ( g2o  ,
RobustKernelDelta  ,
double  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [29/536]

rtabmap::Parameters::RTABMAP_PARAM ( g2o  ,
Solver  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [30/536]

rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
BlockSize  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [31/536]

rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
K  ,
double  ,
0.  04,
""   
)
private

◆ RTABMAP_PARAM() [32/536]

rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
MinDistance  ,
double  ,
,
""   
)
private

◆ RTABMAP_PARAM() [33/536]

rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
QualityLevel  ,
double  ,
0.  001,
""   
)
private

◆ RTABMAP_PARAM() [34/536]

rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
UseHarrisDetector  ,
bool  ,
false  ,
""   
)
private

◆ RTABMAP_PARAM() [35/536]

rtabmap::Parameters::RTABMAP_PARAM ( GMS  ,
ThresholdFactor  ,
double  ,
6.  0,
"The  higher,
the less matches."   
)
private

◆ RTABMAP_PARAM() [36/536]

rtabmap::Parameters::RTABMAP_PARAM ( GMS  ,
WithRotation  ,
bool  ,
false  ,
"Take rotation transformation into account."   
)
private

◆ RTABMAP_PARAM() [37/536]

rtabmap::Parameters::RTABMAP_PARAM ( GMS  ,
WithScale  ,
bool  ,
false  ,
"Take scale transformation into account."   
)
private

◆ RTABMAP_PARAM() [38/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [39/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
CellSize  ,
float  ,
0.  05,
"Resolution of the occupancy grid."   
)
private

◆ RTABMAP_PARAM() [40/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
ClusterRadius  ,
float  ,
0.  1,
uFormat("[%s=true] Cluster maximum radius.", kGridNormalsSegmentation().c_str())   
)
private

◆ RTABMAP_PARAM() [41/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
DepthDecimation  ,
unsigned int  ,
,
uFormat("[%s=true] Decimation of the depth image before creating cloud.", kGridDepthDecimation().c_str())   
)
private

◆ RTABMAP_PARAM() [42/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
FlatObstacleDetected  ,
bool  ,
true  ,
uFormat("[%s=true] Flat obstacles detected.", kGridNormalsSegmentation().c_str())   
)
private

◆ RTABMAP_PARAM() [43/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [44/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
FootprintLength  ,
float  ,
0.  0,
"Footprint length used to filter points over the footprint of the robot."   
)
private

◆ RTABMAP_PARAM() [45/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
FootprintWidth  ,
float  ,
0.  0,
"Footprint width used to filter points over the footprint of the robot. Footprint length should be set."   
)
private

◆ RTABMAP_PARAM() [46/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [47/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [48/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [49/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
MaxGroundHeight  ,
float  ,
0.  0,
uFormat("Maximum ground height (0=disabled). Should be set if \"%s\" is false.", kGridNormalsSegmentation().c_str())   
)
private

◆ RTABMAP_PARAM() [50/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
MaxObstacleHeight  ,
float  ,
0.  0,
"Maximum obstacles height (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [51/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
MinClusterSize  ,
int  ,
10  ,
uFormat("[%s=true] Minimum cluster size to project the points.", kGridNormalsSegmentation().c_str())   
)
private

◆ RTABMAP_PARAM() [52/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
MinGroundHeight  ,
float  ,
0.  0,
"Minimum ground height (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [53/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
NoiseFilteringMinNeighbors  ,
int  ,
,
"Noise filtering minimum neighbors."   
)
private

◆ RTABMAP_PARAM() [54/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
NoiseFilteringRadius  ,
float  ,
0.  0,
"Noise filtering radius (0=disabled). Done after segmentation."   
)
private

◆ RTABMAP_PARAM() [55/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
NormalK  ,
int  ,
20  ,
uFormat("[%s=true] K neighbors to compute normals.", kGridNormalsSegmentation().c_str())   
)
private

◆ RTABMAP_PARAM() [56/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
NormalsSegmentation  ,
bool  ,
true  ,
"Segment ground from obstacles using point  normals,
otherwise a fast passthrough is used."   
)
private

◆ RTABMAP_PARAM() [57/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [58/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
RangeMax  ,
float  ,
5.  0 
)
private

◆ RTABMAP_PARAM() [59/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
RangeMin  ,
float  ,
0.  0,
"Minimum range from sensor."   
)
private

◆ RTABMAP_PARAM() [60/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [61/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [62/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
ScanDecimation  ,
int  ,
,
uFormat("[%s=0 or 2] Decimation of the laser scan before creating cloud.", kGridSensor().c_str())   
)
private

◆ RTABMAP_PARAM() [63/536]

rtabmap::Parameters::RTABMAP_PARAM ( Grid  ,
Sensor  ,
int  ,
,
"Create occupancy grid from selected sensor:  0 = laser scan 
)
private

◆ RTABMAP_PARAM() [64/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
AltitudeDelta  ,
float  ,
,
"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)."   
)
private

◆ RTABMAP_PARAM() [65/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
Eroded  ,
bool  ,
false  ,
"Erode obstacle cells."   
)
private

◆ RTABMAP_PARAM() [66/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
FloodFillDepth  ,
unsigned int  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [67/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
FootprintRadius  ,
float  ,
0.  0,
"Footprint radius (m) used to clear all obstacles under the graph."   
)
private

◆ RTABMAP_PARAM() [68/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
MaxNodes  ,
int  ,
,
"Maximum nodes assembled in the map starting from the last node (0=unlimited)."   
)
private

◆ RTABMAP_PARAM() [69/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
MinSize  ,
float  ,
0.  0,
"Minimum map size (m)."   
)
private

◆ RTABMAP_PARAM() [70/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
OccupancyThr  ,
float  ,
0.  5,
"Occupancy threshold (value between 0 and 1)."   
)
private

◆ RTABMAP_PARAM() [71/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
ProbClampingMax  ,
float  ,
0.  971,
"Probability clamping maximum (value between 0 and 1)."   
)
private

◆ RTABMAP_PARAM() [72/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
ProbClampingMin  ,
float  ,
0.  1192,
"Probability clamping minimum (value between 0 and 1)."   
)
private

◆ RTABMAP_PARAM() [73/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
ProbHit  ,
float  ,
0.  7,
"Probability of a hit (value between 0.5 and 1)."   
)
private

◆ RTABMAP_PARAM() [74/536]

rtabmap::Parameters::RTABMAP_PARAM ( GridGlobal  ,
ProbMiss  ,
float  ,
0.  4,
"Probability of a miss (value between 0 and 0.5)."   
)
private

◆ RTABMAP_PARAM() [75/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [76/536]

rtabmap::Parameters::RTABMAP_PARAM ( GTSAM  ,
IncRelinearizeSkip  ,
int  ,
,
"Only relinearize any variables every X calls to ISAM2::update(). See GTSAM::ISAM2 doc for more info."   
)
private

◆ RTABMAP_PARAM() [77/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [78/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [79/536]

rtabmap::Parameters::RTABMAP_PARAM ( GTSAM  ,
Optimizer  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [80/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
CCFilterOutFarthestPoints  ,
bool  ,
false  ,
"If  true,
the algorithm will automatically ignore farthest points from the  reference,
for better convergence."   
)
private

◆ RTABMAP_PARAM() [81/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
CCMaxFinalRMS  ,
float  ,
0.  2,
"Maximum final RMS error."   
)
private

◆ RTABMAP_PARAM() [82/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
CCSamplingLimit  ,
unsigned int  ,
50000  ,
"Maximum number of points per cloud (they are randomly resampled below this limit otherwise)."   
)
private

◆ RTABMAP_PARAM() [83/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
CorrespondenceRatio  ,
float  ,
0.  1,
"Ratio of matching correspondences to accept the transform."   
)
private

◆ RTABMAP_PARAM() [84/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
DownsamplingStep  ,
int  ,
,
"Downsampling step size (1=no sampling). This is done before uniform sampling."   
)
private

◆ RTABMAP_PARAM() [85/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
Epsilon  ,
float  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [86/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
FiltersEnabled  ,
int  ,
,
"Flag to enable filters:  1 = \"from\" cloud only, 2=\"to\" cloud only, 3=both." 
)
private

◆ RTABMAP_PARAM() [87/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
Force4DoF  ,
bool  ,
false  ,
uFormat("Limit ICP to x, y, z and yaw DoF. Available if %s > 0.", kIcpStrategy().c_str())   
)
private

◆ RTABMAP_PARAM() [88/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
Iterations  ,
int  ,
30  ,
"Max iterations."   
)
private

◆ RTABMAP_PARAM() [89/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
MaxCorrespondenceDistance  ,
float  ,
0.  05,
"Max distance for point correspondences."   
)
private

◆ RTABMAP_PARAM() [90/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
MaxRotation  ,
float  ,
0.  78,
"Maximum ICP rotation correction accepted (rad)."   
)
private

◆ RTABMAP_PARAM() [91/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
MaxTranslation  ,
float  ,
0.  2,
"Maximum ICP translation correction accepted (m)."   
)
private

◆ RTABMAP_PARAM() [92/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [93/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [94/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [95/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
PMMatcherKnn  ,
int  ,
,
"KDTreeMatcher/knn: number of nearest neighbors to consider it the reference. For convenience when configuration file is not set."   
)
private

◆ RTABMAP_PARAM() [96/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
PointToPlane  ,
bool  ,
false  ,
"Use point to plane ICP."   
)
private

◆ RTABMAP_PARAM() [97/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [98/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
PointToPlaneK  ,
int  ,
,
"Number of neighbors to compute normals for point to plane if the cloud doesn't have already normals."   
)
private

◆ RTABMAP_PARAM() [99/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
PointToPlaneLowComplexityStrategy  ,
int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [100/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [101/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
PointToPlaneRadius  ,
float  ,
0.  0,
"Search radius to compute normals for point to plane if the cloud doesn't have already normals."   
)
private

◆ RTABMAP_PARAM() [102/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
RangeMax  ,
float  ,
,
"Maximum range filtering (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [103/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
RangeMin  ,
float  ,
,
"Minimum range filtering (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [104/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [105/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
Strategy  ,
int  ,
,
"ICP implementation:  0 = Point Cloud Library,
= libpointmatcher 
)
private

◆ RTABMAP_PARAM() [106/536]

rtabmap::Parameters::RTABMAP_PARAM ( Icp  ,
VoxelSize  ,
float  ,
0.  05,
"Uniform sampling voxel size (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [107/536]

rtabmap::Parameters::RTABMAP_PARAM ( ImuFilter  ,
ComplementaryBiasAlpha  ,
double  ,
0.  01,
"Bias estimation gain  parameter,
belongs in ."  [0, 1] 
)
private

◆ RTABMAP_PARAM() [108/536]

rtabmap::Parameters::RTABMAP_PARAM ( ImuFilter  ,
ComplementaryDoAdpativeGain  ,
bool  ,
true  ,
"Parameter whether to do adaptive gain or not."   
)
private

◆ RTABMAP_PARAM() [109/536]

rtabmap::Parameters::RTABMAP_PARAM ( ImuFilter  ,
ComplementaryDoBiasEstimation  ,
bool  ,
true  ,
"Parameter whether to do bias estimation or not."   
)
private

◆ RTABMAP_PARAM() [110/536]

rtabmap::Parameters::RTABMAP_PARAM ( ImuFilter  ,
ComplementaryGainAcc  ,
double  ,
0.  01,
"Gain parameter for the complementary  filter,
belongs in ."  [0, 1] 
)
private

◆ RTABMAP_PARAM() [111/536]

rtabmap::Parameters::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] 
)
private

◆ RTABMAP_PARAM() [112/536]

rtabmap::Parameters::RTABMAP_PARAM ( ImuFilter  ,
MadgwickZeta  ,
double  ,
0.  0,
"Gyro drift gain   approx. rad/s,
belongs in ."  [-1, 1] 
)
private

◆ RTABMAP_PARAM() [113/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
Diffusivity  ,
int  ,
,
"Diffusivity type:  0 = DIFF_PM_G1,
= DIFF_PM_G2 
)
private

◆ RTABMAP_PARAM() [114/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
Extended  ,
bool  ,
false  ,
"Set to enable extraction of extended (128-byte) descriptor."   
)
private

◆ RTABMAP_PARAM() [115/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
NOctaveLayers  ,
int  ,
,
"Default number of sublevels per scale level."   
)
private

◆ RTABMAP_PARAM() [116/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
NOctaves  ,
int  ,
,
"Maximum octave evolution of the image."   
)
private

◆ RTABMAP_PARAM() [117/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
Threshold  ,
float  ,
0.  001,
"Detector response threshold to accept keypoint."   
)
private

◆ RTABMAP_PARAM() [118/536]

rtabmap::Parameters::RTABMAP_PARAM ( KAZE  ,
Upright  ,
bool  ,
false  ,
"Set to enable use of upright descriptors (non rotation-invariant)."   
)
private

◆ RTABMAP_PARAM() [119/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
BadSignRatio  ,
float  ,
0.  5,
"Bad signature ratio (less than Ratio x AverageWordsPerImage = bad)."   
)
private

◆ RTABMAP_PARAM() [120/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [121/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
DetectorStrategy  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [122/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [123/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
GridCols  ,
int  ,
,
uFormat("Number of columns of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kKpMaxFeatures().c_str())   
)
private

◆ RTABMAP_PARAM() [124/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
GridRows  ,
int  ,
,
uFormat("Number of rows of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kKpMaxFeatures().c_str())   
)
private

◆ RTABMAP_PARAM() [125/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
IncrementalDictionary  ,
bool  ,
true  ,
""   
)
private

◆ RTABMAP_PARAM() [126/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [127/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
MaxDepth  ,
float  ,
,
"Filter extracted keypoints by depth (0=inf)."   
)
private

◆ RTABMAP_PARAM() [128/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
MaxFeatures  ,
int  ,
500  ,
"Maximum features extracted from the images (0 means not bounded, <0 means no extraction)."   
)
private

◆ RTABMAP_PARAM() [129/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
MinDepth  ,
float  ,
,
"Filter extracted keypoints by depth."   
)
private

◆ RTABMAP_PARAM() [130/536]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM() [131/536]

rtabmap::Parameters::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.)"   
)
private

◆ RTABMAP_PARAM() [132/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
NNStrategy  ,
int  ,
,
kNNFlannNaive = 0,
kNNFlannKdTree  = 1,
kNNFlannLSH  = 2,
kNNBruteForce  = 3 
)
private

◆ RTABMAP_PARAM() [133/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
Parallelized  ,
bool  ,
true  ,
"If the dictionary update and signature creation were parallelized."   
)
private

◆ RTABMAP_PARAM() [134/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SSC  ,
bool  ,
false  ,
"If  true,
SSC(Suppression via Square Covering) is applied to limit keypoints."   
)
private

◆ RTABMAP_PARAM() [135/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixEps  ,
double  ,
0.  02,
"See cv::cornerSubPix()."   
)
private

◆ RTABMAP_PARAM() [136/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixIterations  ,
int  ,
,
"See cv::cornerSubPix(). 0 disables sub pixel refining."   
)
private

◆ RTABMAP_PARAM() [137/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixWinSize  ,
int  ,
,
"See cv::cornerSubPix()."   
)
private

◆ RTABMAP_PARAM() [138/536]

rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
TfIdfLikelihoodUsed  ,
bool  ,
true  ,
"Use of the td-idf strategy to compute the likelihood."   
)
private

◆ RTABMAP_PARAM() [139/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
CornerRefinementMethod  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [140/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
Dictionary  ,
int  ,
,
"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 
)
private

◆ RTABMAP_PARAM() [141/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
Length  ,
float  ,
,
"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)."   
)
private

◆ RTABMAP_PARAM() [142/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [143/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
MaxRange  ,
float  ,
0.  0,
"Maximum range in which markers will be detected. <=0 for unlimited range."   
)
private

◆ RTABMAP_PARAM() [144/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
MinRange  ,
float  ,
0.  0,
"Miniminum range in which markers will be detected. <=0 for unlimited range."   
)
private

◆ RTABMAP_PARAM() [145/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
PriorsVarianceAngular  ,
float  ,
0.  001,
"Angular variance to set on marker priors."   
)
private

◆ RTABMAP_PARAM() [146/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
PriorsVarianceLinear  ,
float  ,
0.  001,
"Linear variance to set on marker priors."   
)
private

◆ RTABMAP_PARAM() [147/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [148/536]

rtabmap::Parameters::RTABMAP_PARAM ( Marker  ,
VarianceLinear  ,
float  ,
0.  001,
"Linear variance to set on marker detections."   
)
private

◆ RTABMAP_PARAM() [149/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
BadSignaturesIgnored  ,
bool  ,
false  ,
"Bad signatures are ignored."   
)
private

◆ RTABMAP_PARAM() [150/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
BinDataKept  ,
bool  ,
true  ,
"Keep binary data in db."   
)
private

◆ RTABMAP_PARAM() [151/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
CompressionParallelized  ,
bool  ,
true  ,
"Compression of sensor data is multi-threaded."   
)
private

◆ RTABMAP_PARAM() [152/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
CovOffDiagIgnored  ,
bool  ,
true  ,
"Ignore off diagonal values of the covariance matrix."   
)
private

◆ RTABMAP_PARAM() [153/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
DepthAsMask  ,
bool  ,
true  ,
"Use depth image as mask when extracting features for vocabulary."   
)
private

◆ RTABMAP_PARAM() [154/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
GenerateIds  ,
bool  ,
true  ,
True = Generate location IDs 
)
private

◆ RTABMAP_PARAM() [155/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
GlobalDescriptorStrategy  ,
int  ,
,
"Extract global descriptor from sensor data.  0 = disabled 
)
private

◆ RTABMAP_PARAM() [156/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
ImageKept  ,
bool  ,
false  ,
"Keep raw images in RAM."   
)
private

◆ RTABMAP_PARAM() [157/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
ImagePostDecimation  ,
unsigned int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [158/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
ImagePreDecimation  ,
unsigned int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [159/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
IncrementalMemory  ,
bool  ,
true  ,
"SLAM  mode,
otherwise it is Localization mode."   
)
private

◆ RTABMAP_PARAM() [160/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [161/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
IntermediateNodeDataKept  ,
bool  ,
false  ,
"Keep intermediate node data in db."   
)
private

◆ RTABMAP_PARAM() [162/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
LaserScanDownsampleStepSize  ,
int  ,
,
If,
,
downsample the laser scans when creating a signature."   
)
private

◆ RTABMAP_PARAM() [163/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
LaserScanNormalK  ,
int  ,
,
If,
0 and laser scans don 't have  normals,
normals will be computed with K search neighbors when creating a signature."   
)
private

◆ RTABMAP_PARAM() [164/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [165/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [166/536]

rtabmap::Parameters::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()   
)
private

◆ RTABMAP_PARAM() [167/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [168/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
NotLinkedNodesKept  ,
bool  ,
true  ,
"Keep not linked nodes in db (rehearsed nodes and deleted nodes)."   
)
private

◆ RTABMAP_PARAM() [169/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RawDescriptorsKept  ,
bool  ,
true  ,
"Raw descriptors kept in memory."   
)
private

◆ RTABMAP_PARAM() [170/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RecentWmRatio  ,
float  ,
0.  2,
"Ratio of locations after the last loop closure in WM that cannot be transferred."   
)
private

◆ RTABMAP_PARAM() [171/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
ReduceGraph  ,
bool  ,
false  ,
"Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set)."   
)
private

◆ RTABMAP_PARAM() [172/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalIdUpdatedToNewOne  ,
bool  ,
false  ,
"On  merge,
update to new id. When  false,
no copy."   
)
private

◆ RTABMAP_PARAM() [173/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalSimilarity  ,
float  ,
0.  6,
"Rehearsal similarity."   
)
private

◆ RTABMAP_PARAM() [174/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalWeightIgnoredWhileMoving  ,
bool  ,
false  ,
"When the robot is  moving,
weights are not updated on rehearsal."   
)
private

◆ RTABMAP_PARAM() [175/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [176/536]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM() [177/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [178/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
STMSize  ,
unsigned int  ,
10  ,
"Short-term memory size."   
)
private

◆ RTABMAP_PARAM() [179/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [180/536]

rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
UseOdomFeatures  ,
bool  ,
true  ,
"Use odometry features instead of regenerating them."   
)
private

◆ RTABMAP_PARAM() [181/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [182/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
AlignWithGround  ,
bool  ,
false  ,
"Align odometry with the ground on initialization."   
)
private

◆ RTABMAP_PARAM() [183/536]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM() [184/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
FillInfoData  ,
bool  ,
true  ,
"Fill info with data (inliers/outliers features)."   
)
private

◆ RTABMAP_PARAM() [185/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
FilteringStrategy  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [186/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
GuessMotion  ,
bool  ,
true  ,
"Guess next transformation from the last motion computed."   
)
private

◆ RTABMAP_PARAM() [187/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
GuessSmoothingDelay  ,
float  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [188/536]

rtabmap::Parameters::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))."   
)
private

◆ RTABMAP_PARAM() [189/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ImageBufferSize  ,
unsigned int  ,
,
"Data buffer size (0 min inf)."   
)
private

◆ RTABMAP_PARAM() [190/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ImageDecimation  ,
unsigned int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [191/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
KalmanMeasurementNoise  ,
float  ,
0.  01,
"Process measurement covariance value."   
)
private

◆ RTABMAP_PARAM() [192/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
KalmanProcessNoise  ,
float  ,
0.  001,
"Process noise covariance value."   
)
private

◆ RTABMAP_PARAM() [193/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
KeyFrameThr  ,
float  ,
0.  3,
" 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."  [Visual] 
)
private

◆ RTABMAP_PARAM() [194/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ParticleLambdaR  ,
float  ,
100  ,
"Lambda of rotational components (roll,pitch,yaw)."   
)
private

◆ RTABMAP_PARAM() [195/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ParticleLambdaT  ,
float  ,
100  ,
"Lambda of translation components (x,y,z)."   
)
private

◆ RTABMAP_PARAM() [196/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ParticleNoiseR  ,
float  ,
0.  002,
"Noise (rad) of rotational components (roll,pitch,yaw)."   
)
private

◆ RTABMAP_PARAM() [197/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ParticleNoiseT  ,
float  ,
0.  002,
"Noise (m) of translation components (x,y,z)."   
)
private

◆ RTABMAP_PARAM() [198/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ParticleSize  ,
unsigned int  ,
400  ,
"Number of particles of the filter."   
)
private

◆ RTABMAP_PARAM() [199/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ResetCountdown  ,
int  ,
,
"Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset)."   
)
private

◆ RTABMAP_PARAM() [200/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
ScanKeyFrameThr  ,
float  ,
0.  9,
" 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."  [Geometry] 
)
private

◆ RTABMAP_PARAM() [201/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
Strategy  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [202/536]

rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
VisKeyFrameThr  ,
int  ,
150  ,
" 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."  [Visual] 
)
private

◆ RTABMAP_PARAM() [203/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
BundleAdjustment  ,
int  ,
,
"Local bundle adjustment:  0 = disabled,
= g2o,
= cvsba 
)
private

◆ RTABMAP_PARAM() [204/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
BundleAdjustmentMaxFrames  ,
int  ,
10  ,
"Maximum frames used for bundle adjustment (0=inf or all current frames in the local map)."   
)
private

◆ RTABMAP_PARAM() [205/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
MaxNewFeatures  ,
int  ,
,
" Maximum features (sorted by keypoint response) added to local map from a new key-frame. 0 means no limit."  [Visual] 
)
private

◆ RTABMAP_PARAM() [206/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
MaxSize  ,
int  ,
2000  ,
" Local map size:  If[Visual],
0(example 5000)  ,
the odometry will maintain a local map of X maximum words."   
)
private

◆ RTABMAP_PARAM() [207/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
ScanMaxSize  ,
int  ,
2000  ,
" Maximum local scan map size."  [Geometry] 
)
private

◆ RTABMAP_PARAM() [208/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
ScanRange  ,
float  ,
,
" Distance Range used to filter points of local map (when > 0). 0 means local map is updated using time and not range."  [Geometry] 
)
private

◆ RTABMAP_PARAM() [209/536]

rtabmap::Parameters::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()   
)
private

◆ RTABMAP_PARAM() [210/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomF2M  ,
ScanSubtractRadius  ,
float  ,
0.  05,
" Radius used to filter points of a new added scan to local map. This could match the voxel size of the scans."  [Geometry] 
)
private

◆ RTABMAP_PARAM() [211/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [212/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
BucketHeight  ,
int  ,
80  ,
""   
)
private

◆ RTABMAP_PARAM() [213/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
BucketWidth  ,
int  ,
80  ,
""   
)
private

◆ RTABMAP_PARAM() [214/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [215/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
FastThreshold  ,
int  ,
20  ,
"FAST threshold."   
)
private

◆ RTABMAP_PARAM() [216/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
FastThresholdAdaptiveGain  ,
double  ,
0.  005,
"FAST threshold adaptive gain."   
)
private

◆ RTABMAP_PARAM() [217/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [218/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
FeatureWindowSize  ,
int  ,
,
"The size of the n x n image patch surrounding each  feature,
used for keypoint matching."   
)
private

◆ RTABMAP_PARAM() [219/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [220/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
MaxKeypointsPerBucket  ,
int  ,
25  ,
""   
)
private

◆ RTABMAP_PARAM() [221/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
MaxMeanReprojectionError  ,
double  ,
10.  0,
"Maximum mean reprojection error over the inlier feature matches for the motion estimate to be considered valid."   
)
private

◆ RTABMAP_PARAM() [222/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
MaxPyramidLevel  ,
int  ,
,
"The maximum Gaussian pyramid level to process the image at. Pyramid level 1 corresponds to the original image."   
)
private

◆ RTABMAP_PARAM() [223/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
MinFeaturesForEstimate  ,
int  ,
20  ,
"Minimum number of features in the inlier set for the motion estimate to be considered valid."   
)
private

◆ RTABMAP_PARAM() [224/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
MinPyramidLevel  ,
int  ,
,
"The minimum pyramid level."   
)
private

◆ RTABMAP_PARAM() [225/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
StereoMaxDisparity  ,
int  ,
128  ,
""   
)
private

◆ RTABMAP_PARAM() [226/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
StereoMaxDistEpipolarLine  ,
double  ,
1.  5,
""   
)
private

◆ RTABMAP_PARAM() [227/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
StereoMaxRefinementDisplacement  ,
double  ,
1.  0,
""   
)
private

◆ RTABMAP_PARAM() [228/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
StereoRequireMutualMatch  ,
bool  ,
true  ,
""   
)
private

◆ RTABMAP_PARAM() [229/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [230/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [231/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
UseAdaptiveThreshold  ,
bool  ,
true  ,
"Use FAST adaptive threshold."   
)
private

◆ RTABMAP_PARAM() [232/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
UseBucketing  ,
bool  ,
true  ,
""   
)
private

◆ RTABMAP_PARAM() [233/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
UseHomographyInitialization  ,
bool  ,
true  ,
"Use homography initialization."   
)
private

◆ RTABMAP_PARAM() [234/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
UseImageNormalization  ,
bool  ,
false  ,
""   
)
private

◆ RTABMAP_PARAM() [235/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomFovis  ,
UseSubpixelRefinement  ,
bool  ,
true  ,
"Specifies whether or not to refine feature matches to subpixel resolution."   
)
private

◆ RTABMAP_PARAM() [236/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
AngVar  ,
float  ,
0.  01,
"Angular output variance."   
)
private

◆ RTABMAP_PARAM() [237/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
LinVar  ,
float  ,
0.  01,
"Linear output variance."   
)
private

◆ RTABMAP_PARAM() [238/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
LocalMapping  ,
bool  ,
true  ,
"Local mapping. It adds more time to compute  odometry,
but accuracy is significantly improved."   
)
private

◆ RTABMAP_PARAM() [239/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
Resolution  ,
float  ,
0.  2,
"Map resolution"   
)
private

◆ RTABMAP_PARAM() [240/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
ScanPeriod  ,
float  ,
0.  1,
"Scan period (s)"   
)
private

◆ RTABMAP_PARAM() [241/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomLOAM  ,
Sensor  ,
int  ,
,
"Velodyne sensor:  0 = VLP-16,
= HDL-32 
)
private

◆ RTABMAP_PARAM() [242/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMono  ,
InitMinFlow  ,
float  ,
100  ,
"Minimum optical flow required for the initialization step."   
)
private

◆ RTABMAP_PARAM() [243/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMono  ,
InitMinTranslation  ,
float  ,
0.  1,
"Minimum translation required for the initialization step."   
)
private

◆ RTABMAP_PARAM() [244/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMono  ,
MaxVariance  ,
float  ,
0.  01,
"Maximum variance to add new points to local map."   
)
private

◆ RTABMAP_PARAM() [245/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [246/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
FastThreshold  ,
int  ,
10  ,
""   
)
private

◆ RTABMAP_PARAM() [247/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
GridCol  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [248/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
GridMaxFeatureNum  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [249/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
GridMinFeatureNum  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [250/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
GridRow  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [251/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
InitCovAccBias  ,
double  ,
0.  01,
""   
)
private

◆ RTABMAP_PARAM() [252/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
InitCovExRot  ,
double  ,
0.  00030462,
""   
)
private

◆ RTABMAP_PARAM() [253/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
InitCovExTrans  ,
double  ,
0.  000025,
""   
)
private

◆ RTABMAP_PARAM() [254/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
InitCovGyroBias  ,
double  ,
0.  01,
""   
)
private

◆ RTABMAP_PARAM() [255/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
InitCovVel  ,
double  ,
0.  25,
""   
)
private

◆ RTABMAP_PARAM() [256/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
MaxCamStateSize  ,
int  ,
20  ,
""   
)
private

◆ RTABMAP_PARAM() [257/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
MaxIteration  ,
int  ,
30  ,
""   
)
private

◆ RTABMAP_PARAM() [258/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
NoiseAcc  ,
double  ,
0.  05,
""   
)
private

◆ RTABMAP_PARAM() [259/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
NoiseAccBias  ,
double  ,
0.  01,
""   
)
private

◆ RTABMAP_PARAM() [260/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
NoiseFeature  ,
double  ,
0.  035,
""   
)
private

◆ RTABMAP_PARAM() [261/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
NoiseGyro  ,
double  ,
0.  005,
""   
)
private

◆ RTABMAP_PARAM() [262/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
NoiseGyroBias  ,
double  ,
0.  001,
""   
)
private

◆ RTABMAP_PARAM() [263/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
OptTranslationThreshold  ,
double  ,
,
""   
)
private

◆ RTABMAP_PARAM() [264/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
PatchSize  ,
int  ,
15  ,
""   
)
private

◆ RTABMAP_PARAM() [265/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
PositionStdThreshold  ,
double  ,
8.  0,
""   
)
private

◆ RTABMAP_PARAM() [266/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
PyramidLevels  ,
int  ,
,
""   
)
private

◆ RTABMAP_PARAM() [267/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
RansacThreshold  ,
double  ,
,
""   
)
private

◆ RTABMAP_PARAM() [268/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
RotationThreshold  ,
double  ,
0.  2618,
""   
)
private

◆ RTABMAP_PARAM() [269/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
StereoThreshold  ,
double  ,
,
""   
)
private

◆ RTABMAP_PARAM() [270/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
TrackingRateThreshold  ,
double  ,
0.  5,
""   
)
private

◆ RTABMAP_PARAM() [271/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
TrackPrecision  ,
double  ,
0.  01,
""   
)
private

◆ RTABMAP_PARAM() [272/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomMSCKF  ,
TranslationThreshold  ,
double  ,
0.  4,
""   
)
private

◆ RTABMAP_PARAM() [273/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpen3D  ,
MaxDepth  ,
float  ,
3.  0,
"Maximum depth."   
)
private

◆ RTABMAP_PARAM() [274/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpen3D  ,
Method  ,
int  ,
,
"Registration method:  0 = PointToPlane,
= Intensity 
)
private

◆ RTABMAP_PARAM() [275/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
AccelerometerNoiseDensity  ,
double  ,
0.  01,
" (accel \"white noise\")"  [m/s^2/sqrt(Hz)] 
)
private

◆ RTABMAP_PARAM() [276/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
AccelerometerRandomWalk  ,
double  ,
0.  001,
" (accel bias diffusion)"  [m/s^3/sqrt(Hz)] 
)
private

◆ RTABMAP_PARAM() [277/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
CalibCamExtrinsics  ,
bool  ,
false  ,
"Bool to determine whether or not to calibrate imu-to-camera pose  
)
private

◆ RTABMAP_PARAM() [278/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
CalibCamIntrinsics  ,
bool  ,
false  ,
"Bool to determine whether or not to calibrate camera intrinsics"   
)
private

◆ RTABMAP_PARAM() [279/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
CalibCamTimeoffset  ,
bool  ,
false  ,
"Bool to determine whether or not to calibrate camera to IMU time offset  
)
private

◆ RTABMAP_PARAM() [280/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
CalibIMUGSensitivity  ,
bool  ,
false  ,
"Bool to determine whether or not to calibrate the Gravity sensitivity"   
)
private

◆ RTABMAP_PARAM() [281/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
CalibIMUIntrinsics  ,
bool  ,
false  ,
"Bool to determine whether or not to calibrate the IMU intrinsics"   
)
private

◆ RTABMAP_PARAM() [282/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
DtSLAMDelay  ,
double  ,
0.  0,
Delay,
in  seconds,
that we should wait from init before we start estimating SLAM features"   
)
private

◆ RTABMAP_PARAM() [283/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FeatRepMSCKF  ,
int  ,
,
"What representation our features are in (msckf features)"   
)
private

◆ RTABMAP_PARAM() [284/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FeatRepSLAM  ,
int  ,
,
"What representation our features are in (slam features)"   
)
private

◆ RTABMAP_PARAM() [285/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FiMaxBaseline  ,
double  ,
40  ,
"Max baseline ratio to accept triangulated features"   
)
private

◆ RTABMAP_PARAM() [286/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FiMaxCondNumber  ,
double  ,
10000  ,
"Max condition number of linear triangulation matrix accept triangulated features"   
)
private

◆ RTABMAP_PARAM() [287/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FiMaxRuns  ,
int  ,
,
"Max runs for Levenberg-Marquardt"   
)
private

◆ RTABMAP_PARAM() [288/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FiRefineFeatures  ,
bool  ,
true  ,
"If we should perform Levenberg-Marquardt refinement"   
)
private

◆ RTABMAP_PARAM() [289/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
FiTriangulate1d  ,
bool  ,
false  ,
"If we should perform 1d triangulation instead of 3d  
)
private

◆ RTABMAP_PARAM() [290/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
GravityMag  ,
double  ,
9.  81,
"Gravity magnitude in the global frame (i.e. should be 9.81 typically)"   
)
private

◆ RTABMAP_PARAM() [291/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
GyroscopeNoiseDensity  ,
double  ,
0.  001,
" (gyro \"white noise\")"  [rad/s/sqrt(Hz)] 
)
private

◆ RTABMAP_PARAM() [292/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
GyroscopeRandomWalk  ,
double  ,
0.  0001,
" (gyro bias diffusion)"  [rad/s^2/sqrt(Hz)] 
)
private

◆ RTABMAP_PARAM() [293/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynInflationBa  ,
double  ,
100.  0,
"What to inflate the recovered bias_a covariance by"   
)
private

◆ RTABMAP_PARAM() [294/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynInflationBg  ,
double  ,
10.  0,
"What to inflate the recovered bias_g covariance by"   
)
private

◆ RTABMAP_PARAM() [295/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynInflationOri  ,
double  ,
10.  0,
"What to inflate the recovered q_GtoI covariance by"   
)
private

◆ RTABMAP_PARAM() [296/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynInflationVel  ,
double  ,
100.  0,
"What to inflate the recovered v_IinG covariance by"   
)
private

◆ RTABMAP_PARAM() [297/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMinDeg  ,
double  ,
10.  0,
"Orientation change needed to try to init  
)
private

◆ RTABMAP_PARAM() [298/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMinRecCond  ,
double  ,
1e 15,
"Reciprocal condition number thresh for info inversion"   
)
private

◆ RTABMAP_PARAM() [299/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMLEMaxIter  ,
int  ,
50  ,
"How many iterations the MLE refinement should use (zero to skip the MLE)"   
)
private

◆ RTABMAP_PARAM() [300/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMLEMaxThreads  ,
int  ,
,
"How many threads the MLE should use"   
)
private

◆ RTABMAP_PARAM() [301/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMLEMaxTime  ,
double  ,
0.  05,
"How many seconds the MLE should be completed in"   
)
private

◆ RTABMAP_PARAM() [302/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynMLEOptCalib  ,
bool  ,
false  ,
"If we should optimize calibration during intialization (not recommended)"   
)
private

◆ RTABMAP_PARAM() [303/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynNumPose  ,
int  ,
,
"Number of poses to use within our window time (evenly spaced)"   
)
private

◆ RTABMAP_PARAM() [304/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitDynUse  ,
bool  ,
false  ,
"If dynamic initialization should be used"   
)
private

◆ RTABMAP_PARAM() [305/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitIMUThresh  ,
double  ,
1.  0,
"Variance threshold on our acceleration to be classified as moving"   
)
private

◆ RTABMAP_PARAM() [306/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitMaxDisparity  ,
double  ,
10.  0,
"Max disparity to consider the platform stationary (dependent on resolution)"   
)
private

◆ RTABMAP_PARAM() [307/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitMaxFeatures  ,
int  ,
50  ,
"How many features to track during initialization (saves on computation)"   
)
private

◆ RTABMAP_PARAM() [308/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
InitWindowTime  ,
double  ,
2.  0,
"Amount of time we will initialize over (seconds)"   
)
private

◆ RTABMAP_PARAM() [309/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
Integration  ,
int  ,
,
0 = discrete,
= rk4 
)
private

◆ RTABMAP_PARAM() [310/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
MaxClones  ,
int  ,
11  ,
"Max clone size of sliding window"   
)
private

◆ RTABMAP_PARAM() [311/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
MaxMSCKFInUpdate  ,
int  ,
50  ,
"Max number of MSCKF features we will use at a given image timestep."   
)
private

◆ RTABMAP_PARAM() [312/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
MaxSLAM  ,
int  ,
50  ,
"Max number of estimated SLAM features"   
)
private

◆ RTABMAP_PARAM() [313/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
MaxSLAMInUpdate  ,
int  ,
25  ,
"Max number of SLAM features we allow to be included in a single EKF update."   
)
private

◆ RTABMAP_PARAM() [314/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
MinPxDist  ,
int  ,
15  ,
"Eistance between features (features near each other provide less information)"   
)
private

◆ RTABMAP_PARAM() [315/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
NumPts  ,
int  ,
200  ,
"Number of points (per camera) we will extract and try to track"   
)
private

◆ RTABMAP_PARAM() [316/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
TryZUPT  ,
bool  ,
true  ,
"If we should try to use zero velocity update  
)
private

◆ RTABMAP_PARAM() [317/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UpMSCKFChi2Multiplier  ,
double  ,
1.  0,
"Chi2 multiplier for MSCKF features"   
)
private

◆ RTABMAP_PARAM() [318/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UpMSCKFSigmaPx  ,
double  ,
1.  0,
"Pixel noise for MSCKF features"   
)
private

◆ RTABMAP_PARAM() [319/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UpSLAMChi2Multiplier  ,
double  ,
1.  0,
"Chi2 multiplier for SLAM features"   
)
private

◆ RTABMAP_PARAM() [320/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UpSLAMSigmaPx  ,
double  ,
1.  0,
"Pixel noise for SLAM features"   
)
private

◆ RTABMAP_PARAM() [321/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UseFEJ  ,
bool  ,
true  ,
"If first-estimate Jacobians should be used (enable for good consistency)"   
)
private

◆ RTABMAP_PARAM() [322/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UseKLT  ,
bool  ,
true  ,
"If true we will use  KLT,
otherwise use a ORB descriptor+robust matching"   
)
private

◆ RTABMAP_PARAM() [323/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
UseStereo  ,
bool  ,
true  ,
"If we have more than 1  camera,
if we should try to track stereo constraints between pairs"   
)
private

◆ RTABMAP_PARAM() [324/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
ZUPTChi2Multiplier  ,
double  ,
0.  0,
"Chi2 multiplier for zero velocity  
)
private

◆ RTABMAP_PARAM() [325/536]

rtabmap::Parameters::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)"   
)
private

◆ RTABMAP_PARAM() [326/536]

rtabmap::Parameters::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)"   
)
private

◆ RTABMAP_PARAM() [327/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
ZUPTNoiseMultiplier  ,
double  ,
10.  0,
"Multiplier of our zupt measurement IMU noise matrix (default should be 1.0)"   
)
private

◆ RTABMAP_PARAM() [328/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomOpenVINS  ,
ZUPTOnlyAtBeginning  ,
bool  ,
false  ,
"If we should only use the zupt at the very beginning static initialization phase"   
)
private

◆ RTABMAP_PARAM() [329/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
AccNoise  ,
double  ,
0.  1,
"IMU accelerometer \"white noise\"."   
)
private

◆ RTABMAP_PARAM() [330/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
AccWalk  ,
double  ,
0.  0001,
"IMU accelerometer \"random walk\"."   
)
private

◆ RTABMAP_PARAM() [331/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
Bf  ,
double  ,
0.  076,
"Fake IR projector baseline (m) used only when stereo is not used."   
)
private

◆ RTABMAP_PARAM() [332/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
Fps  ,
float  ,
0.  0,
"Camera FPS (0 to estimate from input data)."   
)
private

◆ RTABMAP_PARAM() [333/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
GyroNoise  ,
double  ,
0.  01,
"IMU gyroscope \"white noise\"."   
)
private

◆ RTABMAP_PARAM() [334/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
GyroWalk  ,
double  ,
0.  000001,
"IMU gyroscope \"random walk\"."   
)
private

◆ RTABMAP_PARAM() [335/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
Inertial  ,
bool  ,
false  ,
"Enable IMU. Only supported with ORB_SLAM3."   
)
private

◆ RTABMAP_PARAM() [336/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
MapSize  ,
int  ,
3000  ,
"Maximum size of the feature map (0 means infinite). Only supported with ORB_SLAM2."   
)
private

◆ RTABMAP_PARAM() [337/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
MaxFeatures  ,
int  ,
1000  ,
"Maximum ORB features extracted per frame."   
)
private

◆ RTABMAP_PARAM() [338/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
SamplingRate  ,
double  ,
,
"IMU sampling rate (0 to estimate from input data)."   
)
private

◆ RTABMAP_PARAM() [339/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomORBSLAM  ,
ThDepth  ,
double  ,
40.  0,
"Close/Far threshold. Baseline times."   
)
private

◆ RTABMAP_PARAM() [340/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
BucketHeight  ,
double  ,
50  ,
"Height of bucket."   
)
private

◆ RTABMAP_PARAM() [341/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
BucketMaxFeatures  ,
int  ,
,
"Maximal number of features per bucket."   
)
private

◆ RTABMAP_PARAM() [342/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
BucketWidth  ,
double  ,
50  ,
"Width of bucket."   
)
private

◆ RTABMAP_PARAM() [343/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
InlierThreshold  ,
double  ,
2.  0,
"Fundamental matrix inlier threshold."   
)
private

◆ RTABMAP_PARAM() [344/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchBinsize  ,
int  ,
50  ,
"Matching bin width/height (affects efficiency only)."   
)
private

◆ RTABMAP_PARAM() [345/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchDispTolerance  ,
int  ,
,
"Disparity tolerance for stereo matches (in pixels)."   
)
private

◆ RTABMAP_PARAM() [346/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchHalfResolution  ,
bool  ,
true  ,
"Match at half  resolution,
refine at full resolution."   
)
private

◆ RTABMAP_PARAM() [347/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchMultiStage  ,
bool  ,
true  ,
"Multistage matching (denser and faster)."   
)
private

◆ RTABMAP_PARAM() [348/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchNmsN  ,
int  ,
,
"Non-max-suppression: min. distance between maxima (in pixels)."   
)
private

◆ RTABMAP_PARAM() [349/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchNmsTau  ,
int  ,
50  ,
"Non-max-suppression: interest point peakiness threshold."   
)
private

◆ RTABMAP_PARAM() [350/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchOutlierDispTolerance  ,
int  ,
,
"Outlier removal: disparity tolerance (in pixels)."   
)
private

◆ RTABMAP_PARAM() [351/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchOutlierFlowTolerance  ,
int  ,
,
"Outlier removal: flow tolerance (in pixels)."   
)
private

◆ RTABMAP_PARAM() [352/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchRadius  ,
int  ,
200  ,
"Matching radius (du/dv in pixels)."   
)
private

◆ RTABMAP_PARAM() [353/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
MatchRefinement  ,
int  ,
,
"Refinement (0=none,1=pixel,2=subpixel)."   
)
private

◆ RTABMAP_PARAM() [354/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
RansacIters  ,
int  ,
200  ,
"Number of RANSAC iterations."   
)
private

◆ RTABMAP_PARAM() [355/536]

rtabmap::Parameters::RTABMAP_PARAM ( OdomViso2  ,
Reweighting  ,
bool  ,
true  ,
"Lower border weights (more robust to calibration errors)."   
)
private

◆ RTABMAP_PARAM() [356/536]

rtabmap::Parameters::RTABMAP_PARAM ( Optimizer  ,
Epsilon  ,
double  ,
0.  00001,
"Stop optimizing when the error improvement is less than this value."   
)
private

◆ RTABMAP_PARAM() [357/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [358/536]

rtabmap::Parameters::RTABMAP_PARAM ( Optimizer  ,
Iterations  ,
int  ,
100  ,
"Optimization iterations."   
)
private

◆ RTABMAP_PARAM() [359/536]

rtabmap::Parameters::RTABMAP_PARAM ( Optimizer  ,
LandmarksIgnored  ,
bool  ,
false  ,
"Ignore landmark constraints while optimizing. Currently only g2o and gtsam optimization supports this."   
)
private

◆ RTABMAP_PARAM() [360/536]

rtabmap::Parameters::RTABMAP_PARAM ( Optimizer  ,
PriorsIgnored  ,
bool  ,
true  ,
"Ignore prior constraints (global pose or GPS) while optimizing. Currently only g2o and gtsam optimization supports this."   
)
private

◆ RTABMAP_PARAM() [361/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [362/536]

rtabmap::Parameters::RTABMAP_PARAM ( Optimizer  ,
Strategy  ,
int  ,
,
"Graph optimization strategy:  0 = TORO,
= g2o 
)
private

◆ RTABMAP_PARAM() [363/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [364/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [365/536]

rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
FirstLevel  ,
int  ,
,
"It should be 0 in the current implementation."   
)
private

◆ RTABMAP_PARAM() [366/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [367/536]

rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
NLevels  ,
int  ,
,
"The number of pyramid levels. The smallest level will have linear size equal to input_image_linear_size/pow(scaleFactor, nlevels)."   
)
private

◆ RTABMAP_PARAM() [368/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [369/536]

rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
ScaleFactor  ,
float  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [370/536]

rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
ScoreType  ,
int  ,
,
"The default  HARRIS_SCORE = 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."   
)
private

◆ RTABMAP_PARAM() [371/536]

rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
WTA_K  ,
int  ,
,
"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   pointsof 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)."   
)
private

◆ RTABMAP_PARAM() [372/536]

rtabmap::Parameters::RTABMAP_PARAM ( PyDescriptor  ,
Dim  ,
int  ,
4096  ,
"Descriptor dimension."   
)
private

◆ RTABMAP_PARAM() [373/536]

rtabmap::Parameters::RTABMAP_PARAM ( PyDetector  ,
Cuda  ,
bool  ,
true  ,
"Use cuda."   
)
private

◆ RTABMAP_PARAM() [374/536]

rtabmap::Parameters::RTABMAP_PARAM ( PyMatcher  ,
Cuda  ,
bool  ,
true  ,
"Used by SuperGlue."   
)
private

◆ RTABMAP_PARAM() [375/536]

rtabmap::Parameters::RTABMAP_PARAM ( PyMatcher  ,
Iterations  ,
int  ,
20  ,
"Sinkhorn iterations. Used by SuperGlue."   
)
private

◆ RTABMAP_PARAM() [376/536]

rtabmap::Parameters::RTABMAP_PARAM ( PyMatcher  ,
Threshold  ,
float  ,
0.  2,
"Used by SuperGlue."   
)
private

◆ RTABMAP_PARAM() [377/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [378/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [379/536]

rtabmap::Parameters::RTABMAP_PARAM ( Reg  ,
Strategy  ,
int  ,
,
0 = Vis,
= Icp 
)
private

◆ RTABMAP_PARAM() [380/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [381/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
AngularSpeedUpdate  ,
float  ,
0.  0,
"Maximum angular speed (rad/s) to update the map (0 means not limit)."   
)
private

◆ RTABMAP_PARAM() [382/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [383/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
CreateOccupancyGrid  ,
bool  ,
false  ,
"Create local occupancy grid maps. See \"Grid\" group for parameters."   
)
private

◆ RTABMAP_PARAM() [384/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [385/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ForceOdom3DoF  ,
bool  ,
true  ,
uFormat("Force odometry pose to be 3DoF if %s=true.", kRegForce3DoF().c_str())   
)
private

◆ RTABMAP_PARAM() [386/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
GoalReachedRadius  ,
float  ,
0.  5,
"Goal reached radius (m)."   
)
private

◆ RTABMAP_PARAM() [387/536]

rtabmap::Parameters::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:#\"."   
)
private

◆ RTABMAP_PARAM() [388/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
InvertedReg  ,
bool  ,
false  ,
"On loop  closure,
do registration from the target to reference instead of reference to target."   
)
private

◆ RTABMAP_PARAM() [389/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LinearSpeedUpdate  ,
float  ,
0.  0,
"Maximum linear speed (m/s) to update the map (0 means not limit)."   
)
private

◆ RTABMAP_PARAM() [390/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [391/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalBundleOnLoopClosure  ,
bool  ,
false  ,
"Do local bundle adjustment with neighborhood of the loop closure."   
)
private

◆ RTABMAP_PARAM() [392/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalImmunizationRatio  ,
float  ,
0.  25,
"Ratio of working memory for which local nodes are immunized from transfer."   
)
private

◆ RTABMAP_PARAM() [393/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [394/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalizationSmoothing  ,
bool  ,
true  ,
uFormat("Adjust localization constraints based on optimized odometry cache poses (when %s>0).", kRGBDMaxOdomCacheSize().c_str())   
)
private

◆ RTABMAP_PARAM() [395/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [396/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [397/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LoopClosureReextractFeatures  ,
bool  ,
false  ,
"Extract features even if there are some already in the nodes. Raw features are not saved in database."   
)
private

◆ RTABMAP_PARAM() [398/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [399/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [400/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
MaxLocalRetrieved  ,
unsigned int  ,
,
"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)."   
)
private

◆ RTABMAP_PARAM() [401/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
MaxLoopClosureDistance  ,
float  ,
0.  0,
"Reject loop closures/localizations if the distance from the map is over this distance (0=disabled)."   
)
private

◆ RTABMAP_PARAM() [402/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [403/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [404/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
NewMapOdomChangeDistance  ,
float  ,
,
"A new map is created if a change of odometry translation greater than X m is detected (0 m = disabled)."   
)
private

◆ RTABMAP_PARAM() [405/536]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM() [406/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [407/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
PlanAngularVelocity  ,
float  ,
,
"Angular velocity (rad/sec) used to compute path weights."   
)
private

◆ RTABMAP_PARAM() [408/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
PlanLinearVelocity  ,
float  ,
,
"Linear velocity (m/sec) used to compute path weights."   
)
private

◆ RTABMAP_PARAM() [409/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
PlanStuckIterations  ,
int  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [410/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityAngle  ,
float  ,
45  ,
"Maximum angle (degrees) for one-to-one proximity detection."   
)
private

◆ RTABMAP_PARAM() [411/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityBySpace  ,
bool  ,
true  ,
"Detection over locations (in Working Memory) near in space."   
)
private

◆ RTABMAP_PARAM() [412/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityByTime  ,
bool  ,
false  ,
"Detection over all locations in STM."   
)
private

◆ RTABMAP_PARAM() [413/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [414/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [415/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityMaxPaths  ,
int  ,
,
"Maximum paths compared (from the most recent) for proximity detection. 0 means no limit."   
)
private

◆ RTABMAP_PARAM() [416/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [417/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityOdomGuess  ,
bool  ,
false  ,
"Use odometry as motion guess for one-to-one proximity detection."   
)
private

◆ RTABMAP_PARAM() [418/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityPathFilteringRadius  ,
float  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [419/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ProximityPathMaxNeighbors  ,
int  ,
,
"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)."   
)
private

◆ RTABMAP_PARAM() [420/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [421/536]

rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
ScanMatchingIdsSavedInLinks  ,
bool  ,
true  ,
"Save scan matching IDs from one-to-many proximity detection in link's user data."   
)
private

◆ RTABMAP_PARAM() [422/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [423/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
ComputeRMSE  ,
bool  ,
true  ,
"Compute root mean square error (RMSE) and publish it in  statistics,
if ground truth is provided."   
)
private

◆ RTABMAP_PARAM() [424/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
CreateIntermediateNodes  ,
bool  ,
false  ,
uFormat("Create intermediate nodes between loop closure detection. Only used when %s>0.", kRtabmapDetectionRate().c_str())   
)
private

◆ RTABMAP_PARAM() [425/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
DetectionRate  ,
float  ,
,
"Detection rate (Hz). RTAB-Map will filter input images to satisfy this rate."   
)
private

◆ RTABMAP_PARAM() [426/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
ImageBufferSize  ,
unsigned int  ,
,
"Data buffer size (0 min inf)."   
)
private

◆ RTABMAP_PARAM() [427/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [428/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [429/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
LoopRatio  ,
float  ,
,
"The loop closure hypothesis must be over LoopRatio x lastHypothesisValue."   
)
private

◆ RTABMAP_PARAM() [430/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
LoopThr  ,
float  ,
0.  11,
"Loop closing threshold."   
)
private

◆ RTABMAP_PARAM() [431/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
MaxRepublished  ,
unsigned int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [432/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
MaxRetrieved  ,
unsigned int  ,
,
"Maximum nodes retrieved at the same time from LTM."   
)
private

◆ RTABMAP_PARAM() [433/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
MemoryThr  ,
int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [434/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishLastSignature  ,
bool  ,
true  ,
"Publishing last signature."   
)
private

◆ RTABMAP_PARAM() [435/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishLikelihood  ,
bool  ,
true  ,
"Publishing likelihood."   
)
private

◆ RTABMAP_PARAM() [436/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishPdf  ,
bool  ,
true  ,
"Publishing pdf."   
)
private

◆ RTABMAP_PARAM() [437/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishRAMUsage  ,
bool  ,
false  ,
"Publishing RAM usage in statistics (may add a small overhead to get info from the system)."   
)
private

◆ RTABMAP_PARAM() [438/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishStats  ,
bool  ,
true  ,
"Publishing statistics."   
)
private

◆ RTABMAP_PARAM() [439/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [440/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
SaveWMState  ,
bool  ,
false  ,
"Save working memory state after each update in statistics."   
)
private

◆ RTABMAP_PARAM() [441/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [442/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StartNewMapOnLoopClosure  ,
bool  ,
false  ,
"Start a new map only if there is a global loop closure with a previous map."   
)
private

◆ RTABMAP_PARAM() [443/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLogged  ,
bool  ,
false  ,
"Logging enabled."   
)
private

◆ RTABMAP_PARAM() [444/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLoggedHeaders  ,
bool  ,
true  ,
"Add column header description to log files."   
)
private

◆ RTABMAP_PARAM() [445/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLogsBufferedInRAM  ,
bool  ,
true  ,
"Statistic logs buffered in RAM instead of written to hard drive after each iteration."   
)
private

◆ RTABMAP_PARAM() [446/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
TimeThr  ,
float  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [447/536]

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
VirtualPlaceLikelihoodRatio  ,
int  ,
,
"Likelihood ratio for virtual place (for no loop closure hypothesis):  0 = Mean / StdDev 
)
private

◆ RTABMAP_PARAM() [448/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [449/536]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM() [450/536]

rtabmap::Parameters::RTABMAP_PARAM ( SIFT  ,
NFeatures  ,
int  ,
,
"The number of best features to retain. The features are ranked by their scores (measured in SIFT algorithm as the local contrast)."   
)
private

◆ RTABMAP_PARAM() [451/536]

rtabmap::Parameters::RTABMAP_PARAM ( SIFT  ,
NOctaveLayers  ,
int  ,
,
"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."   
)
private

◆ RTABMAP_PARAM() [452/536]

rtabmap::Parameters::RTABMAP_PARAM ( SIFT  ,
RootSIFT  ,
bool  ,
false  ,
"Apply RootSIFT normalization of the descriptors."   
)
private

◆ RTABMAP_PARAM() [453/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [454/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
DenseStrategy  ,
int  ,
,
0 = cv::StereoBM 
)
private

◆ RTABMAP_PARAM() [455/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
Eps  ,
double  ,
0.  01,
uFormat("[%s=true] Epsilon stop criterion.", kStereoOpticalFlow().c_str())   
)
private

◆ RTABMAP_PARAM() [456/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
Iterations  ,
int  ,
30  ,
"Maximum iterations."   
)
private

◆ RTABMAP_PARAM() [457/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
MaxDisparity  ,
float  ,
128.  0,
"Maximum disparity."   
)
private

◆ RTABMAP_PARAM() [458/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
MaxLevel  ,
int  ,
,
"Maximum pyramid level."   
)
private

◆ RTABMAP_PARAM() [459/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
MinDisparity  ,
float  ,
0.  5,
"Minimum disparity."   
)
private

◆ RTABMAP_PARAM() [460/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
OpticalFlow  ,
bool  ,
true  ,
"Use optical flow to find stereo  correspondences,
otherwise a simple block matching approach is used."   
)
private

◆ RTABMAP_PARAM() [461/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [462/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
WinHeight  ,
int  ,
,
"Window height."   
)
private

◆ RTABMAP_PARAM() [463/536]

rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
WinWidth  ,
int  ,
15  ,
"Window width."   
)
private

◆ RTABMAP_PARAM() [464/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
BlockSize  ,
int  ,
15  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [465/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
Disp12MaxDiff  ,
int  ,
1,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [466/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
MinDisparity  ,
int  ,
,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [467/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
NumDisparities  ,
int  ,
128  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [468/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
PreFilterCap  ,
int  ,
31  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [469/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
PreFilterSize  ,
int  ,
,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [470/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
SpeckleRange  ,
int  ,
,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [471/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
SpeckleWindowSize  ,
int  ,
100  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [472/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
TextureThreshold  ,
int  ,
10  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [473/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoBM  ,
UniquenessRatio  ,
int  ,
15  ,
"See cv::StereoBM"   
)
private

◆ RTABMAP_PARAM() [474/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
BlockSize  ,
int  ,
15  ,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [475/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
Disp12MaxDiff  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [476/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
MinDisparity  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [477/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
Mode  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [478/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
NumDisparities  ,
int  ,
128  ,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [479/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
P1  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [480/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
P2  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [481/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
PreFilterCap  ,
int  ,
31  ,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [482/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
SpeckleRange  ,
int  ,
,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [483/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
SpeckleWindowSize  ,
int  ,
100  ,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [484/536]

rtabmap::Parameters::RTABMAP_PARAM ( StereoSGBM  ,
UniquenessRatio  ,
int  ,
20  ,
"See cv::StereoSGBM"   
)
private

◆ RTABMAP_PARAM() [485/536]

rtabmap::Parameters::RTABMAP_PARAM ( SuperPoint  ,
Cuda  ,
bool  ,
true  ,
"Use Cuda device for  Torch,
otherwise CPU device is used by default."   
)
private

◆ RTABMAP_PARAM() [486/536]

rtabmap::Parameters::RTABMAP_PARAM ( SuperPoint  ,
NMS  ,
bool  ,
true  ,
"If  true,
non-maximum suppression is applied to detected keypoints."   
)
private

◆ RTABMAP_PARAM() [487/536]

rtabmap::Parameters::RTABMAP_PARAM ( SuperPoint  ,
NMSRadius  ,
int  ,
,
uFormat("[%s=true] Minimum distance (pixels) between keypoints.", kSuperPointNMS().c_str())   
)
private

◆ RTABMAP_PARAM() [488/536]

rtabmap::Parameters::RTABMAP_PARAM ( SuperPoint  ,
Threshold  ,
float  ,
0.  010,
"Detector response threshold to accept keypoint."   
)
private

◆ RTABMAP_PARAM() [489/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
Extended  ,
bool  ,
false  ,
"Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors)."   
)
private

◆ RTABMAP_PARAM() [490/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
GpuKeypointsRatio  ,
float  ,
0.  01,
"Used with SURF GPU."   
)
private

◆ RTABMAP_PARAM() [491/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [492/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
HessianThreshold  ,
float  ,
500  ,
"Threshold for hessian keypoint detector used in SURF."   
)
private

◆ RTABMAP_PARAM() [493/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
OctaveLayers  ,
int  ,
,
"Number of octave layers within each octave."   
)
private

◆ RTABMAP_PARAM() [494/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
Octaves  ,
int  ,
,
"Number of pyramid octaves the keypoint detector will use."   
)
private

◆ RTABMAP_PARAM() [495/536]

rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
Upright  ,
bool  ,
false  ,
"Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation)."   
)
private

◆ RTABMAP_PARAM() [496/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [497/536]

rtabmap::Parameters::RTABMAP_PARAM ( VhEp  ,
MatchCountMin  ,
int  ,
,
"Minimum of matching visual words pairs to accept the loop hypothesis."   
)
private

◆ RTABMAP_PARAM() [498/536]

rtabmap::Parameters::RTABMAP_PARAM ( VhEp  ,
RansacParam1  ,
float  ,
,
"Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier."   
)
private

◆ RTABMAP_PARAM() [499/536]

rtabmap::Parameters::RTABMAP_PARAM ( VhEp  ,
RansacParam2  ,
float  ,
0.  99,
"Fundamental matrix (see cvFindFundamentalMat()): Performance of RANSAC."   
)
private

◆ RTABMAP_PARAM() [500/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
BundleAdjustment  ,
int  ,
,
"Optimization with bundle adjustment:  0 = disabled,
= g2o,
= cvsba 
)
private

◆ RTABMAP_PARAM() [501/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorFlowEps  ,
float  ,
0.  01,
uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str())   
)
private

◆ RTABMAP_PARAM() [502/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorFlowIterations  ,
int  ,
30  ,
uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str())   
)
private

◆ RTABMAP_PARAM() [503/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorFlowMaxLevel  ,
int  ,
,
uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str())   
)
private

◆ RTABMAP_PARAM() [504/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorFlowWinSize  ,
int  ,
16  ,
uFormat("[%s=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.", kVisCorType().c_str())   
)
private

◆ RTABMAP_PARAM() [505/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [506/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [507/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorNNDR  ,
float  ,
0.  8,
uFormat("[%s=0] NNDR: nearest neighbor distance ratio. Used for knn features matching approach.", kVisCorType().c_str())   
)
private

◆ RTABMAP_PARAM() [508/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorNNType  ,
int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [509/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
CorType  ,
int  ,
,
"Correspondences computation approach:  0 = Features Matching 
)
private

◆ RTABMAP_PARAM() [510/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
DepthAsMask  ,
bool  ,
true  ,
"Use depth image as mask when extracting features."   
)
private

◆ RTABMAP_PARAM() [511/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
EpipolarGeometryVar  ,
float  ,
0.  1,
uFormat("[%s = 2] Epipolar geometry maximum variance to accept the transformation.", kVisEstimationType().c_str())   
)
private

◆ RTABMAP_PARAM() [512/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
EstimationType  ,
int  ,
,
"Motion estimation approach: 0:3D->  3D,
1:3D->  2DPnP,
2:2D->2D(Epipolar Geometry)"   
)
private

◆ RTABMAP_PARAM() [513/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
FeatureType  ,
int  ,
 
)
private

◆ RTABMAP_PARAM() [514/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
ForwardEstOnly  ,
bool  ,
true  ,
"Forward estimation only (A->B). If  false,
a transformation is also computed in backward   directionB->A,
then the two resulting transforms are merged(middle interpolation between the transforms)."   
)
private

◆ RTABMAP_PARAM() [515/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
GridCols  ,
int  ,
,
uFormat("Number of columns of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kVisMaxFeatures().c_str())   
)
private

◆ RTABMAP_PARAM() [516/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
GridRows  ,
int  ,
,
uFormat("Number of rows of the grid used to extract uniformly \"%s / grid cells\" features from each cell.", kVisMaxFeatures().c_str())   
)
private

◆ RTABMAP_PARAM() [517/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
InlierDistance  ,
float  ,
0.  1,
uFormat("[%s = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.", kVisEstimationType().c_str())   
)
private

◆ RTABMAP_PARAM() [518/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
Iterations  ,
int  ,
300  ,
"Maximum iterations to compute the transform."   
)
private

◆ RTABMAP_PARAM() [519/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
MaxDepth  ,
float  ,
,
"Max depth of the features (0 means no limit)."   
)
private

◆ RTABMAP_PARAM() [520/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
MaxFeatures  ,
int  ,
1000  ,
"0 no limits."   
)
private

◆ RTABMAP_PARAM() [521/536]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM() [522/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
MinDepth  ,
float  ,
,
"Min depth of the features (0 means no limit)."   
)
private

◆ RTABMAP_PARAM() [523/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
MinInliers  ,
int  ,
20  ,
"Minimum feature correspondences to compute/accept the transformation."   
)
private

◆ RTABMAP_PARAM() [524/536]

rtabmap::Parameters::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 . The value would be between 0 and 0.5. 0 means disabled."  [-0.5, 0.5] 
)
private

◆ RTABMAP_PARAM() [525/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
PnPFlags  ,
int  ,
,
uFormat("[%s = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P", kVisEstimationType().c_str())   
)
private

◆ RTABMAP_PARAM() [526/536]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM() [527/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
PnPRefineIterations  ,
int  ,
,
uFormat("[%s = 1] Refine iterations. Set to 0 if \"%s\" is also used.", kVisEstimationType().c_str(), kVisBundleAdjustment().c_str())   
)
private

◆ RTABMAP_PARAM() [528/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
PnPReprojError  ,
float  ,
,
uFormat("[%s = 1] PnP reprojection error.", kVisEstimationType().c_str())   
)
private

◆ RTABMAP_PARAM() [529/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
PnPSamplingPolicy  ,
unsigned int  ,
,
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()   
)
private

◆ RTABMAP_PARAM() [530/536]

rtabmap::Parameters::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()   
)
private

◆ RTABMAP_PARAM() [531/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
PnPVarianceMedianRatio  ,
int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [532/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
RefineIterations  ,
int  ,
,
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())   
)
private

◆ RTABMAP_PARAM() [533/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
SSC  ,
bool  ,
false  ,
"If  true,
SSC(Suppression via Square Covering) is applied to limit keypoints."   
)
private

◆ RTABMAP_PARAM() [534/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
SubPixEps  ,
float  ,
0.  02,
"See cv::cornerSubPix()."   
)
private

◆ RTABMAP_PARAM() [535/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
SubPixIterations  ,
int  ,
,
"See cv::cornerSubPix(). 0 disables sub pixel refining."   
)
private

◆ RTABMAP_PARAM() [536/536]

rtabmap::Parameters::RTABMAP_PARAM ( Vis  ,
SubPixWinSize  ,
int  ,
,
"See cv::cornerSubPix()."   
)
private

◆ RTABMAP_PARAM_STR() [1/21]

rtabmap::Parameters::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, ...}."   
)
private

◆ RTABMAP_PARAM_STR() [2/21]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM_STR() [3/21]

rtabmap::Parameters::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())   
)
private

◆ RTABMAP_PARAM_STR() [4/21]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM_STR() [5/21]

rtabmap::Parameters::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()   
)
private

◆ RTABMAP_PARAM_STR() [6/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( Kp  ,
DictionaryPath  ,
""  ,
"Path of the pre-computed dictionary"   
)
private

◆ RTABMAP_PARAM_STR() [7/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( Kp  ,
RoiRatios  ,
"0.0 0.0 0.0 0.0"  ,
"Region of interest ratios ."  [left, right, top, bottom] 
)
private

◆ RTABMAP_PARAM_STR() [8/21]

rtabmap::Parameters::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)."   
)
private

◆ RTABMAP_PARAM_STR() [9/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( Mem  ,
ImageCompressionFormat  ,
".jpg"  ,
"RGB image compression format. It should be \".jpg\" or \".png\"."   
)
private

◆ RTABMAP_PARAM_STR() [10/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( OdomOKVIS  ,
ConfigPath  ,
""  ,
"Path of OKVIS config file."   
)
private

◆ RTABMAP_PARAM_STR() [11/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( OdomOpenVINS  ,
LeftMaskPath  ,
""  ,
"Mask for left image"   
)
private

◆ RTABMAP_PARAM_STR() [12/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( OdomOpenVINS  ,
RightMaskPath  ,
""  ,
"Mask for right image"   
)
private

◆ RTABMAP_PARAM_STR() [13/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( OdomORBSLAM  ,
VocPath  ,
""  ,
"Path to ORB vocabulary (*.txt)."   
)
private

◆ RTABMAP_PARAM_STR() [14/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( OdomVINS  ,
ConfigPath  ,
""  ,
"Path of VINS config file."   
)
private

◆ RTABMAP_PARAM_STR() [15/21]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM_STR() [16/21]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM_STR() [17/21]

rtabmap::Parameters::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\")."   
)
private

◆ RTABMAP_PARAM_STR() [18/21]

rtabmap::Parameters::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."   
)
private

◆ RTABMAP_PARAM_STR() [19/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( Rtabmap  ,
WorkingDirectory  ,
""  ,
"Working directory."   
)
private

◆ RTABMAP_PARAM_STR() [20/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( SuperPoint  ,
ModelPath  ,
""  ,
" Path to pre-trained weights Torch file of SuperPoint (*.pt)."  [Required] 
)
private

◆ RTABMAP_PARAM_STR() [21/21]

rtabmap::Parameters::RTABMAP_PARAM_STR ( Vis  ,
RoiRatios  ,
"0.0 0.0 0.0 0.0"  ,
"Region of interest ratios ."  [left, right, top, bottom] 
)
private

◆ serialize()

std::string rtabmap::Parameters::serialize ( const ParametersMap parameters)
static

Definition at line 93 of file Parameters.cpp.

◆ showUsage()

const char * rtabmap::Parameters::showUsage ( )
static

Definition at line 572 of file Parameters.cpp.

◆ writeINI()

void rtabmap::Parameters::writeINI ( const std::string configFile,
const ParametersMap parameters 
)
static

Definition at line 1287 of file Parameters.cpp.

Member Data Documentation

◆ backwardCompatibilityMap_

ParametersMap rtabmap::Parameters::backwardCompatibilityMap_
staticprivate

Definition at line 966 of file Parameters.h.

◆ descriptions_

ParametersMap rtabmap::Parameters::descriptions_
staticprivate

Definition at line 962 of file Parameters.h.

◆ instance_

Parameters rtabmap::Parameters::instance_
staticprivate

Definition at line 963 of file Parameters.h.

◆ parameters_

ParametersMap rtabmap::Parameters::parameters_
staticprivate

Definition at line 960 of file Parameters.h.

◆ parametersType_

ParametersMap rtabmap::Parameters::parametersType_
staticprivate

Definition at line 961 of file Parameters.h.

◆ removedParameters_

std::map< std::string, std::pair< bool, std::string > > rtabmap::Parameters::removedParameters_
staticprivate

Definition at line 965 of file Parameters.h.


The documentation for this class was generated from the following files:
rtabmap::Parameters::getDefaultParameters
static const ParametersMap & getDefaultParameters()
Definition: Parameters.h:896


rtabmap
Author(s): Mathieu Labbe
autogenerated on Mon Jul 1 2024 02:42:45