Settings.h
Go to the documentation of this file.
00001 /*
00002 Copyright (c) 2011-2014, 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 SETTINGS_H_
00029 #define SETTINGS_H_
00030 
00031 #include "find_object/FindObjectExp.h" // DLL export/import defines
00032 #include "find_object/Version.h" // DLL export/import defines
00033 
00034 #include <QtCore/QMap>
00035 #include <QtCore/QVariant>
00036 #include <QtCore/QByteArray>
00037 #include <opencv2/features2d/features2d.hpp>
00038 
00039 namespace find_object {
00040 
00041 class KeypointDetector;
00042 class DescriptorExtractor;
00043 class GPUFeature2D;
00044 
00045 typedef QMap<QString, QVariant> ParametersMap; // Key, value
00046 typedef QMap<QString, QString> ParametersType; // Key, type
00047 typedef QMap<QString, QString> DescriptionsMap; // Key, description
00048 
00049 typedef unsigned int uint;
00050 
00051 // MACRO BEGIN
00052 
00053 #define PARAMETER_GETTER_bool(PREFIX, NAME) \
00054         static bool get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toBool();}
00055 #define PARAMETER_GETTER_int(PREFIX, NAME) \
00056         static int get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toInt();}
00057 #define PARAMETER_GETTER_uint(PREFIX, NAME) \
00058         static uint get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toUInt();}
00059 #define PARAMETER_GETTER_float(PREFIX, NAME) \
00060         static float get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toFloat();}
00061 #define PARAMETER_GETTER_double(PREFIX, NAME) \
00062         static double get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toDouble();}
00063 #define PARAMETER_GETTER_QString(PREFIX, NAME) \
00064         static QString get##PREFIX##_##NAME() {return parameters_.value(#PREFIX "/" #NAME).toString();}
00065 
00066 #define PARAMETER(PREFIX, NAME, TYPE, DEFAULT_VALUE, DESCRIPTION) \
00067         public: \
00068                 static QString k##PREFIX##_##NAME() {return QString(#PREFIX "/" #NAME);} \
00069                 static TYPE default##PREFIX##_##NAME() {return DEFAULT_VALUE;} \
00070                 static QString type##PREFIX##_##NAME() {return QString(#TYPE);} \
00071                 static QString description##PREFIX##_##NAME() {return QString(DESCRIPTION);} \
00072                 PARAMETER_GETTER_##TYPE(PREFIX, NAME) \
00073                 static void set##PREFIX##_##NAME(const TYPE & value) {parameters_[#PREFIX "/" #NAME] = value;} \
00074         private: \
00075                 class Dummy##PREFIX##_##NAME { \
00076                 public: \
00077                         Dummy##PREFIX##_##NAME() { \
00078                                 defaultParameters_.insert(#PREFIX "/" #NAME, QVariant(DEFAULT_VALUE)); \
00079                                 parameters_.insert(#PREFIX "/" #NAME, DEFAULT_VALUE); \
00080                                 parametersType_.insert(#PREFIX "/" #NAME, #TYPE); \
00081                                 descriptions_.insert(#PREFIX "/" #NAME, DESCRIPTION);} \
00082                 }; \
00083                 Dummy##PREFIX##_##NAME dummy##PREFIX##_##NAME;
00084 
00085 #define PARAMETER_COND(PREFIX, NAME, TYPE, COND, DEFAULT_VALUE1, DEFAULT_VALUE2, DESCRIPTION) \
00086         public: \
00087                 static QString k##PREFIX##_##NAME() {return QString(#PREFIX "/" #NAME);} \
00088                 static TYPE default##PREFIX##_##NAME() {return COND?DEFAULT_VALUE1:DEFAULT_VALUE2;} \
00089                 static QString type##PREFIX##_##NAME() {return QString(#TYPE);} \
00090                 static QString description##PREFIX##_##NAME() {return QString(DESCRIPTION);} \
00091                 PARAMETER_GETTER_##TYPE(PREFIX, NAME) \
00092                 static void set##PREFIX##_##NAME(const TYPE & value) {parameters_[#PREFIX "/" #NAME] = value;} \
00093         private: \
00094                 class Dummy##PREFIX##_##NAME { \
00095                 public: \
00096                         Dummy##PREFIX##_##NAME() { \
00097                                 defaultParameters_.insert(#PREFIX "/" #NAME, QVariant(COND?DEFAULT_VALUE1:DEFAULT_VALUE2)); \
00098                                 parameters_.insert(#PREFIX "/" #NAME, COND?DEFAULT_VALUE1:DEFAULT_VALUE2); \
00099                                 parametersType_.insert(#PREFIX "/" #NAME, #TYPE); \
00100                                 descriptions_.insert(#PREFIX "/" #NAME, DESCRIPTION);} \
00101                 }; \
00102                 Dummy##PREFIX##_##NAME dummy##PREFIX##_##NAME;
00103 // MACRO END
00104 
00105 class FINDOBJECT_EXP Settings
00106 {
00107         PARAMETER(Camera, 1deviceId, int, 0, "Device ID (default 0).");
00108         PARAMETER(Camera, 2imageWidth, int, 0, "Image width (0 means default width from camera).");
00109         PARAMETER(Camera, 3imageHeight, int, 0, "Image height (0 means default height from camera).");
00110         PARAMETER(Camera, 4imageRate, double, 2.0, "Image rate in Hz (0 Hz means as fast as possible)."); // Hz
00111         PARAMETER(Camera, 5mediaPath, QString, "", "Video file or directory of images. If set, the camera is not used. See General->videoFormats and General->imageFormats for available formats.");
00112         PARAMETER(Camera, 6useTcpCamera, bool, false, "Use TCP/IP input camera.");
00113         PARAMETER(Camera, 8port, int, 0, "The images server's port when useTcpCamera is checked. Only one client at the same time is allowed.");
00114         PARAMETER(Camera, 9queueSize, int, 1, "Maximum images buffered from TCP. If 0, all images are buffered.");
00115 
00116         //List format : [Index:item0;item1;item3;...]
00117 
00118         PARAMETER_COND(Feature2D, 1Detector, QString, FINDOBJECT_NONFREE, "7:Dense;Fast;GFTT;MSER;ORB;SIFT;Star;SURF;BRISK" , "1:Dense;Fast;GFTT;MSER;ORB;SIFT;Star;SURF;BRISK", "Keypoint detector.");
00119         PARAMETER_COND(Feature2D, 2Descriptor, QString, FINDOBJECT_NONFREE, "3:Brief;ORB;SIFT;SURF;BRISK;FREAK", "0:Brief;ORB;SIFT;SURF;BRISK;FREAK", "Keypoint descriptor.");
00120         PARAMETER(Feature2D, 3MaxFeatures, int, 0, "Maximum features per image. If the number of features extracted is over this threshold, only X features with the highest response are kept. 0 means all features are kept.");
00121         PARAMETER(Feature2D, 4Affine, bool, false, "(ASIFT) Extract features on multiple affine transformations of the image.");
00122         PARAMETER(Feature2D, 5AffineCount, int, 6, "(ASIFT) Higher the value, more affine transformations will be done.");
00123 
00124         PARAMETER(Feature2D, Brief_bytes, int, 32, "Bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.");
00125 
00126         PARAMETER(Feature2D, Dense_initFeatureScale, float, 1.f, "");
00127         PARAMETER(Feature2D, Dense_featureScaleLevels, int, 1, "");
00128         PARAMETER(Feature2D, Dense_featureScaleMul, float, 0.1f, "");
00129         PARAMETER(Feature2D, Dense_initXyStep, int, 6, "");
00130         PARAMETER(Feature2D, Dense_initImgBound, int, 0, "");
00131         PARAMETER(Feature2D, Dense_varyXyStepWithScale, bool, true, "");
00132         PARAMETER(Feature2D, Dense_varyImgBoundWithScale, bool, false, "");
00133 
00134         PARAMETER(Feature2D, Fast_threshold, int, 10, "Threshold on difference between intensity of the central pixel and pixels of a circle around this pixel.");
00135         PARAMETER(Feature2D, Fast_nonmaxSuppression, bool, true, "If true, non-maximum suppression is applied to detected corners (keypoints).");
00136         PARAMETER(Feature2D, 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.");
00137         PARAMETER(Feature2D, Fast_keypointsRatio, double, 0.05, "Used with FAST GPU.");
00138 
00139         PARAMETER(Feature2D, GFTT_maxCorners, int, 1000, "");
00140         PARAMETER(Feature2D, GFTT_qualityLevel, double, 0.01, "");
00141         PARAMETER(Feature2D, GFTT_minDistance, double, 1, "");
00142         PARAMETER(Feature2D, GFTT_blockSize, int, 3, "");
00143         PARAMETER(Feature2D, GFTT_useHarrisDetector, bool, false, "");
00144         PARAMETER(Feature2D, GFTT_k, double, 0.04, "");
00145 
00146         PARAMETER(Feature2D, ORB_nFeatures, int, 500, "The maximum number of features to retain.");
00147         PARAMETER(Feature2D, ORB_scaleFactor, float,  1.2f, "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.");
00148         PARAMETER(Feature2D, 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).");
00149         PARAMETER(Feature2D, ORB_edgeThreshold, int, 31, "This is size of the border where the features are not detected. It should roughly match the patchSize parameter.");
00150         PARAMETER(Feature2D, ORB_firstLevel, int, 0, "It should be 0 in the current implementation.");
00151         PARAMETER(Feature2D, 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).");
00152         PARAMETER(Feature2D, 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.");
00153         PARAMETER(Feature2D, 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.");
00154         PARAMETER(Feature2D, 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.");
00155 
00156         PARAMETER(Feature2D, MSER_delta, int, 5, "");
00157         PARAMETER(Feature2D, MSER_minArea, int, 60, "");
00158         PARAMETER(Feature2D, MSER_maxArea, int, 14400, "");
00159         PARAMETER(Feature2D, MSER_maxVariation, double, 0.25, "");
00160         PARAMETER(Feature2D, MSER_minDiversity, double, 0.2, "");
00161         PARAMETER(Feature2D, MSER_maxEvolution, int, 200, "");
00162         PARAMETER(Feature2D, MSER_areaThreshold, double, 1.01, "");
00163         PARAMETER(Feature2D, MSER_minMargin, double, 0.003, "");
00164         PARAMETER(Feature2D, MSER_edgeBlurSize, int, 5, "");
00165 
00166 #if FINDOBJECT_NONFREE == 1
00167         PARAMETER(Feature2D, 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).");
00168         PARAMETER(Feature2D, 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.");
00169         PARAMETER(Feature2D, 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.");
00170         PARAMETER(Feature2D, 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).");
00171         PARAMETER(Feature2D, 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.");
00172 
00173         PARAMETER(Feature2D, SURF_hessianThreshold, double, 600.0, "Threshold for hessian keypoint detector used in SURF.");
00174         PARAMETER(Feature2D, SURF_nOctaves, int, 4, "Number of pyramid octaves the keypoint detector will use.");
00175         PARAMETER(Feature2D, SURF_nOctaveLayers, int, 2, "Number of octave layers within each octave.");
00176         PARAMETER(Feature2D, SURF_extended, bool, true, "Extended descriptor flag (true - use extended 128-element descriptors; false - use 64-element descriptors).");
00177         PARAMETER(Feature2D, SURF_upright, bool, false, "Up-right or rotated features flag (true - do not compute orientation of features; false - compute orientation).");
00178         PARAMETER(Feature2D, SURF_gpu, bool, false, "GPU-SURF: Use GPU version of SURF. This option is enabled only if OpenCV is built with CUDA and GPUs are detected.");
00179         PARAMETER(Feature2D, SURF_keypointsRatio, float, 0.01f, "Used with SURF GPU.");
00180 #endif
00181 
00182         PARAMETER(Feature2D, Star_maxSize, int, 45, "");
00183         PARAMETER(Feature2D, Star_responseThreshold, int, 30, "");
00184         PARAMETER(Feature2D, Star_lineThresholdProjected, int, 10, "");
00185         PARAMETER(Feature2D, Star_lineThresholdBinarized, int, 8, "");
00186         PARAMETER(Feature2D, Star_suppressNonmaxSize, int, 5, "");
00187 
00188         PARAMETER(Feature2D, BRISK_thresh, int, 30, "FAST/AGAST detection threshold score.");
00189         PARAMETER(Feature2D, BRISK_octaves, int, 3, "Detection octaves. Use 0 to do single scale.");
00190         PARAMETER(Feature2D, BRISK_patternScale, float, 1.0f, "Apply this scale to the pattern used for sampling the neighbourhood of a keypoint.");
00191 
00192         PARAMETER(Feature2D, FREAK_orientationNormalized, bool, true, "Enable orientation normalization.");
00193         PARAMETER(Feature2D, FREAK_scaleNormalized, bool, true, "Enable scale normalization.");
00194         PARAMETER(Feature2D, FREAK_patternScale, float, 22.0f, "Scaling of the description pattern.");
00195         PARAMETER(Feature2D, FREAK_nOctaves, int, 4, "Number of octaves covered by the detected keypoints.");
00196 
00197         PARAMETER_COND(NearestNeighbor, 1Strategy, QString, FINDOBJECT_NONFREE, "1:Linear;KDTree;KMeans;Composite;Autotuned;Lsh;BruteForce", "6:Linear;KDTree;KMeans;Composite;Autotuned;Lsh;BruteForce", "Nearest neighbor strategy.");
00198         PARAMETER_COND(NearestNeighbor, 2Distance_type, QString, FINDOBJECT_NONFREE, "0:EUCLIDEAN_L2;MANHATTAN_L1;MINKOWSKI;MAX;HIST_INTERSECT;HELLINGER;CHI_SQUARE_CS;KULLBACK_LEIBLER_KL;HAMMING", "1:EUCLIDEAN_L2;MANHATTAN_L1;MINKOWSKI;MAX;HIST_INTERSECT;HELLINGER;CHI_SQUARE_CS;KULLBACK_LEIBLER_KL;HAMMING", "Distance type.");
00199         PARAMETER(NearestNeighbor, 3nndrRatioUsed, bool, true, "Nearest neighbor distance ratio approach to accept the best match.");
00200         PARAMETER(NearestNeighbor, 4nndrRatio, float, 0.8f, "Nearest neighbor distance ratio.");
00201         PARAMETER(NearestNeighbor, 5minDistanceUsed, bool, false, "Minimum distance with the nearest descriptor to accept a match.");
00202         PARAMETER(NearestNeighbor, 6minDistance, float, 1.6f, "Minimum distance. You can look at top of this panel where minimum and maximum distances are shown to properly set this parameter depending of the descriptor used.");
00203 
00204         PARAMETER(NearestNeighbor, BruteForce_gpu, bool, false, "Brute force GPU");
00205 
00206         PARAMETER(NearestNeighbor, search_checks, int, 32, "The number of times the tree(s) in the index should be recursively traversed. A higher value for this parameter would give better search precision, but also take more time. If automatic configuration was used when the index was created, the number of checks required to achieve the specified precision was also computed, in which case this parameter is ignored.");
00207         PARAMETER(NearestNeighbor, search_eps, float, 0, "");
00208         PARAMETER(NearestNeighbor, search_sorted, bool, true, "");
00209 
00210         PARAMETER(NearestNeighbor, KDTree_trees, int, 4, "The number of parallel kd-trees to use. Good values are in the range [1..16].");
00211 
00212         PARAMETER(NearestNeighbor, Composite_trees, int, 4, "The number of parallel kd-trees to use. Good values are in the range [1..16].");
00213         PARAMETER(NearestNeighbor, Composite_branching, int, 32, "The branching factor to use for the hierarchical k-means tree.");
00214         PARAMETER(NearestNeighbor, Composite_iterations, int, 11, "The maximum number of iterations to use in the k-means clustering stage when building the k-means tree. A value of -1 used here means that the k-means clustering should be iterated until convergence.");
00215         PARAMETER(NearestNeighbor, Composite_centers_init, QString, "0:RANDOM;GONZALES;KMEANSPP", "The algorithm to use for selecting the initial centers when performing a k-means clustering step. The possible values are CENTERS_RANDOM (picks the initial cluster centers randomly), CENTERS_GONZALES (picks the initial centers using Gonzales’ algorithm) and CENTERS_KMEANSPP (picks the initial centers using the algorithm suggested in arthur_kmeanspp_2007 ).");
00216         PARAMETER(NearestNeighbor, Composite_cb_index, double, 0.2, "This parameter (cluster boundary index) influences the way exploration is performed in the hierarchical kmeans tree. When cb_index is zero the next kmeans domain to be explored is chosen to be the one with the closest center. A value greater then zero also takes into account the size of the domain.");
00217 
00218         PARAMETER(NearestNeighbor, Autotuned_target_precision, double, 0.8, "Is a number between 0 and 1 specifying the percentage of the approximate nearest-neighbor searches that return the exact nearest-neighbor. Using a higher value for this parameter gives more accurate results, but the search takes longer. The optimum value usually depends on the application.");
00219         PARAMETER(NearestNeighbor, Autotuned_build_weight, double, 0.01, "Specifies the importance of the index build time raported to the nearest-neighbor search time. In some applications it’s acceptable for the index build step to take a long time if the subsequent searches in the index can be performed very fast. In other applications it’s required that the index be build as fast as possible even if that leads to slightly longer search times.");
00220         PARAMETER(NearestNeighbor, Autotuned_memory_weight, double, 0, "Is used to specify the tradeoff between time (index build time and search time) and memory used by the index. A value less than 1 gives more importance to the time spent and a value greater than 1 gives more importance to the memory usage.");
00221         PARAMETER(NearestNeighbor, Autotuned_sample_fraction, double, 0.1, "Is a number between 0 and 1 indicating what fraction of the dataset to use in the automatic parameter configuration algorithm. Running the algorithm on the full dataset gives the most accurate results, but for very large datasets can take longer than desired. In such case using just a fraction of the data helps speeding up this algorithm while still giving good approximations of the optimum parameters.");
00222 
00223         PARAMETER(NearestNeighbor, KMeans_branching, int, 32, "The branching factor to use for the hierarchical k-means tree.");
00224         PARAMETER(NearestNeighbor, KMeans_iterations, int, 11, "The maximum number of iterations to use in the k-means clustering stage when building the k-means tree. A value of -1 used here means that the k-means clustering should be iterated until convergence.");
00225         PARAMETER(NearestNeighbor, KMeans_centers_init, QString, "0:RANDOM;GONZALES;KMEANSPP", "The algorithm to use for selecting the initial centers when performing a k-means clustering step. The possible values are CENTERS_RANDOM (picks the initial cluster centers randomly), CENTERS_GONZALES (picks the initial centers using Gonzales’ algorithm) and CENTERS_KMEANSPP (picks the initial centers using the algorithm suggested in arthur_kmeanspp_2007 ).");
00226         PARAMETER(NearestNeighbor, KMeans_cb_index, double, 0.2, "This parameter (cluster boundary index) influences the way exploration is performed in the hierarchical kmeans tree. When cb_index is zero the next kmeans domain to be explored is chosen to be the one with the closest center. A value greater then zero also takes into account the size of the domain.");
00227 
00228         PARAMETER(NearestNeighbor, Lsh_table_number, int, 12, "The number of hash tables to use (between 10 and 30 usually).");
00229         PARAMETER(NearestNeighbor, Lsh_key_size, int, 20, "The size of the hash key in bits (between 10 and 20 usually).");
00230         PARAMETER(NearestNeighbor, Lsh_multi_probe_level, int, 2, "The number of bits to shift to check for neighboring buckets (0 is regular LSH, 2 is recommended).");
00231 
00232         PARAMETER(General, autoStartCamera, bool, false, "Automatically start the camera when the application is opened.");
00233         PARAMETER(General, autoUpdateObjects, bool, true, "Automatically update objects on every parameter changes, otherwise you would need to press \"Update objects\" on the objects panel.");
00234         PARAMETER(General, nextObjID, uint, 1, "Next object ID to use.");
00235         PARAMETER(General, imageFormats, QString, "*.png *.jpg *.bmp *.tiff *.ppm *.pgm", "Image formats supported.");
00236         PARAMETER(General, videoFormats, QString, "*.avi *.m4v *.mp4", "Video formats supported.");
00237         PARAMETER(General, mirrorView, bool, true, "Flip the camera image horizontally (like all webcam applications).");
00238         PARAMETER(General, invertedSearch, bool, true, "Instead of matching descriptors from the objects to those in a vocabulary created with descriptors extracted from the scene, we create a vocabulary from all the objects' descriptors and we match scene's descriptors to this vocabulary. It is the inverted search mode.");
00239         PARAMETER(General, controlsShown, bool, false, "Show play/image seek controls (useful with video file and directory of images modes).");
00240         PARAMETER(General, threads, int, 1, "Number of threads used for objects matching and homography computation. 0 means as many threads as objects. On InvertedSearch mode, multi-threading has only effect on homography computation.");
00241         PARAMETER(General, multiDetection, bool, false, "Multiple detection of the same object.");
00242         PARAMETER(General, multiDetectionRadius, int, 30, "Ignore detection of the same object in X pixels radius of the previous detections.");
00243         PARAMETER(General, port, int, 0, "Port on objects detected are published. If port=0, a port is chosen automatically.")
00244         PARAMETER(General, autoScroll, bool, true, "Auto scroll to detected object in Objects panel.");
00245         PARAMETER(General, vocabularyIncremental, bool, false, "The vocabulary is created incrementally. When new objects are added, their descriptors are compared to those already in vocabulary to find if the visual word already exist or not. \"NearestNeighbor/nndrRatio\" is used to compare descriptors.");
00246         PARAMETER(General, vocabularyUpdateMinWords, int, 2000, "When the vocabulary is incremental (see \"General/vocabularyIncremental\"), after X words added to vocabulary, the internal index is updated with new words. This parameter lets avoiding to reconstruct the whole nearest neighbor index after each time descriptors of an object are added to vocabulary. 0 means no incremental update.");
00247         PARAMETER(General, sendNoObjDetectedEvents, bool, true, "When there are no objects detected, send an empty object detection event.");
00248         PARAMETER(General, autoPauseOnDetection, bool, false, "Auto pause the camera when an object is detected.");
00249 
00250         PARAMETER(Homography, homographyComputed, bool, true, "Compute homography? On ROS, this is required to publish objects detected.");
00251         PARAMETER(Homography, method, QString, "1:LMEDS;RANSAC", "Type of the robust estimation algorithm: least-median algorithm or RANSAC algorithm.");
00252         PARAMETER(Homography, ransacReprojThr, double, 5.0, "Maximum allowed reprojection error to treat a point pair as an inlier (used in the RANSAC method only). It usually makes sense to set this parameter somewhere in the range of 1 to 10.");
00253         PARAMETER(Homography, minimumInliers, int, 10, "Minimum inliers to accept the homography. Value must be >= 4.");
00254         PARAMETER(Homography, ignoreWhenAllInliers, bool, false, "Ignore homography when all features are inliers (sometimes when the homography doesn't converge, it returns the best homography with all features as inliers).");
00255         PARAMETER(Homography, rectBorderWidth, int, 4, "Homography rectangle border width.");
00256         PARAMETER(Homography, allCornersVisible, bool, false, "All corners of the detected object must be visible in the scene.");
00257         PARAMETER(Homography, minAngle, int, 0, "(Degrees) Homography minimum angle. Set 0 to disable. When the angle is very small, this is a good indication that the homography is wrong. A good value is over 60 degrees.");
00258 
00259 public:
00260         virtual ~Settings(){}
00261 
00262         static QString workingDirectory();
00263         static QString iniDefaultPath();
00264         static QString iniDefaultFileName() {return "config.ini";}
00265         static QString iniPath();
00266 
00267         static void init(const QString & fileName);
00268 
00269         static void loadSettings(const QString & fileName = QString());
00270         static void loadWindowSettings(QByteArray & windowGeometry, QByteArray & windowState, const QString & fileName = QString());
00271         static void saveSettings(const QString & fileName = QString());
00272         static void saveWindowSettings(const QByteArray & windowGeometry, const QByteArray & windowState, const QString & fileName = QString());
00273 
00274         static const ParametersMap & getDefaultParameters() {return defaultParameters_;}
00275         static const ParametersMap & getParameters() {return parameters_;}
00276         static const ParametersType & getParametersType() {return parametersType_;}
00277         static const DescriptionsMap & getDescriptions() {return descriptions_;}
00278         static void setParameter(const QString & key, const QVariant & value) {if(parameters_.contains(key))parameters_[key] = value;}
00279         static void resetParameter(const QString & key) {if(defaultParameters_.contains(key)) parameters_.insert(key, defaultParameters_.value(key));}
00280         static QVariant getParameter(const QString & key) {return parameters_.value(key, QVariant());}
00281 
00282         static KeypointDetector * createKeypointDetector();
00283         static DescriptorExtractor * createDescriptorExtractor();
00284 
00285         static QString currentDescriptorType();
00286         static QString currentDetectorType();
00287         static QString currentNearestNeighborType();
00288 
00289         static bool isBruteForceNearestNeighbor();
00290         static cv::flann::IndexParams * createFlannIndexParams();
00291         static cvflann::flann_distance_t getFlannDistanceType();
00292         static cv::flann::SearchParams getFlannSearchParams();
00293 
00294         static int getHomographyMethod();
00295 
00296 private:
00297         Settings(){}
00298 
00299 private:
00300         static ParametersMap defaultParameters_;
00301         static ParametersMap parameters_;
00302         static ParametersType parametersType_;
00303         static DescriptionsMap descriptions_;
00304         static Settings dummyInit_;
00305         static QString iniPath_;
00306 };
00307 
00308 class KeypointDetector
00309 {
00310 public:
00311         KeypointDetector(cv::FeatureDetector * featureDetector);
00312         KeypointDetector(GPUFeature2D * gpuFeature2D);
00313 
00314         void detect(const cv::Mat & image,
00315                         std::vector<cv::KeyPoint> & keypoints,
00316                         const cv::Mat & mask = cv::Mat());
00317 
00318 private:
00319         cv::FeatureDetector * featureDetector_;
00320         GPUFeature2D * gpuFeature2D_;
00321 };
00322 
00323 class DescriptorExtractor
00324 {
00325 public:
00326         DescriptorExtractor(cv::DescriptorExtractor * descriptorExtractor);
00327         DescriptorExtractor(GPUFeature2D * gpuFeature2D);
00328 
00329         void compute(const cv::Mat & image,
00330                         std::vector<cv::KeyPoint> & keypoints,
00331                         cv::Mat & descriptors);
00332 
00333 private:
00334         cv::DescriptorExtractor * descriptorExtractor_;
00335         GPUFeature2D * gpuFeature2D_;
00336 };
00337 
00338 } // namespace find_object
00339 
00340 #endif /* SETTINGS_H_ */


find_object_2d
Author(s): Mathieu Labbe
autogenerated on Thu Aug 27 2015 13:00:33