Public Member Functions | Static Public Member Functions | Private Member Functions | Static Private Member Functions | Static Private Attributes
rtabmap::Parameters Class Reference

#include <Parameters.h>

List of all members.

Public Member Functions

virtual ~Parameters ()

Static Public Member Functions

static std::string getDefaultDatabaseName ()
static const ParametersMapgetDefaultParameters ()
static std::string getDescription (const std::string &paramKey)
static void parse (const ParametersMap &parameters, const std::string &key, bool &value)
static void parse (const ParametersMap &parameters, const std::string &key, int &value)
static void parse (const ParametersMap &parameters, const std::string &key, unsigned int &value)
static void parse (const ParametersMap &parameters, const std::string &key, float &value)
static void parse (const ParametersMap &parameters, const std::string &key, double &value)
static void parse (const ParametersMap &parameters, const std::string &key, std::string &value)

Private Member Functions

 Parameters ()
 RTABMAP_PARAM (Rtabmap, VhStrategy, int, 0,"None 0, Similarity 1, Epipolar 2.")
 RTABMAP_PARAM (Rtabmap, PublishStats, bool, true,"Publishing statistics.")
 RTABMAP_PARAM (Rtabmap, PublishLastSignature, bool, true,"Publishing last signature.")
 RTABMAP_PARAM (Rtabmap, PublishPdf, bool, true,"Publishing pdf.")
 RTABMAP_PARAM (Rtabmap, PublishLikelihood, bool, true,"Publishing likelihood.")
 RTABMAP_PARAM (Rtabmap, TimeThr, float, 0.0,"Maximum time allowed for the detector (ms) (0 means infinity).")
 RTABMAP_PARAM (Rtabmap, MemoryThr, int, 0,"Maximum signatures in the Working Memory (ms) (0 means infinity).")
 RTABMAP_PARAM (Rtabmap, DetectionRate, float, 1.0,"Detection rate. RTAB-Map will filter input images to satisfy this rate.")
 RTABMAP_PARAM (Rtabmap, ImageBufferSize, int, 1,"Data buffer size (0 min inf).")
 RTABMAP_PARAM (Rtabmap, MaxRetrieved, unsigned int, 2,"Maximum locations retrieved at the same time from LTM.")
 RTABMAP_PARAM (Rtabmap, StatisticLogsBufferedInRAM, bool, true,"Statistic logs buffered in RAM instead of written to hard drive after each iteration.")
 RTABMAP_PARAM (Rtabmap, StatisticLogged, bool, false,"Logging enabled.")
 RTABMAP_PARAM (Rtabmap, StatisticLoggedHeaders, bool, true,"Add column header description to log files.")
 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, LoopThr, float, 0.11,"Loop closing threshold.")
 RTABMAP_PARAM (Rtabmap, LoopRatio, float, 0.0,"The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.")
 RTABMAP_PARAM (Mem, RehearsalSimilarity, float, 0.6,"Rehearsal similarity.")
 RTABMAP_PARAM (Mem, ImageKept, bool, false,"Keep raw images in RAM.")
 RTABMAP_PARAM (Mem, BinDataKept, bool, true,"Keep binary data in db.")
 RTABMAP_PARAM (Mem, NotLinkedNodesKept, bool, true,"Keep not linked nodes in db (rehearsed nodes and deleted nodes).")
 RTABMAP_PARAM (Mem, STMSize, unsigned int, 10,"Short-term memory size.")
 RTABMAP_PARAM (Mem, IncrementalMemory, bool, true,"SLAM mode, otherwise it is Localization mode.")
 RTABMAP_PARAM (Mem, RecentWmRatio, float, 0.2,"Ratio of locations after the last loop closure in WM that cannot be transferred.")
 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, RehearsalIdUpdatedToNewOne, bool, false,"On merge, update to new id. When false, no copy.")
 RTABMAP_PARAM (Mem, RehearsalWeightIgnoredWhileMoving, bool, false,"When the robot is moving, weights are not updated on rehearsal.")
 RTABMAP_PARAM (Mem, GenerateIds, bool, true,"True=Generate location IDs, False=use input image IDs.")
 RTABMAP_PARAM (Mem, BadSignaturesIgnored, bool, false,"Bad signatures are ignored.")
 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, ImageDecimation, int, 1,"Image decimation (>=1) when creating a signature.")
 RTABMAP_PARAM (Mem, LaserScanVoxelSize, float, 0.0,"If > 0.0, voxelize laser scans when creating a signature.")
 RTABMAP_PARAM (Mem, LocalSpaceLinksKeptInWM, bool, true,"If local space links are kept in WM.")
 RTABMAP_PARAM (Kp, IncrementalDictionary, bool, true,"")
 RTABMAP_PARAM (Kp, MaxDepth, float, 0.0,"Filter extracted keypoints by depth (0=inf)")
 RTABMAP_PARAM (Kp, WordsPerImage, int, 400,"")
 RTABMAP_PARAM (Kp, BadSignRatio, float, 0.2,"Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).")
 RTABMAP_PARAM (Kp, TfIdfLikelihoodUsed, bool, true,"Use of the td-idf strategy to compute the likelihood.")
 RTABMAP_PARAM (Kp, Parallelized, bool, true,"If the dictionary update and signature creation were parallelized.")
 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, SubPixWinSize, int, 3,"See cv::cornerSubPix().")
 RTABMAP_PARAM (Kp, SubPixIterations, int, 0,"See cv::cornerSubPix(). 0 disables sub pixel refining.")
 RTABMAP_PARAM (Kp, SubPixEps, double, 0.02,"See cv::cornerSubPix().")
 RTABMAP_PARAM (DbSqlite3, InMemory, bool, false,"Using database in the memory instead of a file on the hard disk.")
 RTABMAP_PARAM (DbSqlite3, CacheSize, unsigned int, 10000,"Sqlite cache size (default is 2000).")
 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 (SURF, Extended, bool, false,"Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).")
 RTABMAP_PARAM (SURF, HessianThreshold, float, 150.0,"Threshold for hessian keypoint detector used in SURF.")
 RTABMAP_PARAM (SURF, Octaves, int, 4,"Number of pyramid octaves the keypoint detector will use.")
 RTABMAP_PARAM (SURF, OctaveLayers, int, 2,"Number of octave layers within each octave.")
 RTABMAP_PARAM (SURF, Upright, bool, false,"Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).")
 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, GpuKeypointsRatio, float, 0.01,"Used with SURF GPU.")
 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, 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.0,"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, 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 (BRIEF, Bytes, int, 32,"Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.")
 RTABMAP_PARAM (FAST, Threshold, int, 30,"Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.")
 RTABMAP_PARAM (FAST, NonmaxSuppression, bool, true,"If true, non-maximum suppression is applied to detected corners (keypoints).")
 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 (GFTT, QualityLevel, double, 0.01,"")
 RTABMAP_PARAM (GFTT, MinDistance, double, 5,"")
 RTABMAP_PARAM (GFTT, BlockSize, int, 3,"")
 RTABMAP_PARAM (GFTT, UseHarrisDetector, bool, false,"")
 RTABMAP_PARAM (GFTT, K, double, 0.04,"")
 RTABMAP_PARAM (ORB, ScaleFactor, float, 1.2,"Pyramid decimation ratio, greater than 1. scaleFactor==2 means the classical pyramid, where each next level has 4x less pixels than the previous, but such a big scale factor will degrade feature matching scores dramatically. On the other hand, too close to 1 scale factor will mean that to cover certain scale range you will need more pyramid levels and so the speed will suffer.")
 RTABMAP_PARAM (ORB, NLevels, int, 1,"The number of pyramid levels. The smallest level will have linear size equal to input_image_linear_size/pow(scaleFactor, nlevels).")
 RTABMAP_PARAM (ORB, EdgeThreshold, int, 31,"This is size of the border where the features are not detected. It should roughly match the patchSize parameter.")
 RTABMAP_PARAM (ORB, FirstLevel, int, 0,"It should be 0 in the current implementation.")
 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 (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, 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, 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 (FREAK, OrientationNormalized, bool, true,"Enable orientation normalization.")
 RTABMAP_PARAM (FREAK, ScaleNormalized, bool, true,"Enable scale normalization.")
 RTABMAP_PARAM (FREAK, PatternScale, float, 22.0,"Scaling of the description pattern.")
 RTABMAP_PARAM (FREAK, NOctaves, int, 4,"Number of octaves covered by the detected keypoints.")
 RTABMAP_PARAM (BRISK, Thresh, int, 30,"FAST/AGAST detection threshold score.")
 RTABMAP_PARAM (BRISK, Octaves, int, 3,"Detection octaves. Use 0 to do single scale.")
 RTABMAP_PARAM (BRISK, PatternScale, float, 1.0,"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.")
 RTABMAP_PARAM (Bayes, VirtualPlacePriorThr, float, 0.9,"Virtual place prior")
 RTABMAP_PARAM (Bayes, FullPredictionUpdate, bool, false,"Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).")
 RTABMAP_PARAM (VhEp, MatchCountMin, int, 8,"Minimum of matching visual words pairs to accept the loop hypothesis.")
 RTABMAP_PARAM (VhEp, RansacParam1, float, 3.0,"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 the RANSAC.")
 RTABMAP_PARAM (RGBD, Enabled, bool, true,"")
 RTABMAP_PARAM (RGBD, PoseScanMatching, bool, false,"Laser scan matching for odometry pose correction (laser scans are required).")
 RTABMAP_PARAM (RGBD, LinearUpdate, float, 0.0,"Min linear displacement to update the map. Rehearsal is done prior to this, so weights are still updated.")
 RTABMAP_PARAM (RGBD, AngularUpdate, float, 0.0,"Min angular displacement to update the map. Rehearsal is done prior to this, so weights are still updated.")
 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 mode 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, GoalReachedRadius, float, 0.5,"Goal reached radius (m).")
 RTABMAP_PARAM (RGBD, PlanVirtualLinks, bool, true,"Before planning in the graph, close nodes are linked together. Radius is defined by \"RGBD/GoalReachedRadius\" parameter.")
 RTABMAP_PARAM (RGBD, GoalsSavedInUserData, bool, true,"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, 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, 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, LocalImmunizationRatio, float, 0.25,"Ratio of working memory for which local nodes are immunized from transfer.")
 RTABMAP_PARAM (RGBD, LocalLoopDetectionTime, bool, false,"Detection over all locations in STM.")
 RTABMAP_PARAM (RGBD, LocalLoopDetectionSpace, bool, false,"Detection over locations (in Working Memory or STM) near in space.")
 RTABMAP_PARAM (RGBD, LocalLoopDetectionMaxGraphDepth, int, 50,"Maximum depth from the current/last loop closure location and the local loop closure hypotheses. Set 0 to ignore.")
 RTABMAP_PARAM (RGBD, LocalLoopDetectionPathFilteringRadius, float, 0.5,"Path filtering radius.")
 RTABMAP_PARAM (RGBD, LocalLoopDetectionPathOdomPosesUsed, bool, true,"When comparing to a local path, merge the scan using the odometry poses instead of the ones in the optimized local graph.")
 RTABMAP_PARAM (RGBD, OptimizeStrategy, int, 0,"Graph optimization strategy: 0=TORO and 1=g2o.")
 RTABMAP_PARAM (RGBD, OptimizeIterations, int, 100,"Optimization iterations.")
 RTABMAP_PARAM (RGBD, OptimizeSlam2D, bool, false,"If optimization is done only on x,y and theta (3DoF). Otherwise, it is done on full 6DoF poses.")
 RTABMAP_PARAM (RGBD, OptimizeVarianceIgnored, 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 (Odom, Strategy, int, 0,"0=Bag-of-words 1=Optical Flow")
 RTABMAP_PARAM (Odom, FeatureType, int, 6,"0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK.")
 RTABMAP_PARAM (Odom, MaxFeatures, int, 400,"0 no limits.")
 RTABMAP_PARAM (Odom, InlierDistance, float, 0.02,"Maximum distance for visual word correspondences.")
 RTABMAP_PARAM (Odom, MinInliers, int, 20,"Minimum visual word correspondences to compute geometry transform.")
 RTABMAP_PARAM (Odom, Iterations, int, 30,"Maximum iterations to compute the transform from visual words.")
 RTABMAP_PARAM (Odom, RefineIterations, int, 5,"Number of iterations used to refine the transformation found by RANSAC. 0 means that the transformation is not refined.")
 RTABMAP_PARAM (Odom, MaxDepth, float, 4.0,"Max depth of the words (0 means no limit).")
 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, Force2D, bool, false,"Force 2D transform (3Dof: x,y and yaw).")
 RTABMAP_PARAM (Odom, FillInfoData, bool, true,"Fill info with data (inliers/outliers features).")
 RTABMAP_PARAM (Odom, PnPEstimation, bool, false,"(PnP) Pose estimation from 2D to 3D correspondences instead of 3D to 3D correspondences.")
 RTABMAP_PARAM (Odom, PnPReprojError, double, 8.0,"PnP reprojection error.")
 RTABMAP_PARAM (Odom, PnPFlags, int, 0,"PnP flags: 0=Iterative, 1=EPNP, 2=P3P")
 RTABMAP_PARAM (OdomBow, LocalHistorySize, int, 1000,"Local history size: If > 0 (example 5000), the odometry will maintain a local map of X maximum words.")
 RTABMAP_PARAM (OdomBow, NNType, int, 3,"kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4")
 RTABMAP_PARAM (OdomBow, NNDR, float, 0.8,"NNDR: nearest neighbor distance ratio.")
 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, 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 (OdomMono, MaxVariance, float, 0.01,"Maximum variance to add new points to local map.")
 RTABMAP_PARAM (OdomFlow, WinSize, int, 16,"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (OdomFlow, Iterations, int, 30,"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (OdomFlow, Eps, double, 0.01,"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (OdomFlow, MaxLevel, int, 3,"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (OdomSubPix, WinSize, int, 3,"Can be used with BOW and optical flow approaches. See cv::cornerSubPix().")
 RTABMAP_PARAM (OdomSubPix, Iterations, int, 0,"Can be used with BOW and optical flow approaches. See cv::cornerSubPix(). 0 disables sub pixel refining.")
 RTABMAP_PARAM (OdomSubPix, Eps, double, 0.02,"Can be used with BOW and optical flow approaches. See cv::cornerSubPix().")
 RTABMAP_PARAM (LccIcp, Type, int, 0,"0=No ICP, 1=ICP 3D, 2=ICP 2D")
 RTABMAP_PARAM (LccIcp, MaxTranslation, float, 0.2,"Maximum ICP translation correction accepted (m).")
 RTABMAP_PARAM (LccIcp, MaxRotation, float, 0.78,"Maximum ICP rotation correction accepted (rad).")
 RTABMAP_PARAM (LccBow, MinInliers, int, 20,"Minimum visual word correspondences to compute geometry transform.")
 RTABMAP_PARAM (LccBow, InlierDistance, float, 0.02,"Maximum distance for visual word correspondences.")
 RTABMAP_PARAM (LccBow, Iterations, int, 100,"Maximum iterations to compute the transform from visual words.")
 RTABMAP_PARAM (LccBow, MaxDepth, float, 4.0,"Max depth of the words (0 means no limit).")
 RTABMAP_PARAM (LccBow, Force2D, bool, false,"Force 2D transform (3Dof: x,y and yaw).")
 RTABMAP_PARAM (LccBow, EpipolarGeometry, bool, false,"Use epipolar geometry to compute the loop closure transform.")
 RTABMAP_PARAM (LccBow, EpipolarGeometryVar, float, 0.02,"Epipolar geometry maximum variance to accept the loop closure.")
 RTABMAP_PARAM (LccReextract, NNType, int, 3,"kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4.")
 RTABMAP_PARAM (LccReextract, NNDR, float, 0.8,"NNDR: nearest neighbor distance ratio.")
 RTABMAP_PARAM (LccReextract, FeatureType, int, 4,"0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK.")
 RTABMAP_PARAM (LccReextract, MaxWords, int, 600,"0 no limits.")
 RTABMAP_PARAM (LccIcp3, Decimation, int, 8,"Depth image decimation.")
 RTABMAP_PARAM (LccIcp3, MaxDepth, float, 4.0,"Max cloud depth.")
 RTABMAP_PARAM (LccIcp3, VoxelSize, float, 0.01,"Voxel size to be used for ICP computation.")
 RTABMAP_PARAM (LccIcp3, Samples, int, 0,"Random samples to be used for ICP computation. Not used if voxelSize is set.")
 RTABMAP_PARAM (LccIcp3, MaxCorrespondenceDistance, float, 0.05,"ICP 3D: Max distance for point correspondences.")
 RTABMAP_PARAM (LccIcp3, Iterations, int, 30,"Max iterations.")
 RTABMAP_PARAM (LccIcp3, CorrespondenceRatio, float, 0.7,"Ratio of matching correspondences to accept the transform.")
 RTABMAP_PARAM (LccIcp3, PointToPlane, bool, false,"Use point to plane ICP.")
 RTABMAP_PARAM (LccIcp3, PointToPlaneNormalNeighbors, int, 20,"Number of neighbors to compute normals for point to plane.")
 RTABMAP_PARAM (LccIcp2, MaxCorrespondenceDistance, float, 0.05,"Max distance for point correspondences.")
 RTABMAP_PARAM (LccIcp2, Iterations, int, 30,"Max iterations.")
 RTABMAP_PARAM (LccIcp2, CorrespondenceRatio, float, 0.3,"Ratio of matching correspondences to accept the transform.")
 RTABMAP_PARAM (LccIcp2, VoxelSize, float, 0.025,"Voxel size to be used for ICP computation.")
 RTABMAP_PARAM (Stereo, WinSize, int, 16,"See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (Stereo, Iterations, int, 30,"See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (Stereo, Eps, double, 0.01,"See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (Stereo, MaxLevel, int, 3,"See cv::calcOpticalFlowPyrLK().")
 RTABMAP_PARAM (Stereo, MaxSlope, float, 0.1,"The maximum slope for each stereo pairs.")
 RTABMAP_PARAM_COND (Kp, NNStrategy, int, RTABMAP_NONFREE, 1, 3,"kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4")
 RTABMAP_PARAM_COND (Kp, NndrRatio, float, RTABMAP_NONFREE, 0.8, 0.9,"NNDR ratio (A matching pair is detected, if its distance is closer than X times the distance of the second nearest neighbor.)")
 RTABMAP_PARAM_COND (Kp, DetectorStrategy, int, RTABMAP_NONFREE, 0, 2,"0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK.")
 RTABMAP_PARAM_COND (LccReextract, Activated, bool, RTABMAP_NONFREE, false, true,"Activate re-extracting features on global loop closure.")
 RTABMAP_PARAM_STR (Rtabmap, WorkingDirectory, Parameters::getDefaultWorkingDirectory(),"Working directory.")
 RTABMAP_PARAM_STR (Kp, RoiRatios,"0.0 0.0 0.0 0.0","Region of interest ratios [left, right, top, bottom].")
 RTABMAP_PARAM_STR (Kp, DictionaryPath,"","Path of the pre-computed dictionary")
 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 (Odom, RoiRatios,"0.0 0.0 0.0 0.0","Region of interest ratios [left, right, top, bottom].")

Static Private Member Functions

static std::string getDefaultWorkingDirectory ()

Static Private Attributes

static ParametersMap descriptions_
static Parameters instance_
static ParametersMap parameters_

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 161 of file Parameters.h.


Constructor & Destructor Documentation

Definition at line 47 of file Parameters.cpp.

Definition at line 43 of file Parameters.cpp.


Member Function Documentation

Definition at line 67 of file Parameters.cpp.

static const ParametersMap& rtabmap::Parameters::getDefaultParameters ( ) [inline, static]

Get default parameters

Definition at line 397 of file Parameters.h.

std::string rtabmap::Parameters::getDefaultWorkingDirectory ( ) [static, private]

Definition at line 51 of file Parameters.cpp.

std::string rtabmap::Parameters::getDescription ( const std::string &  paramKey) [static]

Get parameter description

Definition at line 72 of file Parameters.cpp.

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

Definition at line 87 of file Parameters.cpp.

void rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string &  key,
int &  value 
) [static]

Definition at line 95 of file Parameters.cpp.

void rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string &  key,
unsigned int &  value 
) [static]

Definition at line 103 of file Parameters.cpp.

void rtabmap::Parameters::parse ( const ParametersMap parameters,
const std::string &  key,
float &  value 
) [static]

Definition at line 111 of file Parameters.cpp.

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

Definition at line 119 of file Parameters.cpp.

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

Definition at line 127 of file Parameters.cpp.

rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
VhStrategy  ,
int  ,
,
"None  0,
Similarity  1,
Epipolar 2."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishStats  ,
bool  ,
true  ,
"Publishing statistics."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishLastSignature  ,
bool  ,
true  ,
"Publishing last signature."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishPdf  ,
bool  ,
true  ,
"Publishing pdf."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
PublishLikelihood  ,
bool  ,
true  ,
"Publishing likelihood."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
TimeThr  ,
float  ,
0.  0,
"Maximum time allowed for the detector (ms) (0 means infinity)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
MemoryThr  ,
int  ,
,
"Maximum signatures in the Working Memory (ms) (0 means infinity)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
DetectionRate  ,
float  ,
1.  0,
"Detection rate. RTAB-Map will filter input images to satisfy this rate."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
ImageBufferSize  ,
int  ,
,
"Data buffer size (0 min inf)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
MaxRetrieved  ,
unsigned  int,
,
"Maximum locations retrieved at the same time from LTM."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLogsBufferedInRAM  ,
bool  ,
true  ,
"Statistic logs buffered in RAM instead of written to hard drive after each iteration."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLogged  ,
bool  ,
false  ,
"Logging enabled."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
StatisticLoggedHeaders  ,
bool  ,
true  ,
"Add column header description to log files."   
) [private]
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::Parameters::RTABMAP_PARAM ( Rtabmap  ,
LoopThr  ,
float  ,
0.  11,
"Loop closing threshold."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Rtabmap  ,
LoopRatio  ,
float  ,
0.  0,
"The loop closure hypothesis must be over LoopRatio x lastHypothesisValue."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalSimilarity  ,
float  ,
0.  6,
"Rehearsal similarity."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
ImageKept  ,
bool  ,
false  ,
"Keep raw images in RAM."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
BinDataKept  ,
bool  ,
true  ,
"Keep binary data in db."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
NotLinkedNodesKept  ,
bool  ,
true  ,
"Keep not linked nodes in db (rehearsed nodes and deleted nodes)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
STMSize  ,
unsigned  int,
10  ,
"Short-term memory size."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
IncrementalMemory  ,
bool  ,
true  ,
"SLAM  mode,
otherwise it is Localization mode."   
) [private]
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::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::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalIdUpdatedToNewOne  ,
bool  ,
false  ,
"On  merge,
update to new id.When  false,
no copy."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
RehearsalWeightIgnoredWhileMoving  ,
bool  ,
false  ,
"When the robot is  moving,
weights are not updated on rehearsal."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
GenerateIds  ,
bool  ,
true  ,
True = Generate location IDs 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
BadSignaturesIgnored  ,
bool  ,
false  ,
"Bad signatures are ignored."   
) [private]
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::Parameters::RTABMAP_PARAM ( Mem  ,
ImageDecimation  ,
int  ,
,
"Image decimation (>=1) when creating a signature."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
LaserScanVoxelSize  ,
float  ,
0.  0,
If,
0.  0,
voxelize laser scans when creating a signature."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Mem  ,
LocalSpaceLinksKeptInWM  ,
bool  ,
true  ,
"If local space links are kept in WM."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
IncrementalDictionary  ,
bool  ,
true  ,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
MaxDepth  ,
float  ,
0.  0,
"Filter extracted keypoints by depth (0=inf)"   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
WordsPerImage  ,
int  ,
400  ,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
BadSignRatio  ,
float  ,
0.  2,
"Bad signature ratio (less than Ratio x AverageWordsPerImage = bad)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
TfIdfLikelihoodUsed  ,
bool  ,
true  ,
"Use of the td-idf strategy to compute the likelihood."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
Parallelized  ,
bool  ,
true  ,
"If the dictionary update and signature creation were parallelized."   
) [private]
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::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixWinSize  ,
int  ,
,
"See cv::cornerSubPix()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixIterations  ,
int  ,
,
"See cv::cornerSubPix(). 0 disables sub pixel refining."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Kp  ,
SubPixEps  ,
double  ,
0.  02,
"See cv::cornerSubPix()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
InMemory  ,
bool  ,
false  ,
"Using database in the memory instead of a file on the hard disk."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
CacheSize  ,
unsigned  int,
10000  ,
"Sqlite cache size (default is 2000)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
JournalMode  ,
int  ,
,
0 = DELETE,
= TRUNCATE,
= PERSIST,
= MEMORY 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
Synchronous  ,
int  ,
,
0 = OFF,
= NORMAL 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( DbSqlite3  ,
TempStore  ,
int  ,
,
0 = DEFAULT,
= FILE 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
Extended  ,
bool  ,
false  ,
"Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
HessianThreshold  ,
float  ,
150.  0,
"Threshold for hessian keypoint detector used in SURF."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
Octaves  ,
int  ,
,
"Number of pyramid octaves the keypoint detector will use."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( SURF  ,
OctaveLayers  ,
int  ,
,
"Number of octave layers within each octave."   
) [private]
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::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::Parameters::RTABMAP_PARAM ( SURF  ,
GpuKeypointsRatio  ,
float  ,
0.  01,
"Used with SURF GPU."   
) [private]
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::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::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::Parameters::RTABMAP_PARAM ( SIFT  ,
EdgeThreshold  ,
double  ,
10.  0,
"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::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::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::Parameters::RTABMAP_PARAM ( FAST  ,
Threshold  ,
int  ,
30  ,
"Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( FAST  ,
NonmaxSuppression  ,
bool  ,
true  ,
"If  true,
non-maximum suppression is applied to detected corners(keypoints)."   
) [private]
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::Parameters::RTABMAP_PARAM ( FAST  ,
GpuKeypointsRatio  ,
double  ,
0.  05,
"Used with FAST GPU."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
QualityLevel  ,
double  ,
0.  01,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
MinDistance  ,
double  ,
,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
BlockSize  ,
int  ,
,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
UseHarrisDetector  ,
bool  ,
false  ,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( GFTT  ,
,
double  ,
0.  04,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
ScaleFactor  ,
float  ,
1.  2,
"Pyramid decimation  ratio,
greater than 1.  scaleFactor = =2 means the classical pyramid,
where each next level has 4x less pixels than the  previous,
but such a big scale factor will degrade feature matching scores dramatically.On the other  hand,
too close to 1 scale factor will mean that to cover certain scale range you will need more pyramid levels and so the speed will suffer."   
) [private]
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::Parameters::RTABMAP_PARAM ( ORB  ,
EdgeThreshold  ,
int  ,
31  ,
"This is size of the border where the features are not detected. It should roughly match the patchSize parameter."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( ORB  ,
FirstLevel  ,
int  ,
,
"It should be 0 in the current implementation."   
) [private]
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::Parameters::RTABMAP_PARAM ( ORB  ,
ScoreType  ,
int  ,
,
"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."   
) [private]
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::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::Parameters::RTABMAP_PARAM ( FREAK  ,
OrientationNormalized  ,
bool  ,
true  ,
"Enable orientation normalization."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
ScaleNormalized  ,
bool  ,
true  ,
"Enable scale normalization."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
PatternScale  ,
float  ,
22.  0,
"Scaling of the description pattern."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( FREAK  ,
NOctaves  ,
int  ,
,
"Number of octaves covered by the detected keypoints."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
Thresh  ,
int  ,
30  ,
"FAST/AGAST detection threshold score."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
Octaves  ,
int  ,
,
"Detection octaves. Use 0 to do single scale."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( BRISK  ,
PatternScale  ,
float  ,
1.  0,
"Apply this scale to the pattern used for sampling the neighbourhood of a keypoint."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Bayes  ,
VirtualPlacePriorThr  ,
float  ,
0.  9,
"Virtual place prior"   
) [private]
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::Parameters::RTABMAP_PARAM ( VhEp  ,
MatchCountMin  ,
int  ,
,
"Minimum of matching visual words pairs to accept the loop hypothesis."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( VhEp  ,
RansacParam1  ,
float  ,
3.  0,
"Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( VhEp  ,
RansacParam2  ,
float  ,
0.  99,
"Fundamental matrix (see cvFindFundamentalMat()): Performance of the RANSAC."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
Enabled  ,
bool  ,
true  ,
""   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
PoseScanMatching  ,
bool  ,
false  ,
"Laser scan matching for odometry pose correction (laser scans are required)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LinearUpdate  ,
float  ,
0.  0,
"Min linear displacement to update the map. Rehearsal is done prior to  this,
so weights are still updated."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
AngularUpdate  ,
float  ,
0.  0,
"Min angular displacement to update the map. Rehearsal is done prior to  this,
so weights are still updated."   
) [private]
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::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 mode 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::Parameters::RTABMAP_PARAM ( RGBD  ,
GoalReachedRadius  ,
float  ,
0.  5,
"Goal reached radius (m)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
PlanVirtualLinks  ,
bool  ,
true  ,
"Before planning in the  graph,
close nodes are linked together.Radius is defined by\"RGBD/GoalReachedRadius\" parameter."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
GoalsSavedInUserData  ,
bool  ,
true  ,
"When a goal is received and processed with  success,
it is saved in user data of the location with this format:\"GOAL:#\"."   
) [private]
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::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::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalImmunizationRatio  ,
float  ,
0.  25,
"Ratio of working memory for which local nodes are immunized from transfer."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalLoopDetectionTime  ,
bool  ,
false  ,
"Detection over all locations in STM."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalLoopDetectionSpace  ,
bool  ,
false  ,
"Detection over locations (in Working Memory or STM) near in space."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalLoopDetectionMaxGraphDepth  ,
int  ,
50  ,
"Maximum depth from the current/last loop closure location and the local loop closure hypotheses. Set 0 to ignore."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalLoopDetectionPathFilteringRadius  ,
float  ,
0.  5,
"Path filtering radius."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
LocalLoopDetectionPathOdomPosesUsed  ,
bool  ,
true  ,
"When comparing to a local  path,
merge the scan using the odometry poses instead of the ones in the optimized local graph."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
OptimizeStrategy  ,
int  ,
 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
OptimizeIterations  ,
int  ,
100  ,
"Optimization iterations."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
OptimizeSlam2D  ,
bool  ,
false  ,
"If optimization is done only on  x,
y and theta(3DoF).  Otherwise,
it is done on full 6DoF poses."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( RGBD  ,
OptimizeVarianceIgnored  ,
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::Parameters::RTABMAP_PARAM ( Odom  ,
Strategy  ,
int  ,
 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
FeatureType  ,
int  ,
 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
MaxFeatures  ,
int  ,
400  ,
"0 no limits."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
InlierDistance  ,
float  ,
0.  02,
"Maximum distance for visual word correspondences."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
MinInliers  ,
int  ,
20  ,
"Minimum visual word correspondences to compute geometry transform."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
Iterations  ,
int  ,
30  ,
"Maximum iterations to compute the transform from visual words."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
RefineIterations  ,
int  ,
,
"Number of iterations used to refine the transformation found by RANSAC. 0 means that the transformation is not refined."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
MaxDepth  ,
float  ,
4.  0,
"Max depth of the words (0 means no limit)."   
) [private]
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::Parameters::RTABMAP_PARAM ( Odom  ,
Force2D  ,
bool  ,
false  ,
"Force 2D transform (3Dof: x,y and yaw)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
FillInfoData  ,
bool  ,
true  ,
"Fill info with data (inliers/outliers features)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
PnPEstimation  ,
bool  ,
false  ,
"(PnP) Pose estimation from 2D to 3D correspondences instead of 3D to 3D correspondences."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
PnPReprojError  ,
double  ,
8.  0,
"PnP reprojection error."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Odom  ,
PnPFlags  ,
int  ,
,
"PnP flags:  0 = Iterative,
= EPNP 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomBow  ,
LocalHistorySize  ,
int  ,
1000  ,
"Local history size:  If,
0(example 5000)  ,
the odometry will maintain a local map of X maximum words."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomBow  ,
NNType  ,
int  ,
,
kNNFlannNaive = 0,
kNNFlannKdTree  = 1,
kNNFlannLSH  = 2,
kNNBruteForce  = 3 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomBow  ,
NNDR  ,
float  ,
0.  8,
"NNDR: nearest neighbor distance ratio."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomMono  ,
InitMinFlow  ,
float  ,
100  ,
"Minimum optical flow required for the initialization step."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomMono  ,
InitMinTranslation  ,
float  ,
0.  1,
"Minimum translation required for the initialization step."   
) [private]
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::Parameters::RTABMAP_PARAM ( OdomMono  ,
MaxVariance  ,
float  ,
0.  01,
"Maximum variance to add new points to local map."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomFlow  ,
WinSize  ,
int  ,
16  ,
"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomFlow  ,
Iterations  ,
int  ,
30  ,
"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomFlow  ,
Eps  ,
double  ,
0.  01,
"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomFlow  ,
MaxLevel  ,
int  ,
,
"Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomSubPix  ,
WinSize  ,
int  ,
,
"Can be used with BOW and optical flow approaches. See cv::cornerSubPix()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomSubPix  ,
Iterations  ,
int  ,
,
"Can be used with BOW and optical flow approaches. See cv::cornerSubPix(). 0 disables sub pixel refining."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( OdomSubPix  ,
Eps  ,
double  ,
0.  02,
"Can be used with BOW and optical flow approaches. See cv::cornerSubPix()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp  ,
Type  ,
int  ,
,
0 = No ICP,
= ICP 3D 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp  ,
MaxTranslation  ,
float  ,
0.  2,
"Maximum ICP translation correction accepted (m)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp  ,
MaxRotation  ,
float  ,
0.  78,
"Maximum ICP rotation correction accepted (rad)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
MinInliers  ,
int  ,
20  ,
"Minimum visual word correspondences to compute geometry transform."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
InlierDistance  ,
float  ,
0.  02,
"Maximum distance for visual word correspondences."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
Iterations  ,
int  ,
100  ,
"Maximum iterations to compute the transform from visual words."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
MaxDepth  ,
float  ,
4.  0,
"Max depth of the words (0 means no limit)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
Force2D  ,
bool  ,
false  ,
"Force 2D transform (3Dof: x,y and yaw)."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
EpipolarGeometry  ,
bool  ,
false  ,
"Use epipolar geometry to compute the loop closure transform."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccBow  ,
EpipolarGeometryVar  ,
float  ,
0.  02,
"Epipolar geometry maximum variance to accept the loop closure."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccReextract  ,
NNType  ,
int  ,
,
kNNFlannNaive = 0,
kNNFlannKdTree  = 1,
kNNFlannLSH  = 2,
kNNBruteForce  = 3 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccReextract  ,
NNDR  ,
float  ,
0.  8,
"NNDR: nearest neighbor distance ratio."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccReextract  ,
FeatureType  ,
int  ,
 
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccReextract  ,
MaxWords  ,
int  ,
600  ,
"0 no limits."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
Decimation  ,
int  ,
,
"Depth image decimation."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
MaxDepth  ,
float  ,
4.  0,
"Max cloud depth."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
VoxelSize  ,
float  ,
0.  01,
"Voxel size to be used for ICP computation."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
Samples  ,
int  ,
,
"Random samples to be used for ICP computation. Not used if voxelSize is set."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
MaxCorrespondenceDistance  ,
float  ,
0.  05,
"ICP 3D: Max distance for point correspondences."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
Iterations  ,
int  ,
30  ,
"Max iterations."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
CorrespondenceRatio  ,
float  ,
0.  7,
"Ratio of matching correspondences to accept the transform."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
PointToPlane  ,
bool  ,
false  ,
"Use point to plane ICP."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp3  ,
PointToPlaneNormalNeighbors  ,
int  ,
20  ,
"Number of neighbors to compute normals for point to plane."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp2  ,
MaxCorrespondenceDistance  ,
float  ,
0.  05,
"Max distance for point correspondences."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp2  ,
Iterations  ,
int  ,
30  ,
"Max iterations."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp2  ,
CorrespondenceRatio  ,
float  ,
0.  3,
"Ratio of matching correspondences to accept the transform."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( LccIcp2  ,
VoxelSize  ,
float  ,
0.  025,
"Voxel size to be used for ICP computation."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
WinSize  ,
int  ,
16  ,
"See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
Iterations  ,
int  ,
30  ,
"See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
Eps  ,
double  ,
0.  01,
"See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
MaxLevel  ,
int  ,
,
"See cv::calcOpticalFlowPyrLK()."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM ( Stereo  ,
MaxSlope  ,
float  ,
0.  1,
"The maximum slope for each stereo pairs."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM_COND ( Kp  ,
NNStrategy  ,
int  ,
RTABMAP_NONFREE  ,
,
,
kNNFlannNaive = 0,
kNNFlannKdTree  = 1,
kNNFlannLSH  = 2,
kNNBruteForce  = 3 
) [private]
rtabmap::Parameters::RTABMAP_PARAM_COND ( Kp  ,
NndrRatio  ,
float  ,
RTABMAP_NONFREE  ,
0.  8,
0.  9,
"NNDR ratio (A matching pair is detected, if its distance is closer than X times the distance of the second nearest neighbor.)"   
) [private]
rtabmap::Parameters::RTABMAP_PARAM_COND ( Kp  ,
DetectorStrategy  ,
int  ,
RTABMAP_NONFREE  ,
,
 
) [private]
rtabmap::Parameters::RTABMAP_PARAM_COND ( LccReextract  ,
Activated  ,
bool  ,
RTABMAP_NONFREE  ,
false  ,
true  ,
"Activate re-extracting features on global loop closure."   
) [private]
rtabmap::Parameters::RTABMAP_PARAM_STR ( Rtabmap  ,
WorkingDirectory  ,
Parameters::  getDefaultWorkingDirectory(),
"Working directory."   
) [private]
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::Parameters::RTABMAP_PARAM_STR ( Kp  ,
DictionaryPath  ,
""  ,
"Path of the pre-computed dictionary"   
) [private]
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"   
) [private]
rtabmap::Parameters::RTABMAP_PARAM_STR ( Odom  ,
RoiRatios  ,
"0.0 0.0 0.0 0.0"  ,
"Region of interest ratios ."  [left, right, top, bottom] 
) [private]

Member Data Documentation

Definition at line 423 of file Parameters.h.

Definition at line 424 of file Parameters.h.

Definition at line 422 of file Parameters.h.


The documentation for this class was generated from the following files:


rtabmap
Author(s): Mathieu Labbe
autogenerated on Fri Aug 28 2015 12:51:44