00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef PARAMETERS_H_
00029 #define PARAMETERS_H_
00030
00031
00032 #include "rtabmap/core/RtabmapExp.h"
00033 #include "rtabmap/core/Version.h"
00034 #include <string>
00035 #include <map>
00036
00037 namespace rtabmap
00038 {
00039
00040 typedef std::map<std::string, std::string> ParametersMap;
00041 typedef std::pair<std::string, std::string> ParametersPair;
00042
00061 #define RTABMAP_PARAM(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION) \
00062 public: \
00063 static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
00064 static TYPE default##PREFIX##NAME() {return DEFAULT_VALUE;} \
00065 private: \
00066 class Dummy##PREFIX##NAME { \
00067 public: \
00068 Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, #DEFAULT_VALUE)); \
00069 descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00070 }; \
00071 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00072
00073
00093 #define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION) \
00094 public: \
00095 static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
00096 static std::string default##PREFIX##NAME() {return DEFAULT_VALUE;} \
00097 private: \
00098 class Dummy##PREFIX##NAME { \
00099 public: \
00100 Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, DEFAULT_VALUE)); \
00101 descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00102 }; \
00103 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00104
00105
00124 #define RTABMAP_PARAM_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
00125 public: \
00126 static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
00127 static TYPE default##PREFIX##NAME() {return COND?DEFAULT_VALUE1:DEFAULT_VALUE2;} \
00128 private: \
00129 class Dummy##PREFIX##NAME { \
00130 public: \
00131 Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, COND?#DEFAULT_VALUE1:#DEFAULT_VALUE2)); \
00132 descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00133 }; \
00134 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00135
00136
00161 class RTABMAP_EXP Parameters
00162 {
00163
00164 RTABMAP_PARAM(Rtabmap, VhStrategy, int, 0, "None 0, Similarity 1, Epipolar 2.");
00165 RTABMAP_PARAM(Rtabmap, PublishStats, bool, true, "Publishing statistics.");
00166 RTABMAP_PARAM(Rtabmap, PublishLastSignature, bool, true, "Publishing last signature.");
00167 RTABMAP_PARAM(Rtabmap, PublishPdf, bool, true, "Publishing pdf.");
00168 RTABMAP_PARAM(Rtabmap, PublishLikelihood, bool, true, "Publishing likelihood.");
00169 RTABMAP_PARAM(Rtabmap, TimeThr, float, 0.0, "Maximum time allowed for the detector (ms) (0 means infinity).");
00170 RTABMAP_PARAM(Rtabmap, MemoryThr, int, 0, "Maximum signatures in the Working Memory (ms) (0 means infinity).");
00171 RTABMAP_PARAM(Rtabmap, DetectionRate, float, 1.0, "Detection rate. RTAB-Map will filter input images to satisfy this rate.");
00172 RTABMAP_PARAM(Rtabmap, ImageBufferSize, int, 1, "Data buffer size (0 min inf).");
00173 RTABMAP_PARAM_STR(Rtabmap, WorkingDirectory, Parameters::getDefaultWorkingDirectory(), "Working directory.");
00174 RTABMAP_PARAM(Rtabmap, MaxRetrieved, unsigned int, 2, "Maximum locations retrieved at the same time from LTM.");
00175 RTABMAP_PARAM(Rtabmap, StatisticLogsBufferedInRAM, bool, true, "Statistic logs buffered in RAM instead of written to hard drive after each iteration.");
00176 RTABMAP_PARAM(Rtabmap, StatisticLogged, bool, false, "Logging enabled.");
00177 RTABMAP_PARAM(Rtabmap, StatisticLoggedHeaders, bool, true, "Add column header description to log files.");
00178 RTABMAP_PARAM(Rtabmap, StartNewMapOnLoopClosure, bool, false, "Start a new map only if there is a global loop closure with a previous map.");
00179
00180
00181 RTABMAP_PARAM(Rtabmap, LoopThr, float, 0.11, "Loop closing threshold.");
00182 RTABMAP_PARAM(Rtabmap, LoopRatio, float, 0.0, "The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.");
00183
00184
00185 RTABMAP_PARAM(Mem, RehearsalSimilarity, float, 0.6, "Rehearsal similarity.");
00186 RTABMAP_PARAM(Mem, ImageKept, bool, false, "Keep raw images in RAM.");
00187 RTABMAP_PARAM(Mem, BinDataKept, bool, true, "Keep binary data in db.");
00188 RTABMAP_PARAM(Mem, NotLinkedNodesKept, bool, true, "Keep not linked nodes in db (rehearsed nodes and deleted nodes).");
00189 RTABMAP_PARAM(Mem, STMSize, unsigned int, 10, "Short-term memory size.");
00190 RTABMAP_PARAM(Mem, IncrementalMemory, bool, true, "SLAM mode, otherwise it is Localization mode.");
00191 RTABMAP_PARAM(Mem, RecentWmRatio, float, 0.2, "Ratio of locations after the last loop closure in WM that cannot be transferred.");
00192 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.");
00193 RTABMAP_PARAM(Mem, RehearsalIdUpdatedToNewOne, bool, false, "On merge, update to new id. When false, no copy.");
00194 RTABMAP_PARAM(Mem, RehearsalWeightIgnoredWhileMoving, bool, false, "When the robot is moving, weights are not updated on rehearsal.");
00195 RTABMAP_PARAM(Mem, GenerateIds, bool, true, "True=Generate location IDs, False=use input image IDs.");
00196 RTABMAP_PARAM(Mem, BadSignaturesIgnored, bool, false, "Bad signatures are ignored.");
00197 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.");
00198 RTABMAP_PARAM(Mem, ImageDecimation, int, 1, "Image decimation (>=1) when creating a signature.");
00199 RTABMAP_PARAM(Mem, LaserScanVoxelSize, float, 0.0, "If > 0.0, voxelize laser scans when creating a signature.");
00200 RTABMAP_PARAM(Mem, LocalSpaceLinksKeptInWM, bool, true, "If local space links are kept in WM.");
00201
00202
00203
00204 RTABMAP_PARAM_COND(Kp, NNStrategy, int, RTABMAP_NONFREE, 1, 3, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
00205 RTABMAP_PARAM(Kp, IncrementalDictionary, bool, true, "");
00206 RTABMAP_PARAM(Kp, MaxDepth, float, 0.0, "Filter extracted keypoints by depth (0=inf)");
00207 RTABMAP_PARAM(Kp, WordsPerImage, int, 400, "");
00208 RTABMAP_PARAM(Kp, BadSignRatio, float, 0.2, "Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).");
00209 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.)");
00210 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.");
00211 RTABMAP_PARAM(Kp, TfIdfLikelihoodUsed, bool, true, "Use of the td-idf strategy to compute the likelihood.");
00212 RTABMAP_PARAM(Kp, Parallelized, bool, true, "If the dictionary update and signature creation were parallelized.");
00213 RTABMAP_PARAM_STR(Kp, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
00214 RTABMAP_PARAM_STR(Kp, DictionaryPath, "", "Path of the pre-computed dictionary");
00215 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).");
00216
00217 RTABMAP_PARAM(Kp, SubPixWinSize, int, 3, "See cv::cornerSubPix().");
00218 RTABMAP_PARAM(Kp, SubPixIterations, int, 0, "See cv::cornerSubPix(). 0 disables sub pixel refining.");
00219 RTABMAP_PARAM(Kp, SubPixEps, double, 0.02, "See cv::cornerSubPix().");
00220
00221
00222 RTABMAP_PARAM(DbSqlite3, InMemory, bool, false, "Using database in the memory instead of a file on the hard disk.");
00223 RTABMAP_PARAM(DbSqlite3, CacheSize, unsigned int, 10000, "Sqlite cache size (default is 2000).");
00224 RTABMAP_PARAM(DbSqlite3, JournalMode, int, 3, "0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")");
00225 RTABMAP_PARAM(DbSqlite3, Synchronous, int, 0, "0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")");
00226 RTABMAP_PARAM(DbSqlite3, TempStore, int, 2, "0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")");
00227
00228
00229 RTABMAP_PARAM(SURF, Extended, bool, false, "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
00230 RTABMAP_PARAM(SURF, HessianThreshold, float, 150.0, "Threshold for hessian keypoint detector used in SURF.");
00231 RTABMAP_PARAM(SURF, Octaves, int, 4, "Number of pyramid octaves the keypoint detector will use.");
00232 RTABMAP_PARAM(SURF, OctaveLayers, int, 2, "Number of octave layers within each octave.");
00233 RTABMAP_PARAM(SURF, Upright, bool, false, "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
00234 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.");
00235 RTABMAP_PARAM(SURF, GpuKeypointsRatio, float, 0.01, "Used with SURF GPU.");
00236
00237 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).");
00238 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.");
00239 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.");
00240 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).");
00241 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.");
00242
00243 RTABMAP_PARAM(BRIEF, Bytes, int, 32, "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
00244
00245 RTABMAP_PARAM(FAST, Threshold, int, 30, "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
00246 RTABMAP_PARAM(FAST, NonmaxSuppression, bool, true, "If true, non-maximum suppression is applied to detected corners (keypoints).");
00247 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.");
00248 RTABMAP_PARAM(FAST, GpuKeypointsRatio, double, 0.05, "Used with FAST GPU.");
00249
00250 RTABMAP_PARAM(GFTT, QualityLevel, double, 0.01, "");
00251 RTABMAP_PARAM(GFTT, MinDistance, double, 5, "");
00252 RTABMAP_PARAM(GFTT, BlockSize, int, 3, "");
00253 RTABMAP_PARAM(GFTT, UseHarrisDetector, bool, false, "");
00254 RTABMAP_PARAM(GFTT, K, double, 0.04, "");
00255
00256 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.");
00257 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).");
00258 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.");
00259 RTABMAP_PARAM(ORB, FirstLevel, int, 0, "It should be 0 in the current implementation.");
00260 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).");
00261 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.");
00262 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.");
00263 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.");
00264
00265 RTABMAP_PARAM(FREAK, OrientationNormalized, bool, true, "Enable orientation normalization.");
00266 RTABMAP_PARAM(FREAK, ScaleNormalized, bool, true, "Enable scale normalization.");
00267 RTABMAP_PARAM(FREAK, PatternScale, float, 22.0, "Scaling of the description pattern.");
00268 RTABMAP_PARAM(FREAK, NOctaves, int, 4, "Number of octaves covered by the detected keypoints.");
00269
00270 RTABMAP_PARAM(BRISK, Thresh, int, 30, "FAST/AGAST detection threshold score.");
00271 RTABMAP_PARAM(BRISK, Octaves, int, 3, "Detection octaves. Use 0 to do single scale.");
00272 RTABMAP_PARAM(BRISK, PatternScale, float, 1.0, "Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
00273
00274
00275 RTABMAP_PARAM(Bayes, VirtualPlacePriorThr, float, 0.9, "Virtual place prior");
00276 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, ...}.");
00277 RTABMAP_PARAM(Bayes, FullPredictionUpdate, bool, false, "Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).");
00278
00279
00280 RTABMAP_PARAM(VhEp, MatchCountMin, int, 8, "Minimum of matching visual words pairs to accept the loop hypothesis.");
00281 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.");
00282 RTABMAP_PARAM(VhEp, RansacParam2, float, 0.99, "Fundamental matrix (see cvFindFundamentalMat()): Performance of the RANSAC.");
00283
00284
00285 RTABMAP_PARAM(RGBD, Enabled, bool, true, "");
00286 RTABMAP_PARAM(RGBD, PoseScanMatching, bool, false, "Laser scan matching for odometry pose correction (laser scans are required).");
00287 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.");
00288 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.");
00289 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).");
00290 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).");
00291 RTABMAP_PARAM(RGBD, GoalReachedRadius, float, 0.5, "Goal reached radius (m).");
00292 RTABMAP_PARAM(RGBD, PlanVirtualLinks, bool, true, "Before planning in the graph, close nodes are linked together. Radius is defined by \"RGBD/GoalReachedRadius\" parameter.");
00293 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:#\".");
00294 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).");
00295 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.");
00296 RTABMAP_PARAM(RGBD, LocalImmunizationRatio, float, 0.25, "Ratio of working memory for which local nodes are immunized from transfer.");
00297
00298
00299 RTABMAP_PARAM(RGBD, LocalLoopDetectionTime, bool, false, "Detection over all locations in STM.");
00300 RTABMAP_PARAM(RGBD, LocalLoopDetectionSpace, bool, false, "Detection over locations (in Working Memory or STM) near in space.");
00301 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.");
00302 RTABMAP_PARAM(RGBD, LocalLoopDetectionPathFilteringRadius, float, 0.5, "Path filtering radius.");
00303 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.");
00304
00305
00306 RTABMAP_PARAM(RGBD, OptimizeStrategy, int, 0, "Graph optimization strategy: 0=TORO and 1=g2o.");
00307 RTABMAP_PARAM(RGBD, OptimizeIterations, int, 100, "Optimization iterations.");
00308 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.");
00309 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.");
00310
00311
00312 RTABMAP_PARAM(Odom, Strategy, int, 0, "0=Bag-of-words 1=Optical Flow");
00313 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.");
00314 RTABMAP_PARAM(Odom, MaxFeatures, int, 400, "0 no limits.");
00315 RTABMAP_PARAM(Odom, InlierDistance, float, 0.02, "Maximum distance for visual word correspondences.");
00316 RTABMAP_PARAM(Odom, MinInliers, int, 20, "Minimum visual word correspondences to compute geometry transform.");
00317 RTABMAP_PARAM(Odom, Iterations, int, 30, "Maximum iterations to compute the transform from visual words.");
00318 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.");
00319 RTABMAP_PARAM(Odom, MaxDepth, float, 4.0, "Max depth of the words (0 means no limit).");
00320 RTABMAP_PARAM(Odom, ResetCountdown, int, 0, "Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).");
00321 RTABMAP_PARAM_STR(Odom, RoiRatios, "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
00322 RTABMAP_PARAM(Odom, Force2D, bool, false, "Force 2D transform (3Dof: x,y and yaw).");
00323 RTABMAP_PARAM(Odom, FillInfoData, bool, true, "Fill info with data (inliers/outliers features).");
00324 RTABMAP_PARAM(Odom, PnPEstimation, bool, false, "(PnP) Pose estimation from 2D to 3D correspondences instead of 3D to 3D correspondences.");
00325 RTABMAP_PARAM(Odom, PnPReprojError, double, 8.0, "PnP reprojection error.");
00326 RTABMAP_PARAM(Odom, PnPFlags, int, 0, "PnP flags: 0=Iterative, 1=EPNP, 2=P3P");
00327
00328
00329 RTABMAP_PARAM(OdomBow, LocalHistorySize, int, 1000, "Local history size: If > 0 (example 5000), the odometry will maintain a local map of X maximum words.");
00330 RTABMAP_PARAM(OdomBow, NNType, int, 3, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
00331 RTABMAP_PARAM(OdomBow, NNDR, float, 0.8, "NNDR: nearest neighbor distance ratio.");
00332
00333
00334 RTABMAP_PARAM(OdomMono, InitMinFlow, float, 100, "Minimum optical flow required for the initialization step.");
00335 RTABMAP_PARAM(OdomMono, InitMinTranslation, float, 0.1, "Minimum translation required for the initialization step.");
00336 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.");
00337 RTABMAP_PARAM(OdomMono, MaxVariance, float, 0.01, "Maximum variance to add new points to local map.");
00338
00339
00340
00341 RTABMAP_PARAM(OdomFlow, WinSize, int, 16, "Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().");
00342 RTABMAP_PARAM(OdomFlow, Iterations, int, 30, "Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().");
00343 RTABMAP_PARAM(OdomFlow, Eps, double, 0.01, "Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().");
00344 RTABMAP_PARAM(OdomFlow, MaxLevel, int, 3, "Used for optical flow approach and for stereo matching. See cv::calcOpticalFlowPyrLK().");
00345
00346 RTABMAP_PARAM(OdomSubPix, WinSize, int, 3, "Can be used with BOW and optical flow approaches. See cv::cornerSubPix().");
00347 RTABMAP_PARAM(OdomSubPix, Iterations, int, 0, "Can be used with BOW and optical flow approaches. See cv::cornerSubPix(). 0 disables sub pixel refining.");
00348 RTABMAP_PARAM(OdomSubPix, Eps, double, 0.02, "Can be used with BOW and optical flow approaches. See cv::cornerSubPix().");
00349
00350
00351 RTABMAP_PARAM(LccIcp, Type, int, 0, "0=No ICP, 1=ICP 3D, 2=ICP 2D");
00352 RTABMAP_PARAM(LccIcp, MaxTranslation, float, 0.2, "Maximum ICP translation correction accepted (m).");
00353 RTABMAP_PARAM(LccIcp, MaxRotation, float, 0.78, "Maximum ICP rotation correction accepted (rad).");
00354
00355 RTABMAP_PARAM(LccBow, MinInliers, int, 20, "Minimum visual word correspondences to compute geometry transform.");
00356 RTABMAP_PARAM(LccBow, InlierDistance, float, 0.02, "Maximum distance for visual word correspondences.");
00357 RTABMAP_PARAM(LccBow, Iterations, int, 100, "Maximum iterations to compute the transform from visual words.");
00358 RTABMAP_PARAM(LccBow, MaxDepth, float, 4.0, "Max depth of the words (0 means no limit).");
00359 RTABMAP_PARAM(LccBow, Force2D, bool, false, "Force 2D transform (3Dof: x,y and yaw).");
00360 RTABMAP_PARAM(LccBow, EpipolarGeometry, bool, false, "Use epipolar geometry to compute the loop closure transform.");
00361 RTABMAP_PARAM(LccBow, EpipolarGeometryVar, float, 0.02, "Epipolar geometry maximum variance to accept the loop closure.");
00362 RTABMAP_PARAM_COND(LccReextract, Activated, bool, RTABMAP_NONFREE, false, true, "Activate re-extracting features on global loop closure.");
00363 RTABMAP_PARAM(LccReextract, NNType, int, 3, "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4.");
00364 RTABMAP_PARAM(LccReextract, NNDR, float, 0.8, "NNDR: nearest neighbor distance ratio.");
00365 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.");
00366 RTABMAP_PARAM(LccReextract, MaxWords, int, 600, "0 no limits.");
00367
00368 RTABMAP_PARAM(LccIcp3, Decimation, int, 8, "Depth image decimation.");
00369 RTABMAP_PARAM(LccIcp3, MaxDepth, float, 4.0, "Max cloud depth.");
00370 RTABMAP_PARAM(LccIcp3, VoxelSize, float, 0.01, "Voxel size to be used for ICP computation.");
00371 RTABMAP_PARAM(LccIcp3, Samples, int, 0, "Random samples to be used for ICP computation. Not used if voxelSize is set.");
00372 RTABMAP_PARAM(LccIcp3, MaxCorrespondenceDistance, float, 0.05, "ICP 3D: Max distance for point correspondences.");
00373 RTABMAP_PARAM(LccIcp3, Iterations, int, 30, "Max iterations.");
00374 RTABMAP_PARAM(LccIcp3, CorrespondenceRatio, float, 0.7, "Ratio of matching correspondences to accept the transform.");
00375 RTABMAP_PARAM(LccIcp3, PointToPlane, bool, false, "Use point to plane ICP.");
00376 RTABMAP_PARAM(LccIcp3, PointToPlaneNormalNeighbors, int, 20, "Number of neighbors to compute normals for point to plane.");
00377
00378 RTABMAP_PARAM(LccIcp2, MaxCorrespondenceDistance, float, 0.05, "Max distance for point correspondences.");
00379 RTABMAP_PARAM(LccIcp2, Iterations, int, 30, "Max iterations.");
00380 RTABMAP_PARAM(LccIcp2, CorrespondenceRatio, float, 0.3, "Ratio of matching correspondences to accept the transform.");
00381 RTABMAP_PARAM(LccIcp2, VoxelSize, float, 0.025, "Voxel size to be used for ICP computation.");
00382
00383
00384 RTABMAP_PARAM(Stereo, WinSize, int, 16, "See cv::calcOpticalFlowPyrLK().");
00385 RTABMAP_PARAM(Stereo, Iterations, int, 30, "See cv::calcOpticalFlowPyrLK().");
00386 RTABMAP_PARAM(Stereo, Eps, double, 0.01, "See cv::calcOpticalFlowPyrLK().");
00387 RTABMAP_PARAM(Stereo, MaxLevel, int, 3, "See cv::calcOpticalFlowPyrLK().");
00388 RTABMAP_PARAM(Stereo, MaxSlope, float, 0.1, "The maximum slope for each stereo pairs.");
00389
00390 public:
00391 virtual ~Parameters();
00392
00397 static const ParametersMap & getDefaultParameters()
00398 {
00399 return parameters_;
00400 }
00401
00406 static std::string getDescription(const std::string & paramKey);
00407
00408 static void parse(const ParametersMap & parameters, const std::string & key, bool & value);
00409 static void parse(const ParametersMap & parameters, const std::string & key, int & value);
00410 static void parse(const ParametersMap & parameters, const std::string & key, unsigned int & value);
00411 static void parse(const ParametersMap & parameters, const std::string & key, float & value);
00412 static void parse(const ParametersMap & parameters, const std::string & key, double & value);
00413 static void parse(const ParametersMap & parameters, const std::string & key, std::string & value);
00414
00415 static std::string getDefaultDatabaseName();
00416
00417 private:
00418 Parameters();
00419 static std::string getDefaultWorkingDirectory();
00420
00421 private:
00422 static ParametersMap parameters_;
00423 static ParametersMap descriptions_;
00424 static Parameters instance_;
00425 };
00426
00427 }
00428
00429 #endif
00430