Parameters.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2010-2016, Mathieu Labbe - IntRoLab - Universite de Sherbrooke
00003 All rights reserved.
00004 
00005 Redistribution and use in source and binary forms, with or without
00006 modification, are permitted provided that the following conditions are met:
00007     * Redistributions of source code must retain the above copyright
00008       notice, this list of conditions and the following disclaimer.
00009     * Redistributions in binary form must reproduce the above copyright
00010       notice, this list of conditions and the following disclaimer in the
00011       documentation and/or other materials provided with the distribution.
00012     * Neither the name of the Universite de Sherbrooke nor the
00013       names of its contributors may be used to endorse or promote products
00014       derived from this software without specific prior written permission.
00015 
00016 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
00017 ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
00018 WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00019 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY
00020 DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
00021 (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00022 LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
00023 ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
00024 (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
00025 SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00026 */
00027 
00028 #ifndef PARAMETERS_H_
00029 #define PARAMETERS_H_
00030 
00031 // default parameters
00032 #include "rtabmap/core/RtabmapExp.h" // DLL export/import defines
00033 #include "rtabmap/core/Version.h" // DLL export/import defines
00034 #include <string>
00035 #include <map>
00036 
00037 namespace rtabmap
00038 {
00039 
00040 typedef std::map<std::string, std::string> ParametersMap; // Key, value
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                 static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
00066         private: \
00067                 class Dummy##PREFIX##NAME { \
00068                 public: \
00069                         Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, #DEFAULT_VALUE)); \
00070                                                                    parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
00071                                                                    descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00072                 }; \
00073                 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00074 // end define PARAM
00075 
00095 #define RTABMAP_PARAM_STR(PREFIX, NAME, DEFAULT_VALUE, DESCRIPTION) \
00096         public: \
00097                 static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
00098                 static std::string default##PREFIX##NAME() {return DEFAULT_VALUE;} \
00099                 static std::string type##PREFIX##NAME() {return std::string("string");} \
00100         private: \
00101                 class Dummy##PREFIX##NAME { \
00102                 public: \
00103                         Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, DEFAULT_VALUE)); \
00104                                                                    parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, "string")); \
00105                                                                    descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00106                 }; \
00107                 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00108 // end define PARAM
00109 
00128 #define RTABMAP_PARAM_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
00129         public: \
00130                 static std::string k##PREFIX##NAME() {return std::string(#PREFIX "/" #NAME);} \
00131                 static TYPE default##PREFIX##NAME() {return COND?DEFAULT_VALUE1:DEFAULT_VALUE2;} \
00132                 static std::string type##PREFIX##NAME() {return std::string(#TYPE);} \
00133         private: \
00134                 class Dummy##PREFIX##NAME { \
00135                 public: \
00136                         Dummy##PREFIX##NAME() {parameters_.insert(ParametersPair(#PREFIX "/" #NAME, COND?#DEFAULT_VALUE1:#DEFAULT_VALUE2)); \
00137                                                                    parametersType_.insert(ParametersPair(#PREFIX "/" #NAME, #TYPE)); \
00138                                                                    descriptions_.insert(ParametersPair(#PREFIX "/" #NAME, DESCRIPTION));} \
00139                 }; \
00140                 Dummy##PREFIX##NAME dummy##PREFIX##NAME;
00141 // end define PARAM
00142 
00167 class RTABMAP_EXP Parameters
00168 {
00169         // Rtabmap parameters
00170         RTABMAP_PARAM(Rtabmap, VhStrategy,                       int, 0,     "None 0, Similarity 1, Epipolar 2.");
00171         RTABMAP_PARAM(Rtabmap, PublishStats,                 bool, true, "Publishing statistics.");
00172         RTABMAP_PARAM(Rtabmap, PublishLastSignature,         bool, true, "Publishing last signature.");
00173         RTABMAP_PARAM(Rtabmap, PublishPdf,                       bool, true, "Publishing pdf.");
00174         RTABMAP_PARAM(Rtabmap, PublishLikelihood,                bool, true, "Publishing likelihood.");
00175         RTABMAP_PARAM(Rtabmap, TimeThr,                              float, 0,   "Maximum time allowed for the detector (ms) (0 means infinity).");
00176         RTABMAP_PARAM(Rtabmap, MemoryThr,                            int, 0,     "Maximum signatures in the Working Memory (ms) (0 means infinity).");
00177         RTABMAP_PARAM(Rtabmap, DetectionRate,                float, 1,   "Detection rate. RTAB-Map will filter input images to satisfy this rate.");
00178         RTABMAP_PARAM(Rtabmap, ImageBufferSize,              unsigned int, 1, "Data buffer size (0 min inf).");
00179         RTABMAP_PARAM(Rtabmap, CreateIntermediateNodes,      bool, false, "Create intermediate nodes between loop closure detection. Only used when Rtabmap/DetectionRate>0.");
00180         RTABMAP_PARAM_STR(Rtabmap, WorkingDirectory,         "", "Working directory.");
00181         RTABMAP_PARAM(Rtabmap, MaxRetrieved,                 unsigned int, 2, "Maximum locations retrieved at the same time from LTM.");
00182         RTABMAP_PARAM(Rtabmap, StatisticLogsBufferedInRAM,   bool, true, "Statistic logs buffered in RAM instead of written to hard drive after each iteration.");
00183         RTABMAP_PARAM(Rtabmap, StatisticLogged,                  bool, false, "Logging enabled.");
00184         RTABMAP_PARAM(Rtabmap, StatisticLoggedHeaders,           bool, true, "Add column header description to log files.");
00185         RTABMAP_PARAM(Rtabmap, StartNewMapOnLoopClosure,     bool, false, "Start a new map only if there is a global loop closure with a previous map.");
00186 
00187         // Hypotheses selection
00188         RTABMAP_PARAM(Rtabmap, LoopThr,              float, 0.11,       "Loop closing threshold.");
00189         RTABMAP_PARAM(Rtabmap, LoopRatio,        float, 0,          "The loop closure hypothesis must be over LoopRatio x lastHypothesisValue.");
00190 
00191         // Memory
00192         RTABMAP_PARAM(Mem, RehearsalSimilarity,     float, 0.6,         "Rehearsal similarity.");
00193         RTABMAP_PARAM(Mem, ImageKept,                   bool, false,    "Keep raw images in RAM.");
00194         RTABMAP_PARAM(Mem, BinDataKept,                     bool, true,         "Keep binary data in db.");
00195         RTABMAP_PARAM(Mem, RawDescriptorsKept,          bool, true,     "Raw descriptors kept in memory.");
00196         RTABMAP_PARAM(Mem, MapLabelsAdded,                  bool, true,         "Create map labels. The first node of a map will be labelled as \"map#\" where # is the map ID.");
00197         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).");
00198         RTABMAP_PARAM(Mem, NotLinkedNodesKept,      bool, true,         "Keep not linked nodes in db (rehearsed nodes and deleted nodes).");
00199         RTABMAP_PARAM(Mem, STMSize,                     unsigned int, 10, "Short-term memory size.");
00200         RTABMAP_PARAM(Mem, IncrementalMemory,       bool, true,         "SLAM mode, otherwise it is Localization mode.");
00201         RTABMAP_PARAM(Mem, ReduceGraph,             bool, false,        "Reduce graph. Merge nodes when loop closures are added (ignoring those with user data set).");
00202         RTABMAP_PARAM(Mem, RecentWmRatio,           float, 0.2,         "Ratio of locations after the last loop closure in WM that cannot be transferred.");
00203         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.");
00204         RTABMAP_PARAM(Mem, RehearsalIdUpdatedToNewOne, bool, false, "On merge, update to new id. When false, no copy.");
00205         RTABMAP_PARAM(Mem, RehearsalWeightIgnoredWhileMoving, bool, false, "When the robot is moving, weights are not updated on rehearsal.");
00206         RTABMAP_PARAM(Mem, GenerateIds,             bool, true,     "True=Generate location IDs, False=use input image IDs.");
00207         RTABMAP_PARAM(Mem, BadSignaturesIgnored,    bool, false,     "Bad signatures are ignored.");
00208         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.");
00209         RTABMAP_PARAM(Mem, ImagePreDecimation,      int, 1,          "Image decimation (>=1) before features extraction.");
00210         RTABMAP_PARAM(Mem, ImagePostDecimation,     int, 1,          "Image decimation (>=1) of saved data in created signatures (after features extraction). Decimation is done from the original image.");
00211         RTABMAP_PARAM(Mem, LaserScanDownsampleStepSize, int, 1,      "If > 1, downsample the laser scans when creating a signature.");
00212         RTABMAP_PARAM(Mem, UseOdomFeatures,             bool, false, "Use odometry features.");
00213 
00214         // KeypointMemory (Keypoint-based)
00215         RTABMAP_PARAM(Kp, NNStrategy,            int, 1,            "kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4");
00216         RTABMAP_PARAM(Kp, IncrementalDictionary, bool, true,            "");
00217         RTABMAP_PARAM(Kp, IncrementalFlann,      bool, true,            "When using FLANN based strategy, add/remove points to its index without always rebuilding the index (the index is built only when the dictionary doubles in size).");
00218         RTABMAP_PARAM(Kp, MaxDepth,              float, 0,              "Filter extracted keypoints by depth (0=inf).");
00219         RTABMAP_PARAM(Kp, MinDepth,              float, 0,              "Filter extracted keypoints by depth.");
00220         RTABMAP_PARAM(Kp, MaxFeatures,           int, 400,                      "Maximum features extracted from the images (0 means not bounded, <0 means no extraction).");
00221         RTABMAP_PARAM(Kp, BadSignRatio,          float, 0.5,            "Bad signature ratio (less than Ratio x AverageWordsPerImage = bad).");
00222         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.)");
00223 #ifdef RTABMAP_NONFREE
00224         RTABMAP_PARAM(Kp, DetectorStrategy,      int, 0,            "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB.");
00225 #else
00226         RTABMAP_PARAM(Kp, DetectorStrategy,      int, 2,            "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB.");
00227 #endif
00228         RTABMAP_PARAM(Kp, TfIdfLikelihoodUsed,   bool, true,            "Use of the td-idf strategy to compute the likelihood.");
00229         RTABMAP_PARAM(Kp, Parallelized,          bool, true,            "If the dictionary update and signature creation were parallelized.");
00230         RTABMAP_PARAM_STR(Kp, RoiRatios, "0.0 0.0 0.0 0.0",             "Region of interest ratios [left, right, top, bottom].");
00231         RTABMAP_PARAM_STR(Kp, DictionaryPath,    "",                            "Path of the pre-computed dictionary");
00232         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).");
00233     RTABMAP_PARAM(Kp, SubPixWinSize,            int, 3,        "See cv::cornerSubPix().");
00234         RTABMAP_PARAM(Kp, SubPixIterations,         int, 0,        "See cv::cornerSubPix(). 0 disables sub pixel refining.");
00235         RTABMAP_PARAM(Kp, SubPixEps,                double, 0.02,  "See cv::cornerSubPix().");
00236 
00237         //Database
00238         RTABMAP_PARAM(DbSqlite3, InMemory,         bool, false,                 "Using database in the memory instead of a file on the hard disk.");
00239         RTABMAP_PARAM(DbSqlite3, CacheSize,    unsigned int, 10000, "Sqlite cache size (default is 2000).");
00240         RTABMAP_PARAM(DbSqlite3, JournalMode,  int, 3,                          "0=DELETE, 1=TRUNCATE, 2=PERSIST, 3=MEMORY, 4=OFF (see sqlite3 doc : \"PRAGMA journal_mode\")");
00241         RTABMAP_PARAM(DbSqlite3, Synchronous,  int, 0,                          "0=OFF, 1=NORMAL, 2=FULL (see sqlite3 doc : \"PRAGMA synchronous\")");
00242         RTABMAP_PARAM(DbSqlite3, TempStore,    int, 2,                          "0=DEFAULT, 1=FILE, 2=MEMORY (see sqlite3 doc : \"PRAGMA temp_store\")");
00243 
00244         // Keypoints descriptors/detectors
00245         RTABMAP_PARAM(SURF, Extended,             bool, false,      "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
00246         RTABMAP_PARAM(SURF, HessianThreshold, float, 500,               "Threshold for hessian keypoint detector used in SURF.");
00247         RTABMAP_PARAM(SURF, Octaves,              int, 4,                       "Number of pyramid octaves the keypoint detector will use.");
00248         RTABMAP_PARAM(SURF, OctaveLayers,         int, 2,                       "Number of octave layers within each octave.");
00249         RTABMAP_PARAM(SURF, Upright,          bool, false,      "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
00250         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.");
00251         RTABMAP_PARAM(SURF, GpuKeypointsRatio,    float, 0.01,  "Used with SURF GPU.");
00252 
00253         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).");
00254         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.");
00255         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.");
00256         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).");
00257         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.");
00258 
00259         RTABMAP_PARAM(BRIEF, Bytes,                int, 32,     "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
00260 
00261         RTABMAP_PARAM(FAST, Threshold,          int, 10,            "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
00262         RTABMAP_PARAM(FAST, NonmaxSuppression,  bool, true,     "If true, non-maximum suppression is applied to detected corners (keypoints).");
00263         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.");
00264         RTABMAP_PARAM(FAST, GpuKeypointsRatio,  double, 0.05,   "Used with FAST GPU.");
00265         RTABMAP_PARAM(FAST, MinThreshold,       int, 1,             "Minimum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
00266         RTABMAP_PARAM(FAST, MaxThreshold,       int, 200,           "Maximum threshold. Used only when FAST/GridRows and FAST/GridCols are set.");
00267         RTABMAP_PARAM(FAST, GridRows,           int, 4,         "Grid rows (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell.");
00268         RTABMAP_PARAM(FAST, GridCols,           int, 4,         "Grid cols (0 to disable). Adapts the detector to partition the source image into a grid and detect points in each cell.");
00269 
00270         RTABMAP_PARAM(GFTT, QualityLevel, double, 0.001, "");
00271         RTABMAP_PARAM(GFTT, MinDistance, double, 5, "");
00272         RTABMAP_PARAM(GFTT, BlockSize, int, 3, "");
00273         RTABMAP_PARAM(GFTT, UseHarrisDetector, bool, false, "");
00274         RTABMAP_PARAM(GFTT, K, double, 0.04, "");
00275 
00276         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.");
00277         RTABMAP_PARAM(ORB, NLevels,              int, 8,       "The number of pyramid levels. The smallest level will have linear size equal to input_image_linear_size/pow(scaleFactor, nlevels).");
00278         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.");
00279         RTABMAP_PARAM(ORB, FirstLevel,           int, 0,       "It should be 0 in the current implementation.");
00280         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).");
00281         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.");
00282         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.");
00283         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.");
00284 
00285         RTABMAP_PARAM(FREAK, OrientationNormalized, bool, true,   "Enable orientation normalization.");
00286         RTABMAP_PARAM(FREAK, ScaleNormalized,       bool, true,   "Enable scale normalization.");
00287         RTABMAP_PARAM(FREAK, PatternScale,          float, 22,    "Scaling of the description pattern.");
00288         RTABMAP_PARAM(FREAK, NOctaves,              int, 4,        "Number of octaves covered by the detected keypoints.");
00289 
00290         RTABMAP_PARAM(BRISK, Thresh,                int, 30,      "FAST/AGAST detection threshold score.");
00291         RTABMAP_PARAM(BRISK, Octaves,               int, 3,       "Detection octaves. Use 0 to do single scale.");
00292         RTABMAP_PARAM(BRISK, PatternScale,          float, 1,    "Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
00293 
00294         // BayesFilter
00295         RTABMAP_PARAM(Bayes, VirtualPlacePriorThr,           float, 0.9, "Virtual place prior");
00296         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, ...}.");
00297         RTABMAP_PARAM(Bayes, FullPredictionUpdate,           bool, false, "Regenerate all the prediction matrix on each iteration (otherwise only removed/added ids are updated).");
00298 
00299         // Verify hypotheses
00300         RTABMAP_PARAM(VhEp, MatchCountMin, int, 8,              "Minimum of matching visual words pairs to accept the loop hypothesis.");
00301         RTABMAP_PARAM(VhEp, RansacParam1,  float, 3,    "Fundamental matrix (see cvFindFundamentalMat()): Max distance (in pixels) from the epipolar line for a point to be inlier.");
00302         RTABMAP_PARAM(VhEp, RansacParam2,  float, 0.99, "Fundamental matrix (see cvFindFundamentalMat()): Performance of the RANSAC.");
00303 
00304         // RGB-D SLAM
00305         RTABMAP_PARAM(RGBD, Enabled,                  bool, true,  "");
00306         RTABMAP_PARAM(RGBD, LinearUpdate,             float, 0.1,  "Minimum linear displacement to update the map. Rehearsal is done prior to this, so weights are still updated.");
00307         RTABMAP_PARAM(RGBD, AngularUpdate,            float, 0.1,  "Minimum angular displacement to update the map. Rehearsal is done prior to this, so weights are still updated.");
00308         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).");
00309         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).");
00310         RTABMAP_PARAM(RGBD, OptimizeMaxError,         float, 1,    "Reject loop closures if optimization error is greater than this value (0=disabled). This will help to detect when a wrong loop closure is added to the graph. Not compatible with \"Optimizer/Robust\" if enabled.");
00311         RTABMAP_PARAM(RGBD, GoalReachedRadius,        float, 0.5,  "Goal reached radius (m).");
00312         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.");
00313         RTABMAP_PARAM(RGBD, PlanLinearVelocity,       float, 0,    "Linear velocity (m/sec) used to compute path weights.");
00314         RTABMAP_PARAM(RGBD, PlanAngularVelocity,      float, 0,    "Angular velocity (rad/sec) used to compute path weights.");
00315         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:#\".");
00316         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).");
00317         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.");
00318         RTABMAP_PARAM(RGBD, LocalImmunizationRatio,   float, 0.25, "Ratio of working memory for which local nodes are immunized from transfer.");
00319         RTABMAP_PARAM(RGBD, ScanMatchingIdsSavedInLinks, bool, true,      "Save scan matching IDs in link's user data.");
00320         RTABMAP_PARAM(RGBD, NeighborLinkRefining,          bool, false,  "When a new node is added to the graph, the transformation of its neighbor link to the previous node is refined using ICP (laser scans required!).");
00321         RTABMAP_PARAM(RGBD, LoopClosureReextractFeatures,  bool, false,  "Extract features even if there are some already in the nodes.");
00322 
00323         // Local/Proximity loop closure detection
00324         RTABMAP_PARAM(RGBD, ProximityByTime,              bool, false,  "Detection over all locations in STM.");
00325         RTABMAP_PARAM(RGBD, ProximityBySpace,             bool, true,   "Detection over locations (in Working Memory or STM) near in space.");
00326         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.");
00327         RTABMAP_PARAM(RGBD, ProximityPathFilteringRadius, float, 0.5,   "Path filtering radius.");
00328         RTABMAP_PARAM(RGBD, ProximityPathRawPosesUsed,    bool, true,   "When comparing to a local path, merge the scan using the odometry poses (with neighbor link optimizations) instead of the ones in the optimized local graph.");
00329         RTABMAP_PARAM(RGBD, ProximityAngle,               float, 45,    "Maximum angle (degrees) for visual proximity detection.");
00330 
00331         // Graph optimization
00332 #ifdef RTABMAP_GTSAM
00333         RTABMAP_PARAM(Optimizer, Strategy,          int, 2,          "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
00334 #else
00335 #ifdef RTABMAP_G2O
00336         RTABMAP_PARAM(Optimizer, Strategy,          int, 1,          "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
00337 #else
00338         RTABMAP_PARAM(Optimizer, Strategy,          int, 0,          "Graph optimization strategy: 0=TORO, 1=g2o and 2=GTSAM.");
00339 #endif
00340 #endif
00341         RTABMAP_PARAM(Optimizer, Iterations,        int, 100,        "Optimization iterations.");
00342         RTABMAP_PARAM(Optimizer, Slam2D,            bool, false,     "If optimization is done only on x,y and theta (3DoF). Otherwise, it is done on full 6DoF poses.");
00343         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.");
00344         RTABMAP_PARAM(Optimizer, Epsilon,           double, 0.0001,  "Stop optimizing when the error improvement is less than this value.");
00345         RTABMAP_PARAM(Optimizer, Robust,            bool, false,      "Robust graph optimization using Vertigo (only work for g2o and GTSAM optimization strategies). Not compatible with \"RGBD/OptimizeMaxError\" if enabled.");
00346 
00347         RTABMAP_PARAM(g2o, Solver,                  int, 0,          "0=csparse 1=pcg 2=cholmod");
00348         RTABMAP_PARAM(g2o, Optimizer,               int, 0,          "0=Levenberg 1=GaussNewton");
00349         RTABMAP_PARAM(g2o, PixelVariance,           double, 1,       "Pixel variance used for SBA.");
00350 
00351         // Odometry
00352         RTABMAP_PARAM(Odom, Strategy,                   int, 0,                 "0=Frame-to-Map (F2M) 1=Frame-to-Frame (F2F)");
00353         RTABMAP_PARAM(Odom, ResetCountdown,         int, 0,         "Automatically reset odometry after X consecutive images on which odometry cannot be computed (value=0 disables auto-reset).");
00354         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)).");
00355         RTABMAP_PARAM(Odom, FillInfoData,                   bool, true,     "Fill info with data (inliers/outliers features).");
00356         RTABMAP_PARAM(Odom, ImageBufferSize,        unsigned int, 1, "Data buffer size (0 min inf).");
00357         RTABMAP_PARAM(Odom, FilteringStrategy,          int, 0,         "0=No filtering 1=Kalman filtering 2=Particle filtering");
00358         RTABMAP_PARAM(Odom, ParticleSize,                   unsigned int, 400,  "Number of particles of the filter.");
00359         RTABMAP_PARAM(Odom, ParticleNoiseT,             float, 0.002,     "Noise (m) of translation components (x,y,z).");
00360         RTABMAP_PARAM(Odom, ParticleLambdaT,            float, 100,       "Lambda of translation components (x,y,z).");
00361         RTABMAP_PARAM(Odom, ParticleNoiseR,             float, 0.002,     "Noise (rad) of rotational components (roll,pitch,yaw).");
00362         RTABMAP_PARAM(Odom, ParticleLambdaR,            float, 100,       "Lambda of rotational components (roll,pitch,yaw).");
00363         RTABMAP_PARAM(Odom, KalmanProcessNoise,         float, 0.001,     "Process noise covariance value.");
00364         RTABMAP_PARAM(Odom, KalmanMeasurementNoise, float, 0.01,      "Process measurement covariance value.");
00365         RTABMAP_PARAM(Odom, GuessMotion,            bool, false,      "Guess next transformation from the last motion computed.");
00366         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.");
00367         RTABMAP_PARAM(Odom, ScanKeyFrameThr,        float, 0.7,       "[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.");
00368         RTABMAP_PARAM(Odom, ImageDecimation,        int, 1,           "Decimation of the images before registration.");
00369         RTABMAP_PARAM(Odom, AlignWithGround,        bool, false,      "Align odometry with the ground on initialization.");
00370 
00371         // Odometry Bag-of-words
00372         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.");
00373         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.");
00374         RTABMAP_PARAM(OdomF2M, ScanMaxSize,         int, 2000,    "[Geometry] Maximum local scan map size.");
00375         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.");
00376         RTABMAP_PARAM_STR(OdomF2M, FixedMapPath,    "",           "Path to a fixed map (RTAB-Map's database) to be used for odometry. Odometry will be constraint to this map. RGB-only images can be used if odometry PnP estimation is used.")
00377 
00378         // Odometry Mono
00379         RTABMAP_PARAM(OdomMono, InitMinFlow,            float, 100,  "Minimum optical flow required for the initialization step.");
00380         RTABMAP_PARAM(OdomMono, InitMinTranslation,     float, 0.1,  "Minimum translation required for the initialization step.");
00381         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.");
00382         RTABMAP_PARAM(OdomMono, MaxVariance,            float, 0.01, "Maximum variance to add new points to local map.");
00383 
00384         // Common registration parameters
00385         RTABMAP_PARAM(Reg, VarianceFromInliersCount, bool, false,   "Set variance as the inverse of the number of inliers. Otherwise, the variance is computed as the average 3D position error of the inliers.");
00386         RTABMAP_PARAM(Reg, Strategy,                 int, 0,        "0=Vis, 1=Icp, 2=VisIcp");
00387         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.");
00388         
00389         // Visual registration parameters
00390         RTABMAP_PARAM(Vis, EstimationType,           int, 0,            "Motion estimation approach: 0:3D->3D, 1:3D->2D (PnP), 2:2D->2D (Epipolar Geometry)");
00391         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).");
00392         RTABMAP_PARAM(Vis, InlierDistance,           float, 0.1,    "[Vis/EstimationType = 0] Maximum distance for feature correspondences. Used by 3D->3D estimation approach.");
00393         RTABMAP_PARAM(Vis, RefineIterations,         int, 5,        "[Vis/EstimationType = 0] Number of iterations used to refine the transformation found by RANSAC. 0 means that the transformation is not refined.");
00394         RTABMAP_PARAM(Vis, PnPReprojError,               float, 2,      "[Vis/EstimationType = 1] PnP reprojection error.");
00395         RTABMAP_PARAM(Vis, PnPFlags,                 int, 1,        "[Vis/EstimationType = 1] PnP flags: 0=Iterative, 1=EPNP, 2=P3P");
00396         RTABMAP_PARAM(Vis, PnPRefineIterations,      int, 1,        "[Vis/EstimationType = 1] Refine iterations.");
00397         RTABMAP_PARAM(Vis, EpipolarGeometryVar,      float, 0.02,   "[Vis/EstimationType = 2] Epipolar geometry maximum variance to accept the transformation.");
00398         RTABMAP_PARAM(Vis, MinInliers,               int, 20,           "Minimum feature correspondences to compute/accept the transformation.");
00399         RTABMAP_PARAM(Vis, Iterations,               int, 100,          "Maximum iterations to compute the transform.");
00400 #ifndef RTABMAP_NONFREE
00401 #ifdef RTABMAP_OPENCV3
00402         // OpenCV 3 without xFeatures2D module doesn't have BRIEF
00403         RTABMAP_PARAM(Vis, FeatureType, int, 8, "0=SURF 1=SIFT 2=ORB 3=FAST/FREAK 4=FAST/BRIEF 5=GFTT/FREAK 6=GFTT/BRIEF 7=BRISK 8=GFTT/ORB.");
00404 #else
00405         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.");
00406 #endif
00407 #else
00408         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.");
00409 #endif
00410         
00411         RTABMAP_PARAM(Vis, MaxFeatures,              int, 1000,     "0 no limits.");
00412         RTABMAP_PARAM(Vis, MaxDepth,                 float, 0,      "Max depth of the features (0 means no limit).");
00413         RTABMAP_PARAM(Vis, MinDepth,                 float, 0,      "Min depth of the features (0 means no limit).");
00414         RTABMAP_PARAM_STR(Vis, RoiRatios,        "0.0 0.0 0.0 0.0", "Region of interest ratios [left, right, top, bottom].");
00415     RTABMAP_PARAM(Vis, SubPixWinSize,            int, 3,        "See cv::cornerSubPix().");
00416         RTABMAP_PARAM(Vis, SubPixIterations,         int, 0,        "See cv::cornerSubPix(). 0 disables sub pixel refining.");
00417         RTABMAP_PARAM(Vis, SubPixEps,                float, 0.02,   "See cv::cornerSubPix().");
00418         RTABMAP_PARAM(Vis, CorType,                  int, 0,        "Correspondences computation approach: 0=Features Matching, 1=Optical Flow");
00419         RTABMAP_PARAM(Vis, CorNNType,                int, 1,        "[Vis/CorrespondenceType=0] kNNFlannNaive=0, kNNFlannKdTree=1, kNNFlannLSH=2, kNNBruteForce=3, kNNBruteForceGPU=4. Used for features matching approach.");
00420         RTABMAP_PARAM(Vis, CorNNDR,                  float, 0.8,    "[Vis/CorrespondenceType=0] NNDR: nearest neighbor distance ratio. Used for features matching approach.");
00421         RTABMAP_PARAM(Vis, CorGuessWinSize,          int, 50,       "[Vis/CorrespondenceType=0] Matching window size (pixels) around projected points when a guess transform is provided to find correspondences. 0 means disabled.");
00422         RTABMAP_PARAM(Vis, CorFlowWinSize,           int, 16,       "[Vis/CorrespondenceType=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.");
00423         RTABMAP_PARAM(Vis, CorFlowIterations,        int, 30,       "[Vis/CorrespondenceType=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.");
00424         RTABMAP_PARAM(Vis, CorFlowEps,               float, 0.01,   "[Vis/CorrespondenceType=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.");
00425         RTABMAP_PARAM(Vis, CorFlowMaxLevel,          int, 3,        "[Vis/CorrespondenceType=1] See cv::calcOpticalFlowPyrLK(). Used for optical flow approach.");
00426 
00427         // ICP registration parameters
00428         RTABMAP_PARAM(Icp, MaxTranslation,            float, 0.2,   "Maximum ICP translation correction accepted (m).");
00429         RTABMAP_PARAM(Icp, MaxRotation,               float, 0.78,  "Maximum ICP rotation correction accepted (rad).");
00430         RTABMAP_PARAM(Icp, VoxelSize,                 float, 0.025, "Uniform sampling voxel size (0=disabled).");
00431         RTABMAP_PARAM(Icp, DownsamplingStep,          int, 1,       "Downsampling step size (1=no sampling). This is done before uniform sampling.");
00432         RTABMAP_PARAM(Icp, MaxCorrespondenceDistance, float, 0.05,  "Max distance for point correspondences.");
00433         RTABMAP_PARAM(Icp, Iterations,                int, 30,          "Max iterations.");
00434         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.");
00435         RTABMAP_PARAM(Icp, CorrespondenceRatio,       float, 0.2,   "Ratio of matching correspondences to accept the transform.");
00436         RTABMAP_PARAM(Icp, PointToPlane,              bool, false,      "Use point to plane ICP.");
00437         RTABMAP_PARAM(Icp, PointToPlaneNormalNeighbors, int, 20,    "Number of neighbors to compute normals for point to plane.");
00438 
00439         // Stereo disparity
00440         RTABMAP_PARAM(Stereo, WinWidth,              int, 15,       "Window width.");
00441         RTABMAP_PARAM(Stereo, WinHeight,             int, 3,        "Window height.");
00442         RTABMAP_PARAM(Stereo, Iterations,            int, 30,       "Maximum iterations.");
00443         RTABMAP_PARAM(Stereo, MaxLevel,              int, 3,        "Maximum pyramid level.");
00444         RTABMAP_PARAM(Stereo, MinDisparity,          int, 1,        "Minimum disparity.");
00445         RTABMAP_PARAM(Stereo, MaxDisparity,          int, 128,      "Maximum disparity.");
00446         RTABMAP_PARAM(Stereo, OpticalFlow,           bool, true,    "Use optical flow to find stereo correspondences, otherwise a simple block matching approach is used.");
00447         RTABMAP_PARAM(Stereo, SSD,                   bool, true,    "[Stereo/OpticalFlow = false] Use Sum of Squared Differences (SSD) window, otherwise Sum of Absolute Differences (SAD) window is used.");
00448         RTABMAP_PARAM(Stereo, Eps,                   double, 0.01,  "[Stereo/OpticalFlow = true] Epsilon stop criterion.");
00449 
00450         RTABMAP_PARAM(StereoBM, BlockSize,           int, 15,       "See cv::StereoBM");
00451         RTABMAP_PARAM(StereoBM, MinDisparity,        int, 0,        "See cv::StereoBM");
00452         RTABMAP_PARAM(StereoBM, NumDisparities,      int, 64,       "See cv::StereoBM");
00453         RTABMAP_PARAM(StereoBM, PreFilterSize,       int, 9,        "See cv::StereoBM");
00454         RTABMAP_PARAM(StereoBM, PreFilterCap,        int, 31,       "See cv::StereoBM");
00455         RTABMAP_PARAM(StereoBM, UniquenessRatio,     int, 15,       "See cv::StereoBM");
00456         RTABMAP_PARAM(StereoBM, TextureThreshold,    int, 10,       "See cv::StereoBM");
00457         RTABMAP_PARAM(StereoBM, SpeckleWindowSize,   int, 100,      "See cv::StereoBM");
00458         RTABMAP_PARAM(StereoBM, SpeckleRange,        int, 4,        "See cv::StereoBM");
00459 
00460 public:
00461         virtual ~Parameters();
00462 
00467         static const ParametersMap & getDefaultParameters()
00468         {
00469                 return parameters_;
00470         }
00471         
00476         static std::string getType(const std::string & paramKey);
00477 
00482         static std::string getDescription(const std::string & paramKey);
00483 
00484         static void parse(const ParametersMap & parameters, const std::string & key, bool & value);
00485         static void parse(const ParametersMap & parameters, const std::string & key, int & value);
00486         static void parse(const ParametersMap & parameters, const std::string & key, unsigned int & value);
00487         static void parse(const ParametersMap & parameters, const std::string & key, float & value);
00488         static void parse(const ParametersMap & parameters, const std::string & key, double & value);
00489         static void parse(const ParametersMap & parameters, const std::string & key, std::string & value);
00490         static void parse(const ParametersMap & parameters, ParametersMap & parametersOut);
00491 
00492         static const char * showUsage();
00493         static ParametersMap parseArguments(int argc, char * argv[]);
00494 
00495         static std::string getVersion();
00496         static std::string getDefaultDatabaseName();
00497         
00498         static std::string serialize(const ParametersMap & parameters);
00499         static ParametersMap deserialize(const std::string & parameters);
00500 
00501         static bool isFeatureParameter(const std::string & param);
00502         static ParametersMap getDefaultOdometryParameters(bool stereo = false);
00503         static ParametersMap getDefaultParameters(const std::string & group);
00504         static ParametersMap filterParameters(const ParametersMap & parameters, const std::string & group);
00505 
00506         static void readINI(const std::string & configFile, ParametersMap & parameters);
00507         static void writeINI(const std::string & configFile, const ParametersMap & parameters);
00508 
00513         static const std::map<std::string, std::pair<bool, std::string> > & getRemovedParameters();
00514         
00518         static const ParametersMap & getBackwardCompatibilityMap();
00519 
00520         static std::string createDefaultWorkingDirectory();
00521 
00522 private:
00523         Parameters();
00524 
00525 private:
00526         static ParametersMap parameters_;
00527         static ParametersMap parametersType_;
00528         static ParametersMap descriptions_;
00529         static Parameters instance_;
00530         
00531         static std::map<std::string, std::pair<bool, std::string> > removedParameters_;
00532         static ParametersMap backwardCompatibilityMap_;
00533 };
00534 
00535 }
00536 
00537 #endif /* PARAMETERS_H_ */
00538 


rtabmap
Author(s): Mathieu Labbe
autogenerated on Sat Jul 23 2016 11:44:17