opencv 2.2.0
/usr/src/RPM/BUILD/libopencv2.2-2.2.0/modules/features2d/include/opencv2/features2d/features2d.hpp
Go to the documentation of this file.
00001 /*M///////////////////////////////////////////////////////////////////////////////////////
00002 //
00003 //  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
00004 //
00005 //  By downloading, copying, installing or using the software you agree to this license.
00006 //  If you do not agree to this license, do not download, install,
00007 //  copy or use the software.
00008 //
00009 //
00010 //                           License Agreement
00011 //                For Open Source Computer Vision Library
00012 //
00013 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
00014 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
00015 // Third party copyrights are property of their respective owners.
00016 //
00017 // Redistribution and use in source and binary forms, with or without modification,
00018 // are permitted provided that the following conditions are met:
00019 //
00020 //   * Redistribution's of source code must retain the above copyright notice,
00021 //     this list of conditions and the following disclaimer.
00022 //
00023 //   * Redistribution's in binary form must reproduce the above copyright notice,
00024 //     this list of conditions and the following disclaimer in the documentation
00025 //     and/or other materials provided with the distribution.
00026 //
00027 //   * The name of the copyright holders may not be used to endorse or promote products
00028 //     derived from this software without specific prior written permission.
00029 //
00030 // This software is provided by the copyright holders and contributors "as is" and
00031 // any express or implied warranties, including, but not limited to, the implied
00032 // warranties of merchantability and fitness for a particular purpose are disclaimed.
00033 // In no event shall the Intel Corporation or contributors be liable for any direct,
00034 // indirect, incidental, special, exemplary, or consequential damages
00035 // (including, but not limited to, procurement of substitute goods or services;
00036 // loss of use, data, or profits; or business interruption) however caused
00037 // and on any theory of liability, whether in contract, strict liability,
00038 // or tort (including negligence or otherwise) arising in any way out of
00039 // the use of this software, even if advised of the possibility of such damage.
00040 //
00041 //M*/
00042 
00043 #ifndef __OPENCV_FEATURES_2D_HPP__
00044 #define __OPENCV_FEATURES_2D_HPP__
00045 
00046 #include "opencv2/core/core.hpp"
00047 #include "opencv2/flann/flann.hpp"
00048 
00049 #ifdef __cplusplus
00050 #include <limits>
00051 
00052 extern "C" {
00053 #endif
00054 
00055 typedef struct CvSURFPoint
00056 {
00057     CvPoint2D32f pt;
00058 
00059     int          laplacian;
00060     int          size;
00061     float        dir;
00062     float        hessian;
00063 
00064 } CvSURFPoint;
00065 
00066 CV_INLINE CvSURFPoint cvSURFPoint( CvPoint2D32f pt, int laplacian,
00067                                    int size, float dir CV_DEFAULT(0),
00068                                    float hessian CV_DEFAULT(0))
00069 {
00070     CvSURFPoint kp;
00071 
00072     kp.pt        = pt;
00073     kp.laplacian = laplacian;
00074     kp.size      = size;
00075     kp.dir       = dir;
00076     kp.hessian   = hessian;
00077 
00078     return kp;
00079 }
00080 
00081 typedef struct CvSURFParams
00082 {
00083     int    extended;
00084     double hessianThreshold;
00085 
00086     int    nOctaves;
00087     int    nOctaveLayers;
00088 
00089 } CvSURFParams;
00090 
00091 CVAPI(CvSURFParams) cvSURFParams( double hessianThreshold, int extended CV_DEFAULT(0) );
00092 
00093 // If useProvidedKeyPts!=0, keypoints are not detected, but descriptors are computed
00094 //  at the locations provided in keypoints (a CvSeq of CvSURFPoint).
00095 CVAPI(void) cvExtractSURF( const CvArr* img, const CvArr* mask,
00096                            CvSeq** keypoints, CvSeq** descriptors,
00097                            CvMemStorage* storage, CvSURFParams params, int useProvidedKeyPts CV_DEFAULT(0)  );
00098 
00102 typedef struct CvMSERParams
00103 {
00105     int delta;
00107     int maxArea;
00109     int minArea;
00111     float maxVariation;
00113     float minDiversity;
00114     
00116     
00118     int maxEvolution;
00120     double areaThreshold;
00122     double minMargin;
00124     int edgeBlurSize;
00125 } CvMSERParams;
00126 
00127 CVAPI(CvMSERParams) cvMSERParams( int delta CV_DEFAULT(5), int min_area CV_DEFAULT(60),
00128                            int max_area CV_DEFAULT(14400), float max_variation CV_DEFAULT(.25f),
00129                            float min_diversity CV_DEFAULT(.2f), int max_evolution CV_DEFAULT(200),
00130                            double area_threshold CV_DEFAULT(1.01),
00131                            double min_margin CV_DEFAULT(.003),
00132                            int edge_blur_size CV_DEFAULT(5) );
00133 
00134 // Extracts the contours of Maximally Stable Extremal Regions
00135 CVAPI(void) cvExtractMSER( CvArr* _img, CvArr* _mask, CvSeq** contours, CvMemStorage* storage, CvMSERParams params );
00136 
00137 
00138 typedef struct CvStarKeypoint
00139 {
00140     CvPoint pt;
00141     int size;
00142     float response;
00143 } CvStarKeypoint;
00144 
00145 CV_INLINE CvStarKeypoint cvStarKeypoint(CvPoint pt, int size, float response)
00146 {
00147     CvStarKeypoint kpt;
00148     kpt.pt = pt;
00149     kpt.size = size;
00150     kpt.response = response;
00151     return kpt;
00152 }
00153 
00154 typedef struct CvStarDetectorParams
00155 {
00156     int maxSize;
00157     int responseThreshold;
00158     int lineThresholdProjected;
00159     int lineThresholdBinarized;
00160     int suppressNonmaxSize;
00161 } CvStarDetectorParams;
00162 
00163 CV_INLINE CvStarDetectorParams cvStarDetectorParams(
00164     int maxSize CV_DEFAULT(45),
00165     int responseThreshold CV_DEFAULT(30),
00166     int lineThresholdProjected CV_DEFAULT(10),
00167     int lineThresholdBinarized CV_DEFAULT(8),
00168     int suppressNonmaxSize CV_DEFAULT(5))
00169 {
00170     CvStarDetectorParams params;
00171     params.maxSize = maxSize;
00172     params.responseThreshold = responseThreshold;
00173     params.lineThresholdProjected = lineThresholdProjected;
00174     params.lineThresholdBinarized = lineThresholdBinarized;
00175     params.suppressNonmaxSize = suppressNonmaxSize;
00176 
00177     return params;
00178 }
00179 
00180 CVAPI(CvSeq*) cvGetStarKeypoints( const CvArr* img, CvMemStorage* storage,
00181         CvStarDetectorParams params CV_DEFAULT(cvStarDetectorParams()));
00182 
00183 #ifdef __cplusplus
00184 }
00185 
00186 namespace cv
00187 {
00188     struct CV_EXPORTS DefaultRngAuto
00189     {
00190         const uint64 old_state;
00191 
00192         DefaultRngAuto() : old_state(theRNG().state) { theRNG().state = (uint64)-1; }
00193         ~DefaultRngAuto() { theRNG().state = old_state; }
00194 
00195         DefaultRngAuto& operator=(const DefaultRngAuto&);
00196     };
00197 
00198 
00199 // CvAffinePose: defines a parameterized affine transformation of an image patch.
00200 // An image patch is rotated on angle phi (in degrees), then scaled lambda1 times
00201 // along horizontal and lambda2 times along vertical direction, and then rotated again
00202 // on angle (theta - phi).
00203 class CV_EXPORTS CvAffinePose
00204 {
00205 public:
00206     float phi;
00207     float theta;
00208     float lambda1;
00209     float lambda2;
00210 };
00211 
00224 class CV_EXPORTS_W_SIMPLE KeyPoint
00225 {
00226 public:
00228     CV_WRAP KeyPoint() : pt(0,0), size(0), angle(-1), response(0), octave(0), class_id(-1) {}
00230     KeyPoint(Point2f _pt, float _size, float _angle=-1,
00231             float _response=0, int _octave=0, int _class_id=-1)
00232             : pt(_pt), size(_size), angle(_angle),
00233             response(_response), octave(_octave), class_id(_class_id) {}
00235     CV_WRAP KeyPoint(float x, float y, float _size, float _angle=-1,
00236             float _response=0, int _octave=0, int _class_id=-1)
00237             : pt(x, y), size(_size), angle(_angle),
00238             response(_response), octave(_octave), class_id(_class_id) {}
00240     static void convert(const std::vector<KeyPoint>& keypoints,
00241                         CV_OUT std::vector<Point2f>& points2f,
00242                         const std::vector<int>& keypointIndexes=std::vector<int>());
00244     static void convert(const std::vector<Point2f>& points2f,
00245                         CV_OUT std::vector<KeyPoint>& keypoints,
00246                         float size=1, float response=1, int octave=0, int class_id=-1);
00247 
00251     static float overlap(const KeyPoint& kp1, const KeyPoint& kp2);
00252 
00253     CV_PROP_RW Point2f pt; 
00254     CV_PROP_RW float size; 
00255     CV_PROP_RW float angle; 
00256     CV_PROP_RW float response; 
00257     CV_PROP_RW int octave; 
00258     CV_PROP_RW int class_id; 
00259 };
00260 
00262 CV_EXPORTS void write(FileStorage& fs, const string& name, const vector<KeyPoint>& keypoints);
00264 CV_EXPORTS void read(const FileNode& node, CV_OUT vector<KeyPoint>& keypoints);    
00265 
00271 class CV_EXPORTS SIFT
00272 {
00273 public:
00274     struct CV_EXPORTS CommonParams
00275     {
00276         static const int DEFAULT_NOCTAVES = 4;
00277         static const int DEFAULT_NOCTAVE_LAYERS = 3;
00278         static const int DEFAULT_FIRST_OCTAVE = -1;
00279         enum { FIRST_ANGLE = 0, AVERAGE_ANGLE = 1 };
00280 
00281         CommonParams();
00282         CommonParams( int _nOctaves, int _nOctaveLayers, int _firstOctave, int _angleMode );
00283         int nOctaves, nOctaveLayers, firstOctave;
00284         int angleMode;
00285     };
00286 
00287     struct CV_EXPORTS DetectorParams
00288     {
00289         static double GET_DEFAULT_THRESHOLD() { return 0.04 / SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS / 2.0; }
00290         static double GET_DEFAULT_EDGE_THRESHOLD() { return 10.0; }
00291 
00292         DetectorParams();
00293         DetectorParams( double _threshold, double _edgeThreshold );
00294         double threshold, edgeThreshold;
00295     };
00296 
00297     struct CV_EXPORTS DescriptorParams
00298     {
00299         static double GET_DEFAULT_MAGNIFICATION() { return 3.0; }
00300         static const bool DEFAULT_IS_NORMALIZE = true;
00301         static const int DESCRIPTOR_SIZE = 128;
00302 
00303         DescriptorParams();
00304         DescriptorParams( double _magnification, bool _isNormalize, bool _recalculateAngles );
00305         double magnification;
00306         bool isNormalize;
00307         bool recalculateAngles;
00308     };
00309 
00310     SIFT();
00312     SIFT( double _threshold, double _edgeThreshold,
00313           int _nOctaves=CommonParams::DEFAULT_NOCTAVES,
00314           int _nOctaveLayers=CommonParams::DEFAULT_NOCTAVE_LAYERS,
00315           int _firstOctave=CommonParams::DEFAULT_FIRST_OCTAVE,
00316           int _angleMode=CommonParams::FIRST_ANGLE );
00318     SIFT( double _magnification, bool _isNormalize=true,
00319           bool _recalculateAngles = true,
00320           int _nOctaves=CommonParams::DEFAULT_NOCTAVES,
00321           int _nOctaveLayers=CommonParams::DEFAULT_NOCTAVE_LAYERS,
00322           int _firstOctave=CommonParams::DEFAULT_FIRST_OCTAVE,
00323           int _angleMode=CommonParams::FIRST_ANGLE );
00324     SIFT( const CommonParams& _commParams,
00325           const DetectorParams& _detectorParams = DetectorParams(),
00326           const DescriptorParams& _descriptorParams = DescriptorParams() );
00327 
00329     int descriptorSize() const { return DescriptorParams::DESCRIPTOR_SIZE; }
00331     void operator()(const Mat& img, const Mat& mask,
00332                     vector<KeyPoint>& keypoints) const;
00335     void operator()(const Mat& img, const Mat& mask,
00336                     vector<KeyPoint>& keypoints,
00337                     Mat& descriptors,
00338                     bool useProvidedKeypoints=false) const;
00339 
00340     CommonParams getCommonParams () const { return commParams; }
00341     DetectorParams getDetectorParams () const { return detectorParams; }
00342     DescriptorParams getDescriptorParams () const { return descriptorParams; }
00343 protected:
00344     CommonParams commParams;
00345     DetectorParams detectorParams;
00346     DescriptorParams descriptorParams;
00347 };
00348 
00349     
00355 class CV_EXPORTS_W SURF : public CvSURFParams
00356 {
00357 public:
00359     CV_WRAP SURF();
00361     CV_WRAP SURF(double _hessianThreshold, int _nOctaves=4,
00362          int _nOctaveLayers=2, bool _extended=false);
00363 
00365     CV_WRAP int descriptorSize() const;
00367     CV_WRAP_AS(detect) void operator()(const Mat& img, const Mat& mask,
00368                     CV_OUT vector<KeyPoint>& keypoints) const;
00370     CV_WRAP_AS(detect) void operator()(const Mat& img, const Mat& mask,
00371                     CV_OUT vector<KeyPoint>& keypoints,
00372                     CV_OUT vector<float>& descriptors,
00373                     bool useProvidedKeypoints=false) const;
00374 };
00375 
00385 class CV_EXPORTS_W MSER : public CvMSERParams
00386 {
00387 public:
00389     CV_WRAP MSER();
00391     CV_WRAP MSER( int _delta, int _min_area, int _max_area,
00392           double _max_variation, double _min_diversity,
00393           int _max_evolution, double _area_threshold,
00394           double _min_margin, int _edge_blur_size );
00396     CV_WRAP_AS(detect) void operator()( const Mat& image,
00397         CV_OUT vector<vector<Point> >& msers, const Mat& mask ) const;
00398 };
00399 
00405 class CV_EXPORTS_W StarDetector : public CvStarDetectorParams
00406 {
00407 public:
00409     CV_WRAP StarDetector();
00411     CV_WRAP StarDetector(int _maxSize, int _responseThreshold,
00412                  int _lineThresholdProjected,
00413                  int _lineThresholdBinarized,
00414                  int _suppressNonmaxSize);
00416     CV_WRAP_AS(detect) void operator()(const Mat& image,
00417                 CV_OUT vector<KeyPoint>& keypoints) const;
00418 };
00419 
00421 CV_EXPORTS void FAST( const Mat& image, CV_OUT vector<KeyPoint>& keypoints,
00422                       int threshold, bool nonmaxSupression=true );
00423 
00427 class CV_EXPORTS PatchGenerator
00428 {
00429 public:
00430     PatchGenerator();
00431     PatchGenerator(double _backgroundMin, double _backgroundMax,
00432                    double _noiseRange, bool _randomBlur=true,
00433                    double _lambdaMin=0.6, double _lambdaMax=1.5,
00434                    double _thetaMin=-CV_PI, double _thetaMax=CV_PI,
00435                    double _phiMin=-CV_PI, double _phiMax=CV_PI );
00436     void operator()(const Mat& image, Point2f pt, Mat& patch, Size patchSize, RNG& rng) const;
00437     void operator()(const Mat& image, const Mat& transform, Mat& patch,
00438                     Size patchSize, RNG& rng) const;
00439     void warpWholeImage(const Mat& image, Mat& matT, Mat& buf,
00440                         CV_OUT Mat& warped, int border, RNG& rng) const;
00441     void generateRandomTransform(Point2f srcCenter, Point2f dstCenter,
00442                                  CV_OUT Mat& transform, RNG& rng,
00443                                  bool inverse=false) const;
00444     void setAffineParam(double lambda, double theta, double phi);
00445     
00446     double backgroundMin, backgroundMax;
00447     double noiseRange;
00448     bool randomBlur;
00449     double lambdaMin, lambdaMax;
00450     double thetaMin, thetaMax;
00451     double phiMin, phiMax;
00452 };
00453 
00454 
00455 class CV_EXPORTS LDetector
00456 {
00457 public:
00458     LDetector();
00459     LDetector(int _radius, int _threshold, int _nOctaves,
00460               int _nViews, double _baseFeatureSize, double _clusteringDistance);
00461     void operator()(const Mat& image,
00462                     CV_OUT vector<KeyPoint>& keypoints,
00463                     int maxCount=0, bool scaleCoords=true) const;
00464     void operator()(const vector<Mat>& pyr,
00465                     CV_OUT vector<KeyPoint>& keypoints,
00466                     int maxCount=0, bool scaleCoords=true) const;
00467     void getMostStable2D(const Mat& image, CV_OUT vector<KeyPoint>& keypoints,
00468                          int maxCount, const PatchGenerator& patchGenerator) const;
00469     void setVerbose(bool verbose);
00470     
00471     void read(const FileNode& node);
00472     void write(FileStorage& fs, const String& name=String()) const;
00473     
00474     int radius;
00475     int threshold;
00476     int nOctaves;
00477     int nViews;
00478     bool verbose;
00479     
00480     double baseFeatureSize;
00481     double clusteringDistance;
00482 };
00483 
00484 typedef LDetector YAPE;
00485 
00486 class CV_EXPORTS FernClassifier
00487 {
00488 public:
00489     FernClassifier();
00490     FernClassifier(const FileNode& node);
00491     FernClassifier(const vector<vector<Point2f> >& points,
00492                    const vector<Mat>& refimgs,
00493                    const vector<vector<int> >& labels=vector<vector<int> >(),
00494                    int _nclasses=0, int _patchSize=PATCH_SIZE,
00495                    int _signatureSize=DEFAULT_SIGNATURE_SIZE,
00496                    int _nstructs=DEFAULT_STRUCTS,
00497                    int _structSize=DEFAULT_STRUCT_SIZE,
00498                    int _nviews=DEFAULT_VIEWS,
00499                    int _compressionMethod=COMPRESSION_NONE,
00500                    const PatchGenerator& patchGenerator=PatchGenerator());
00501     virtual ~FernClassifier();
00502     virtual void read(const FileNode& n);
00503     virtual void write(FileStorage& fs, const String& name=String()) const;
00504     virtual void trainFromSingleView(const Mat& image,
00505                                      const vector<KeyPoint>& keypoints,
00506                                      int _patchSize=PATCH_SIZE,
00507                                      int _signatureSize=DEFAULT_SIGNATURE_SIZE,
00508                                      int _nstructs=DEFAULT_STRUCTS,
00509                                      int _structSize=DEFAULT_STRUCT_SIZE,
00510                                      int _nviews=DEFAULT_VIEWS,
00511                                      int _compressionMethod=COMPRESSION_NONE,
00512                                      const PatchGenerator& patchGenerator=PatchGenerator());
00513     virtual void train(const vector<vector<Point2f> >& points,
00514                        const vector<Mat>& refimgs,
00515                        const vector<vector<int> >& labels=vector<vector<int> >(),
00516                        int _nclasses=0, int _patchSize=PATCH_SIZE,
00517                        int _signatureSize=DEFAULT_SIGNATURE_SIZE,
00518                        int _nstructs=DEFAULT_STRUCTS,
00519                        int _structSize=DEFAULT_STRUCT_SIZE,
00520                        int _nviews=DEFAULT_VIEWS,
00521                        int _compressionMethod=COMPRESSION_NONE,
00522                        const PatchGenerator& patchGenerator=PatchGenerator());
00523     virtual int operator()(const Mat& img, Point2f kpt, vector<float>& signature) const;
00524     virtual int operator()(const Mat& patch, vector<float>& signature) const;
00525     virtual void clear();
00526     void setVerbose(bool verbose);
00527     
00528     int getClassCount() const;
00529     int getStructCount() const;
00530     int getStructSize() const;
00531     int getSignatureSize() const;
00532     int getCompressionMethod() const;
00533     Size getPatchSize() const;
00534     
00535     struct Feature
00536     {
00537         uchar x1, y1, x2, y2;
00538         Feature() : x1(0), y1(0), x2(0), y2(0) {}
00539         Feature(int _x1, int _y1, int _x2, int _y2)
00540         : x1((uchar)_x1), y1((uchar)_y1), x2((uchar)_x2), y2((uchar)_y2)
00541         {}
00542         template<typename _Tp> bool operator ()(const Mat_<_Tp>& patch) const
00543         { return patch(y1,x1) > patch(y2, x2); }
00544     };
00545     
00546     enum
00547     {
00548         PATCH_SIZE = 31,
00549         DEFAULT_STRUCTS = 50,
00550         DEFAULT_STRUCT_SIZE = 9,
00551         DEFAULT_VIEWS = 5000,
00552         DEFAULT_SIGNATURE_SIZE = 176,
00553         COMPRESSION_NONE = 0,
00554         COMPRESSION_RANDOM_PROJ = 1,
00555         COMPRESSION_PCA = 2,
00556         DEFAULT_COMPRESSION_METHOD = COMPRESSION_NONE
00557     };
00558     
00559 protected:
00560     virtual void prepare(int _nclasses, int _patchSize, int _signatureSize,
00561                          int _nstructs, int _structSize,
00562                          int _nviews, int _compressionMethod);
00563     virtual void finalize(RNG& rng);
00564     virtual int getLeaf(int fidx, const Mat& patch) const;
00565     
00566     bool verbose;
00567     int nstructs;
00568     int structSize;
00569     int nclasses;
00570     int signatureSize;
00571     int compressionMethod;
00572     int leavesPerStruct;
00573     Size patchSize;
00574     vector<Feature> features;
00575     vector<int> classCounters;
00576     vector<float> posteriors;
00577 };
00578 
00579 
00580 /****************************************************************************************\
00581 *                                 Calonder Classifier                                    *
00582 \****************************************************************************************/
00583 
00584 struct RTreeNode;
00585 
00586 struct CV_EXPORTS BaseKeypoint
00587 {
00588   int x;
00589   int y;
00590   IplImage* image;
00591 
00592   BaseKeypoint()
00593     : x(0), y(0), image(NULL)
00594   {}
00595 
00596   BaseKeypoint(int x, int y, IplImage* image)
00597     : x(x), y(y), image(image)
00598   {}
00599 };
00600 
00601 class CV_EXPORTS RandomizedTree
00602 {
00603 public:
00604   friend class RTreeClassifier;
00605 
00606   static const uchar PATCH_SIZE = 32;
00607   static const int DEFAULT_DEPTH = 9;
00608   static const int DEFAULT_VIEWS = 5000;
00609   static const size_t DEFAULT_REDUCED_NUM_DIM = 176;
00610   static float GET_LOWER_QUANT_PERC() { return .03f; }
00611   static float GET_UPPER_QUANT_PERC() { return .92f; }
00612 
00613   RandomizedTree();
00614   ~RandomizedTree();
00615 
00616   void train(std::vector<BaseKeypoint> const& base_set, RNG &rng,
00617              int depth, int views, size_t reduced_num_dim, int num_quant_bits);
00618   void train(std::vector<BaseKeypoint> const& base_set, RNG &rng,
00619              PatchGenerator &make_patch, int depth, int views, size_t reduced_num_dim,
00620              int num_quant_bits);
00621 
00622   // following two funcs are EXPERIMENTAL (do not use unless you know exactly what you do)
00623   static void quantizeVector(float *vec, int dim, int N, float bnds[2], int clamp_mode=0);
00624   static void quantizeVector(float *src, int dim, int N, float bnds[2], uchar *dst);
00625 
00626   // patch_data must be a 32x32 array (no row padding)
00627   float* getPosterior(uchar* patch_data);
00628   const float* getPosterior(uchar* patch_data) const;
00629   uchar* getPosterior2(uchar* patch_data);
00630   const uchar* getPosterior2(uchar* patch_data) const;
00631 
00632   void read(const char* file_name, int num_quant_bits);
00633   void read(std::istream &is, int num_quant_bits);
00634   void write(const char* file_name) const;
00635   void write(std::ostream &os) const;
00636 
00637   int classes() { return classes_; }
00638   int depth() { return depth_; }
00639 
00640   //void setKeepFloatPosteriors(bool b) { keep_float_posteriors_ = b; }
00641   void discardFloatPosteriors() { freePosteriors(1); }
00642 
00643   inline void applyQuantization(int num_quant_bits) { makePosteriors2(num_quant_bits); }
00644 
00645   // debug
00646   void savePosteriors(std::string url, bool append=false);
00647   void savePosteriors2(std::string url, bool append=false);
00648 
00649 private:
00650   int classes_;
00651   int depth_;
00652   int num_leaves_;
00653   std::vector<RTreeNode> nodes_;
00654   float **posteriors_;        // 16-bytes aligned posteriors
00655   uchar **posteriors2_;     // 16-bytes aligned posteriors
00656   std::vector<int> leaf_counts_;
00657 
00658   void createNodes(int num_nodes, RNG &rng);
00659   void allocPosteriorsAligned(int num_leaves, int num_classes);
00660   void freePosteriors(int which);    // which: 1=posteriors_, 2=posteriors2_, 3=both
00661   void init(int classes, int depth, RNG &rng);
00662   void addExample(int class_id, uchar* patch_data);
00663   void finalize(size_t reduced_num_dim, int num_quant_bits);
00664   int getIndex(uchar* patch_data) const;
00665   inline float* getPosteriorByIndex(int index);
00666   inline const float* getPosteriorByIndex(int index) const;
00667   inline uchar* getPosteriorByIndex2(int index);
00668   inline const uchar* getPosteriorByIndex2(int index) const;
00669   //void makeRandomMeasMatrix(float *cs_phi, PHI_DISTR_TYPE dt, size_t reduced_num_dim);
00670   void convertPosteriorsToChar();
00671   void makePosteriors2(int num_quant_bits);
00672   void compressLeaves(size_t reduced_num_dim);
00673   void estimateQuantPercForPosteriors(float perc[2]);
00674 };
00675 
00676 
00677 inline uchar* getData(IplImage* image)
00678 {
00679   return reinterpret_cast<uchar*>(image->imageData);
00680 }
00681 
00682 inline float* RandomizedTree::getPosteriorByIndex(int index)
00683 {
00684   return const_cast<float*>(const_cast<const RandomizedTree*>(this)->getPosteriorByIndex(index));
00685 }
00686 
00687 inline const float* RandomizedTree::getPosteriorByIndex(int index) const
00688 {
00689   return posteriors_[index];
00690 }
00691 
00692 inline uchar* RandomizedTree::getPosteriorByIndex2(int index)
00693 {
00694   return const_cast<uchar*>(const_cast<const RandomizedTree*>(this)->getPosteriorByIndex2(index));
00695 }
00696 
00697 inline const uchar* RandomizedTree::getPosteriorByIndex2(int index) const
00698 {
00699   return posteriors2_[index];
00700 }
00701 
00702 struct CV_EXPORTS RTreeNode
00703 {
00704   short offset1, offset2;
00705 
00706   RTreeNode() {}
00707   RTreeNode(uchar x1, uchar y1, uchar x2, uchar y2)
00708     : offset1(y1*RandomizedTree::PATCH_SIZE + x1),
00709       offset2(y2*RandomizedTree::PATCH_SIZE + x2)
00710   {}
00711 
00713   inline bool operator() (uchar* patch_data) const
00714   {
00715     return patch_data[offset1] > patch_data[offset2];
00716   }
00717 };
00718 
00719 class CV_EXPORTS RTreeClassifier
00720 {
00721 public:
00722   static const int DEFAULT_TREES = 48;
00723   static const size_t DEFAULT_NUM_QUANT_BITS = 4;
00724 
00725   RTreeClassifier();
00726   void train(std::vector<BaseKeypoint> const& base_set,
00727              RNG &rng,
00728              int num_trees = RTreeClassifier::DEFAULT_TREES,
00729              int depth = RandomizedTree::DEFAULT_DEPTH,
00730              int views = RandomizedTree::DEFAULT_VIEWS,
00731              size_t reduced_num_dim = RandomizedTree::DEFAULT_REDUCED_NUM_DIM,
00732              int num_quant_bits = DEFAULT_NUM_QUANT_BITS);
00733   void train(std::vector<BaseKeypoint> const& base_set,
00734              RNG &rng,
00735              PatchGenerator &make_patch,
00736              int num_trees = RTreeClassifier::DEFAULT_TREES,
00737              int depth = RandomizedTree::DEFAULT_DEPTH,
00738              int views = RandomizedTree::DEFAULT_VIEWS,
00739              size_t reduced_num_dim = RandomizedTree::DEFAULT_REDUCED_NUM_DIM,
00740              int num_quant_bits = DEFAULT_NUM_QUANT_BITS);
00741 
00742   // sig must point to a memory block of at least classes()*sizeof(float|uchar) bytes
00743   void getSignature(IplImage *patch, uchar *sig) const;
00744   void getSignature(IplImage *patch, float *sig) const;
00745   void getSparseSignature(IplImage *patch, float *sig, float thresh) const;
00746   // TODO: deprecated in favor of getSignature overload, remove
00747   void getFloatSignature(IplImage *patch, float *sig) const { getSignature(patch, sig); }
00748 
00749   static int countNonZeroElements(float *vec, int n, double tol=1e-10);
00750   static inline void safeSignatureAlloc(uchar **sig, int num_sig=1, int sig_len=176);
00751   static inline uchar* safeSignatureAlloc(int num_sig=1, int sig_len=176);
00752 
00753   inline int classes() const { return classes_; }
00754   inline int original_num_classes() const { return original_num_classes_; }
00755 
00756   void setQuantization(int num_quant_bits);
00757   void discardFloatPosteriors();
00758 
00759   void read(const char* file_name);
00760   void read(std::istream &is);
00761   void write(const char* file_name) const;
00762   void write(std::ostream &os) const;
00763 
00764   // experimental and debug
00765   void saveAllFloatPosteriors(std::string file_url);
00766   void saveAllBytePosteriors(std::string file_url);
00767   void setFloatPosteriorsFromTextfile_176(std::string url);
00768   float countZeroElements();
00769 
00770   std::vector<RandomizedTree> trees_;
00771 
00772 private:
00773   int classes_;
00774   int num_quant_bits_;
00775   mutable uchar **posteriors_;
00776   mutable unsigned short *ptemp_;
00777   int original_num_classes_;
00778   bool keep_floats_;
00779 };
00780 
00781 /****************************************************************************************\
00782 *                                     One-Way Descriptor                                 *
00783 \****************************************************************************************/
00784 
00785 class CV_EXPORTS OneWayDescriptor
00786 {
00787 public:
00788     OneWayDescriptor();
00789     ~OneWayDescriptor();
00790 
00791     // allocates memory for given descriptor parameters
00792     void Allocate(int pose_count, CvSize size, int nChannels);
00793 
00794     // GenerateSamples: generates affine transformed patches with averaging them over small transformation variations.
00795     // If external poses and transforms were specified, uses them instead of generating random ones
00796     // - pose_count: the number of poses to be generated
00797     // - frontal: the input patch (can be a roi in a larger image)
00798     // - norm: if nonzero, normalizes the output patch so that the sum of pixel intensities is 1
00799     void GenerateSamples(int pose_count, IplImage* frontal, int norm = 0);
00800 
00801     // GenerateSamplesFast: generates affine transformed patches with averaging them over small transformation variations.
00802     // Uses precalculated transformed pca components.
00803     // - frontal: the input patch (can be a roi in a larger image)
00804     // - pca_hr_avg: pca average vector
00805     // - pca_hr_eigenvectors: pca eigenvectors
00806     // - pca_descriptors: an array of precomputed descriptors of pca components containing their affine transformations
00807     //   pca_descriptors[0] corresponds to the average, pca_descriptors[1]-pca_descriptors[pca_dim] correspond to eigenvectors
00808     void GenerateSamplesFast(IplImage* frontal, CvMat* pca_hr_avg,
00809                              CvMat* pca_hr_eigenvectors, OneWayDescriptor* pca_descriptors);
00810 
00811     // sets the poses and corresponding transforms
00812     void SetTransforms(CvAffinePose* poses, CvMat** transforms);
00813 
00814     // Initialize: builds a descriptor.
00815     // - pose_count: the number of poses to build. If poses were set externally, uses them rather than generating random ones
00816     // - frontal: input patch. Can be a roi in a larger image
00817     // - feature_name: the feature name to be associated with the descriptor
00818     // - norm: if 1, the affine transformed patches are normalized so that their sum is 1
00819     void Initialize(int pose_count, IplImage* frontal, const char* feature_name = 0, int norm = 0);
00820 
00821     // InitializeFast: builds a descriptor using precomputed descriptors of pca components
00822     // - pose_count: the number of poses to build
00823     // - frontal: input patch. Can be a roi in a larger image
00824     // - feature_name: the feature name to be associated with the descriptor
00825     // - pca_hr_avg: average vector for PCA
00826     // - pca_hr_eigenvectors: PCA eigenvectors (one vector per row)
00827     // - pca_descriptors: precomputed descriptors of PCA components, the first descriptor for the average vector
00828     // followed by the descriptors for eigenvectors
00829     void InitializeFast(int pose_count, IplImage* frontal, const char* feature_name,
00830                         CvMat* pca_hr_avg, CvMat* pca_hr_eigenvectors, OneWayDescriptor* pca_descriptors);
00831 
00832     // ProjectPCASample: unwarps an image patch into a vector and projects it into PCA space
00833     // - patch: input image patch
00834     // - avg: PCA average vector
00835     // - eigenvectors: PCA eigenvectors, one per row
00836     // - pca_coeffs: output PCA coefficients
00837     void ProjectPCASample(IplImage* patch, CvMat* avg, CvMat* eigenvectors, CvMat* pca_coeffs) const;
00838 
00839     // InitializePCACoeffs: projects all warped patches into PCA space
00840     // - avg: PCA average vector
00841     // - eigenvectors: PCA eigenvectors, one per row
00842     void InitializePCACoeffs(CvMat* avg, CvMat* eigenvectors);
00843 
00844     // EstimatePose: finds the closest match between an input patch and a set of patches with different poses
00845     // - patch: input image patch
00846     // - pose_idx: the output index of the closest pose
00847     // - distance: the distance to the closest pose (L2 distance)
00848     void EstimatePose(IplImage* patch, int& pose_idx, float& distance) const;
00849 
00850     // EstimatePosePCA: finds the closest match between an input patch and a set of patches with different poses.
00851     // The distance between patches is computed in PCA space
00852     // - patch: input image patch
00853     // - pose_idx: the output index of the closest pose
00854     // - distance: distance to the closest pose (L2 distance in PCA space)
00855     // - avg: PCA average vector. If 0, matching without PCA is used
00856     // - eigenvectors: PCA eigenvectors, one per row
00857     void EstimatePosePCA(CvArr* patch, int& pose_idx, float& distance, CvMat* avg, CvMat* eigenvalues) const;
00858 
00859     // GetPatchSize: returns the size of each image patch after warping (2 times smaller than the input patch)
00860     CvSize GetPatchSize() const
00861     {
00862         return m_patch_size;
00863     }
00864 
00865     // GetInputPatchSize: returns the required size of the patch that the descriptor is built from
00866     // (2 time larger than the patch after warping)
00867     CvSize GetInputPatchSize() const
00868     {
00869         return cvSize(m_patch_size.width*2, m_patch_size.height*2);
00870     }
00871 
00872     // GetPatch: returns a patch corresponding to specified pose index
00873     // - index: pose index
00874     // - return value: the patch corresponding to specified pose index
00875     IplImage* GetPatch(int index);
00876 
00877     // GetPose: returns a pose corresponding to specified pose index
00878     // - index: pose index
00879     // - return value: the pose corresponding to specified pose index
00880     CvAffinePose GetPose(int index) const;
00881 
00882     // Save: saves all patches with different poses to a specified path
00883     void Save(const char* path);
00884 
00885     // ReadByName: reads a descriptor from a file storage
00886     // - fs: file storage
00887     // - parent: parent node
00888     // - name: node name
00889     // - return value: 1 if succeeded, 0 otherwise
00890     int ReadByName(CvFileStorage* fs, CvFileNode* parent, const char* name);
00891 
00892     // ReadByName: reads a descriptor from a file node
00893     // - parent: parent node
00894     // - name: node name
00895     // - return value: 1 if succeeded, 0 otherwise
00896     int ReadByName(const FileNode &parent, const char* name);
00897 
00898     // Write: writes a descriptor into a file storage
00899     // - fs: file storage
00900     // - name: node name
00901     void Write(CvFileStorage* fs, const char* name);
00902 
00903     // GetFeatureName: returns a name corresponding to a feature
00904     const char* GetFeatureName() const;
00905 
00906     // GetCenter: returns the center of the feature
00907     CvPoint GetCenter() const;
00908 
00909     void SetPCADimHigh(int pca_dim_high) {m_pca_dim_high = pca_dim_high;};
00910     void SetPCADimLow(int pca_dim_low) {m_pca_dim_low = pca_dim_low;};
00911 
00912     int GetPCADimLow() const;
00913     int GetPCADimHigh() const;
00914 
00915     CvMat** GetPCACoeffs() const {return m_pca_coeffs;}
00916 
00917 protected:
00918     int m_pose_count; // the number of poses
00919     CvSize m_patch_size; // size of each image
00920     IplImage** m_samples; // an array of length m_pose_count containing the patch in different poses
00921     IplImage* m_input_patch;
00922     IplImage* m_train_patch;
00923     CvMat** m_pca_coeffs; // an array of length m_pose_count containing pca decomposition of the patch in different poses
00924     CvAffinePose* m_affine_poses; // an array of poses
00925     CvMat** m_transforms; // an array of affine transforms corresponding to poses
00926 
00927     string m_feature_name; // the name of the feature associated with the descriptor
00928     CvPoint m_center; // the coordinates of the feature (the center of the input image ROI)
00929 
00930     int m_pca_dim_high; // the number of descriptor pca components to use for generating affine poses
00931     int m_pca_dim_low; // the number of pca components to use for comparison
00932 };
00933 
00934 
00935 // OneWayDescriptorBase: encapsulates functionality for training/loading a set of one way descriptors
00936 // and finding the nearest closest descriptor to an input feature
00937 class CV_EXPORTS OneWayDescriptorBase
00938 {
00939 public:
00940 
00941     // creates an instance of OneWayDescriptor from a set of training files
00942     // - patch_size: size of the input (large) patch
00943     // - pose_count: the number of poses to generate for each descriptor
00944     // - train_path: path to training files
00945     // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
00946     // than patch_size each dimension
00947     // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
00948     // - pca_desc_config: the name of the file that contains descriptors of PCA components
00949     OneWayDescriptorBase(CvSize patch_size, int pose_count, const char* train_path = 0, const char* pca_config = 0,
00950                          const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1,
00951                          int pca_dim_high = 100, int pca_dim_low = 100);
00952 
00953     OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
00954                          float _scale_min = 0.7f, float _scale_max=1.5f, float _scale_step=1.2f, int pyr_levels = 1,
00955                          int pca_dim_high = 100, int pca_dim_low = 100);
00956 
00957 
00958     virtual ~OneWayDescriptorBase();
00959     void clear ();
00960 
00961 
00962     // Allocate: allocates memory for a given number of descriptors
00963     void Allocate(int train_feature_count);
00964 
00965     // AllocatePCADescriptors: allocates memory for pca descriptors
00966     void AllocatePCADescriptors();
00967 
00968     // returns patch size
00969     CvSize GetPatchSize() const {return m_patch_size;};
00970     // returns the number of poses for each descriptor
00971     int GetPoseCount() const {return m_pose_count;};
00972 
00973     // returns the number of pyramid levels
00974     int GetPyrLevels() const {return m_pyr_levels;};
00975 
00976     // returns the number of descriptors
00977     int GetDescriptorCount() const {return m_train_feature_count;};
00978 
00979     // CreateDescriptorsFromImage: creates descriptors for each of the input features
00980     // - src: input image
00981     // - features: input features
00982     // - pyr_levels: the number of pyramid levels
00983     void CreateDescriptorsFromImage(IplImage* src, const std::vector<cv::KeyPoint>& features);
00984 
00985     // CreatePCADescriptors: generates descriptors for PCA components, needed for fast generation of feature descriptors
00986     void CreatePCADescriptors();
00987 
00988     // returns a feature descriptor by feature index
00989     const OneWayDescriptor* GetDescriptor(int desc_idx) const {return &m_descriptors[desc_idx];};
00990 
00991     // FindDescriptor: finds the closest descriptor
00992     // - patch: input image patch
00993     // - desc_idx: output index of the closest descriptor to the input patch
00994     // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
00995     // - distance: distance from the input patch to the closest feature pose
00996     // - _scales: scales of the input patch for each descriptor
00997     // - scale_ranges: input scales variation (float[2])
00998     void FindDescriptor(IplImage* patch, int& desc_idx, int& pose_idx, float& distance, float* _scale = 0, float* scale_ranges = 0) const;
00999 
01000     // - patch: input image patch
01001     // - n: number of the closest indexes
01002     // - desc_idxs: output indexes of the closest descriptor to the input patch (n)
01003     // - pose_idx: output indexes of the closest pose of the closest descriptor to the input patch (n)
01004     // - distances: distance from the input patch to the closest feature pose (n)
01005     // - _scales: scales of the input patch
01006     // - scale_ranges: input scales variation (float[2])
01007     void FindDescriptor(IplImage* patch, int n, std::vector<int>& desc_idxs, std::vector<int>& pose_idxs,
01008                         std::vector<float>& distances, std::vector<float>& _scales, float* scale_ranges = 0) const;
01009 
01010     // FindDescriptor: finds the closest descriptor
01011     // - src: input image
01012     // - pt: center of the feature
01013     // - desc_idx: output index of the closest descriptor to the input patch
01014     // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
01015     // - distance: distance from the input patch to the closest feature pose
01016     void FindDescriptor(IplImage* src, cv::Point2f pt, int& desc_idx, int& pose_idx, float& distance) const;
01017 
01018     // InitializePoses: generates random poses
01019     void InitializePoses();
01020 
01021     // InitializeTransformsFromPoses: generates 2x3 affine matrices from poses (initializes m_transforms)
01022     void InitializeTransformsFromPoses();
01023 
01024     // InitializePoseTransforms: subsequently calls InitializePoses and InitializeTransformsFromPoses
01025     void InitializePoseTransforms();
01026 
01027     // InitializeDescriptor: initializes a descriptor
01028     // - desc_idx: descriptor index
01029     // - train_image: image patch (ROI is supported)
01030     // - feature_label: feature textual label
01031     void InitializeDescriptor(int desc_idx, IplImage* train_image, const char* feature_label);
01032 
01033     void InitializeDescriptor(int desc_idx, IplImage* train_image, const cv::KeyPoint& keypoint, const char* feature_label);
01034 
01035     // InitializeDescriptors: load features from an image and create descriptors for each of them
01036     void InitializeDescriptors(IplImage* train_image, const vector<cv::KeyPoint>& features,
01037                                const char* feature_label = "", int desc_start_idx = 0);
01038 
01039     // Write: writes this object to a file storage
01040     // - fs: output filestorage
01041     void Write (FileStorage &fs) const;
01042     
01043     // Read: reads OneWayDescriptorBase object from a file node
01044     // - fn: input file node    
01045     void Read (const FileNode &fn);
01046 
01047     // LoadPCADescriptors: loads PCA descriptors from a file
01048     // - filename: input filename
01049     int LoadPCADescriptors(const char* filename);
01050 
01051     // LoadPCADescriptors: loads PCA descriptors from a file node
01052     // - fn: input file node
01053     int LoadPCADescriptors(const FileNode &fn);
01054 
01055     // SavePCADescriptors: saves PCA descriptors to a file
01056     // - filename: output filename
01057     void SavePCADescriptors(const char* filename);
01058 
01059     // SavePCADescriptors: saves PCA descriptors to a file storage
01060     // - fs: output file storage
01061     void SavePCADescriptors(CvFileStorage* fs) const;
01062 
01063     // GeneratePCA: calculate and save PCA components and descriptors
01064     // - img_path: path to training PCA images directory
01065     // - images_list: filename with filenames of training PCA images
01066     void GeneratePCA(const char* img_path, const char* images_list, int pose_count=500);
01067 
01068     // SetPCAHigh: sets the high resolution pca matrices (copied to internal structures)
01069     void SetPCAHigh(CvMat* avg, CvMat* eigenvectors);
01070 
01071     // SetPCALow: sets the low resolution pca matrices (copied to internal structures)
01072     void SetPCALow(CvMat* avg, CvMat* eigenvectors);
01073 
01074     int GetLowPCA(CvMat** avg, CvMat** eigenvectors)
01075     {
01076         *avg = m_pca_avg;
01077         *eigenvectors = m_pca_eigenvectors;
01078         return m_pca_dim_low;
01079     };
01080 
01081     int GetPCADimLow() const {return m_pca_dim_low;};
01082     int GetPCADimHigh() const {return m_pca_dim_high;};
01083 
01084     void ConvertDescriptorsArrayToTree(); // Converting pca_descriptors array to KD tree
01085 
01086     // GetPCAFilename: get default PCA filename
01087     static string GetPCAFilename () { return "pca.yml"; }
01088 
01089 protected:
01090     CvSize m_patch_size; // patch size
01091     int m_pose_count; // the number of poses for each descriptor
01092     int m_train_feature_count; // the number of the training features
01093     OneWayDescriptor* m_descriptors; // array of train feature descriptors
01094     CvMat* m_pca_avg; // PCA average Vector for small patches
01095     CvMat* m_pca_eigenvectors; // PCA eigenvectors for small patches
01096     CvMat* m_pca_hr_avg; // PCA average Vector for large patches
01097     CvMat* m_pca_hr_eigenvectors; // PCA eigenvectors for large patches
01098     OneWayDescriptor* m_pca_descriptors; // an array of PCA descriptors
01099 
01100     cv::flann::Index* m_pca_descriptors_tree;
01101     CvMat* m_pca_descriptors_matrix;
01102 
01103     CvAffinePose* m_poses; // array of poses
01104     CvMat** m_transforms; // array of affine transformations corresponding to poses
01105 
01106     int m_pca_dim_high;
01107     int m_pca_dim_low;
01108 
01109     int m_pyr_levels;
01110     float scale_min;
01111     float scale_max;
01112     float scale_step;
01113 
01114     // SavePCAall: saves PCA components and descriptors to a file storage
01115     // - fs: output file storage
01116     void SavePCAall (FileStorage &fs) const;
01117 
01118     // LoadPCAall: loads PCA components and descriptors from a file node
01119     // - fn: input file node
01120     void LoadPCAall (const FileNode &fn);
01121 };
01122 
01123 class CV_EXPORTS OneWayDescriptorObject : public OneWayDescriptorBase
01124 {
01125 public:
01126     // creates an instance of OneWayDescriptorObject from a set of training files
01127     // - patch_size: size of the input (large) patch
01128     // - pose_count: the number of poses to generate for each descriptor
01129     // - train_path: path to training files
01130     // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
01131     // than patch_size each dimension
01132     // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
01133     // - pca_desc_config: the name of the file that contains descriptors of PCA components
01134     OneWayDescriptorObject(CvSize patch_size, int pose_count, const char* train_path, const char* pca_config,
01135                            const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1);
01136 
01137     OneWayDescriptorObject(CvSize patch_size, int pose_count, const string &pca_filename,
01138                            const string &train_path = string (), const string &images_list = string (),
01139                            float _scale_min = 0.7f, float _scale_max=1.5f, float _scale_step=1.2f, int pyr_levels = 1);
01140 
01141 
01142     virtual ~OneWayDescriptorObject();
01143 
01144     // Allocate: allocates memory for a given number of features
01145     // - train_feature_count: the total number of features
01146     // - object_feature_count: the number of features extracted from the object
01147     void Allocate(int train_feature_count, int object_feature_count);
01148 
01149 
01150     void SetLabeledFeatures(const vector<cv::KeyPoint>& features) {m_train_features = features;};
01151     vector<cv::KeyPoint>& GetLabeledFeatures() {return m_train_features;};
01152     const vector<cv::KeyPoint>& GetLabeledFeatures() const {return m_train_features;};
01153     vector<cv::KeyPoint> _GetLabeledFeatures() const;
01154 
01155     // IsDescriptorObject: returns 1 if descriptor with specified index is positive, otherwise 0
01156     int IsDescriptorObject(int desc_idx) const;
01157 
01158     // MatchPointToPart: returns the part number of a feature if it matches one of the object parts, otherwise -1
01159     int MatchPointToPart(CvPoint pt) const;
01160 
01161     // GetDescriptorPart: returns the part number of the feature corresponding to a specified descriptor
01162     // - desc_idx: descriptor index
01163     int GetDescriptorPart(int desc_idx) const;
01164 
01165 
01166     void InitializeObjectDescriptors(IplImage* train_image, const vector<cv::KeyPoint>& features,
01167                                      const char* feature_label, int desc_start_idx = 0, float scale = 1.0f,
01168                                      int is_background = 0);
01169 
01170     // GetObjectFeatureCount: returns the number of object features
01171     int GetObjectFeatureCount() const {return m_object_feature_count;};
01172 
01173 protected:
01174     int* m_part_id; // contains part id for each of object descriptors
01175     vector<cv::KeyPoint> m_train_features; // train features
01176     int m_object_feature_count; // the number of the positive features
01177 
01178 };
01179 
01180 
01181 /****************************************************************************************\
01182 *                                    FeatureDetector                                     *
01183 \****************************************************************************************/
01184 
01185 /*
01186  * Abstract base class for 2D image feature detectors.
01187  */
01188 class CV_EXPORTS FeatureDetector
01189 {
01190 public:
01191     virtual ~FeatureDetector();
01192     
01193     /*
01194      * Detect keypoints in an image.
01195      * image        The image.
01196      * keypoints    The detected keypoints.
01197      * mask         Mask specifying where to look for keypoints (optional). Must be a char
01198      *              matrix with non-zero values in the region of interest.
01199      */
01200     void detect( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01201     
01202     /*
01203      * Detect keypoints in an image set.
01204      * images       Image collection.
01205      * keypoints    Collection of keypoints detected in an input images. keypoints[i] is a set of keypoints detected in an images[i].
01206      * masks        Masks for image set. masks[i] is a mask for images[i].
01207      */
01208     void detect( const vector<Mat>& images, vector<vector<KeyPoint> >& keypoints, const vector<Mat>& masks=vector<Mat>() ) const;
01209 
01210     // Read detector object from a file node.
01211     virtual void read( const FileNode& );
01212     // Read detector object from a file node.
01213     virtual void write( FileStorage& ) const;
01214 
01215     // Create feature detector by detector name.
01216     static Ptr<FeatureDetector> create( const string& detectorType );
01217 
01218 protected:
01219         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const = 0;
01220     /*
01221      * Remove keypoints that are not in the mask.
01222      * Helper function, useful when wrapping a library call for keypoint detection that
01223      * does not support a mask argument.
01224      */
01225     static void removeInvalidPoints( const Mat& mask, vector<KeyPoint>& keypoints );
01226 };
01227 
01228 class CV_EXPORTS FastFeatureDetector : public FeatureDetector
01229 {
01230 public:
01231     FastFeatureDetector( int threshold=10, bool nonmaxSuppression=true );
01232     virtual void read( const FileNode& fn );
01233     virtual void write( FileStorage& fs ) const;
01234 
01235 protected:
01236         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01237 
01238     int threshold;
01239     bool nonmaxSuppression;
01240 };
01241 
01242 
01243 class CV_EXPORTS GoodFeaturesToTrackDetector : public FeatureDetector
01244 {
01245 public:
01246     class CV_EXPORTS Params
01247     {
01248     public:
01249         Params( int maxCorners=1000, double qualityLevel=0.01, double minDistance=1.,
01250                 int blockSize=3, bool useHarrisDetector=false, double k=0.04 );
01251         void read( const FileNode& fn );
01252         void write( FileStorage& fs ) const;
01253 
01254         int maxCorners;
01255         double qualityLevel;
01256         double minDistance;
01257         int blockSize;
01258         bool useHarrisDetector;
01259         double k;
01260     };
01261 
01262     GoodFeaturesToTrackDetector( const GoodFeaturesToTrackDetector::Params& params=GoodFeaturesToTrackDetector::Params() );
01263     GoodFeaturesToTrackDetector( int maxCorners, double qualityLevel, double minDistance,
01264                                  int blockSize=3, bool useHarrisDetector=false, double k=0.04 );
01265     virtual void read( const FileNode& fn );
01266     virtual void write( FileStorage& fs ) const;
01267 
01268 protected:
01269         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01270         
01271         Params params;
01272 };
01273 
01274 class CV_EXPORTS MserFeatureDetector : public FeatureDetector
01275 {
01276 public:
01277     MserFeatureDetector( CvMSERParams params=cvMSERParams() );
01278     MserFeatureDetector( int delta, int minArea, int maxArea, double maxVariation, double minDiversity,
01279                          int maxEvolution, double areaThreshold, double minMargin, int edgeBlurSize );
01280     virtual void read( const FileNode& fn );
01281     virtual void write( FileStorage& fs ) const;
01282 
01283 protected:
01284         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01285 
01286     MSER mser;
01287 };
01288 
01289 class CV_EXPORTS StarFeatureDetector : public FeatureDetector
01290 {
01291 public:
01292     StarFeatureDetector( const CvStarDetectorParams& params=cvStarDetectorParams() );
01293     StarFeatureDetector( int maxSize, int responseThreshold=30, int lineThresholdProjected = 10,
01294                          int lineThresholdBinarized=8, int suppressNonmaxSize=5 );
01295     virtual void read( const FileNode& fn );
01296     virtual void write( FileStorage& fs ) const;
01297 
01298 protected:
01299         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01300 
01301     StarDetector star;
01302 };
01303 
01304 class CV_EXPORTS SiftFeatureDetector : public FeatureDetector
01305 {
01306 public:
01307     SiftFeatureDetector( const SIFT::DetectorParams& detectorParams=SIFT::DetectorParams(),
01308                          const SIFT::CommonParams& commonParams=SIFT::CommonParams() );
01309     SiftFeatureDetector( double threshold, double edgeThreshold,
01310                          int nOctaves=SIFT::CommonParams::DEFAULT_NOCTAVES,
01311                          int nOctaveLayers=SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS,
01312                          int firstOctave=SIFT::CommonParams::DEFAULT_FIRST_OCTAVE,
01313                          int angleMode=SIFT::CommonParams::FIRST_ANGLE );
01314     virtual void read( const FileNode& fn );
01315     virtual void write( FileStorage& fs ) const;
01316 
01317 protected:
01318         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01319 
01320     SIFT sift;
01321 };
01322 
01323 class CV_EXPORTS SurfFeatureDetector : public FeatureDetector
01324 {
01325 public:
01326     SurfFeatureDetector( double hessianThreshold=400., int octaves=3, int octaveLayers=4 );
01327     virtual void read( const FileNode& fn );
01328     virtual void write( FileStorage& fs ) const;
01329 
01330 protected:
01331         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01332 
01333     SURF surf;
01334 };
01335 
01336 class CV_EXPORTS SimpleBlobDetector : public cv::FeatureDetector
01337 {
01338 public:
01339   struct CV_EXPORTS Params
01340   {
01341       Params();
01342       float thresholdStep;
01343       float minThreshold;
01344       float maxThreshold;
01345       float maxCentersDist;
01346       int defaultKeypointSize;
01347       size_t minRepeatability;
01348       bool computeRadius;
01349       bool isGrayscaleCentroid;
01350       int centroidROIMargin;
01351 
01352       bool filterByArea, filterByInertia, filterByCircularity, filterByColor, filterByConvexity;
01353       float minArea;
01354       float maxArea;
01355       float minCircularity;
01356       float minInertiaRatio;
01357       float minConvexity;
01358       uchar blobColor;
01359   };
01360 
01361   SimpleBlobDetector(const SimpleBlobDetector::Params &parameters = SimpleBlobDetector::Params());
01362 protected:
01363   struct CV_EXPORTS Center
01364   {
01365     cv::Point2d location;
01366     double radius;
01367     double confidence;
01368   };
01369 
01370   virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01371   virtual void findBlobs(const cv::Mat &image, const cv::Mat &binaryImage, std::vector<Center> &centers) const;
01372 
01373   cv::Point2d computeGrayscaleCentroid(const cv::Mat &image, const std::vector<cv::Point> &contour) const;
01374 
01375   Params params;
01376 };
01377 
01378 class CV_EXPORTS DenseFeatureDetector : public FeatureDetector
01379 {
01380 public:
01381     class CV_EXPORTS Params
01382     {
01383     public:
01384         Params( float initFeatureScale=1.f, int featureScaleLevels=1, float featureScaleMul=0.1f,
01385                 int initXyStep=6, int initImgBound=0, bool varyXyStepWithScale=true, bool varyImgBoundWithScale=false );
01386         float initFeatureScale;
01387         int featureScaleLevels;
01388         float featureScaleMul;
01389 
01390         int initXyStep;
01391         int initImgBound;
01392 
01393         bool varyXyStepWithScale;
01394         bool varyImgBoundWithScale;
01395     };
01396 
01397     DenseFeatureDetector( const DenseFeatureDetector::Params& params=DenseFeatureDetector::Params() );
01398     
01399         // TODO implement read/write
01400 
01401 protected:
01402         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01403 
01404         Params params;
01405 };
01406 
01407 /*
01408  * Adapts a detector to partition the source image into a grid and detect
01409  * points in each cell.
01410  */
01411 class CV_EXPORTS GridAdaptedFeatureDetector : public FeatureDetector
01412 {
01413 public:
01414     /*
01415      * detector            Detector that will be adapted.
01416      * maxTotalKeypoints   Maximum count of keypoints detected on the image. Only the strongest keypoints
01417      *                      will be keeped.
01418      * gridRows            Grid rows count.
01419      * gridCols            Grid column count.
01420      */
01421     GridAdaptedFeatureDetector( const Ptr<FeatureDetector>& detector, int maxTotalKeypoints=1000,
01422                                 int gridRows=4, int gridCols=4 );
01423     
01424     // TODO implement read/write
01425 
01426 protected:
01427         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01428 
01429     Ptr<FeatureDetector> detector;
01430     int maxTotalKeypoints;
01431     int gridRows;
01432     int gridCols;
01433 };
01434 
01435 /*
01436  * Adapts a detector to detect points over multiple levels of a Gaussian
01437  * pyramid. Useful for detectors that are not inherently scaled.
01438  */
01439 class CV_EXPORTS PyramidAdaptedFeatureDetector : public FeatureDetector
01440 {
01441 public:
01442     PyramidAdaptedFeatureDetector( const Ptr<FeatureDetector>& detector, int levels=2 );
01443     
01444     // TODO implement read/write
01445 
01446 protected:
01447         virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01448 
01449     Ptr<FeatureDetector> detector;
01450     int levels;
01451 };
01452 
01456 class CV_EXPORTS AdjusterAdapter: public FeatureDetector
01457 {
01458 public:   
01461     virtual ~AdjusterAdapter() {}
01466         virtual void tooFew(int min, int n_detected) = 0;
01471         virtual void tooMany(int max, int n_detected) = 0;
01475         virtual bool good() const = 0;
01476 
01477     static Ptr<AdjusterAdapter> create( const string& detectorType );
01478 };
01491 class CV_EXPORTS DynamicAdaptedFeatureDetector: public FeatureDetector
01492 {
01493 public:
01494 
01501     DynamicAdaptedFeatureDetector( const Ptr<AdjusterAdapter>& adjaster, int min_features=400, int max_features=500, int max_iters=5 );
01502 
01503 protected:
01504     virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01505 
01506 private:
01507         int escape_iters_;
01508         int min_features_, max_features_;
01509         Ptr<AdjusterAdapter> adjuster_;
01510 };
01511 
01515 class CV_EXPORTS FastAdjuster: public AdjusterAdapter
01516 {
01517 public:
01521         FastAdjuster(int init_thresh = 20, bool nonmax = true);
01522         virtual void tooFew(int min, int n_detected);
01523         virtual void tooMany(int max, int n_detected);
01524         virtual bool good() const;
01525 
01526 protected:
01527     virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01528 
01529         int thresh_;
01530         bool nonmax_;
01531 };
01532 
01533 
01537 class CV_EXPORTS StarAdjuster: public AdjusterAdapter
01538 {
01539 public:
01540         StarAdjuster(double initial_thresh = 30.0);
01541         virtual void tooFew(int min, int n_detected);
01542         virtual void tooMany(int max, int n_detected);
01543         virtual bool good() const;
01544 
01545 protected:
01546     virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01547 
01548         double thresh_;
01549         CvStarDetectorParams params_; //todo use these instead of thresh_
01550 };
01551 
01552 class CV_EXPORTS SurfAdjuster: public AdjusterAdapter
01553 {
01554 public:
01555     SurfAdjuster();
01556         virtual void tooFew(int min, int n_detected);
01557         virtual void tooMany(int max, int n_detected);
01558         virtual bool good() const;
01559 
01560 protected:
01561     virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
01562 
01563         double thresh_;
01564 };
01565 
01566 CV_EXPORTS Mat windowedMatchingMask( const vector<KeyPoint>& keypoints1, const vector<KeyPoint>& keypoints2,
01567                                      float maxDeltaX, float maxDeltaY );
01568 
01569 /****************************************************************************************\
01570 *                                 DescriptorExtractor                                    *
01571 \****************************************************************************************/
01572 
01573 /*
01574  * Abstract base class for computing descriptors for image keypoints.
01575  *
01576  * In this interface we assume a keypoint descriptor can be represented as a
01577  * dense, fixed-dimensional vector of some basic type. Most descriptors used
01578  * in practice follow this pattern, as it makes it very easy to compute
01579  * distances between descriptors. Therefore we represent a collection of
01580  * descriptors as a cv::Mat, where each row is one keypoint descriptor.
01581  */
01582 class CV_EXPORTS DescriptorExtractor
01583 {
01584 public:
01585     virtual ~DescriptorExtractor();
01586 
01587     /*
01588      * Compute the descriptors for a set of keypoints in an image.
01589      * image        The image.
01590      * keypoints    The input keypoints. Keypoints for which a descriptor cannot be computed are removed.
01591      * descriptors  Copmputed descriptors. Row i is the descriptor for keypoint i.
01592      */
01593     void compute( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
01594 
01595     /*
01596      * Compute the descriptors for a keypoints collection detected in image collection.
01597      * images       Image collection.
01598      * keypoints    Input keypoints collection. keypoints[i] is keypoints detected in images[i].
01599      *              Keypoints for which a descriptor cannot be computed are removed.
01600      * descriptors  Descriptor collection. descriptors[i] are descriptors computed for set keypoints[i].
01601      */
01602     void compute( const vector<Mat>& images, vector<vector<KeyPoint> >& keypoints, vector<Mat>& descriptors ) const;
01603 
01604     virtual void read( const FileNode& );
01605     virtual void write( FileStorage& ) const;
01606 
01607     virtual int descriptorSize() const = 0;
01608     virtual int descriptorType() const = 0;
01609 
01610     static Ptr<DescriptorExtractor> create( const string& descriptorExtractorType );
01611 
01612 protected:
01613         virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const = 0;
01614 
01615     /*
01616      * Remove keypoints within borderPixels of an image edge.
01617      */
01618     static void removeBorderKeypoints( vector<KeyPoint>& keypoints,
01619                                        Size imageSize, int borderSize );
01620 };
01621 
01622 /*
01623  * SiftDescriptorExtractor
01624  */
01625 class CV_EXPORTS SiftDescriptorExtractor : public DescriptorExtractor
01626 {
01627 public:
01628     SiftDescriptorExtractor( const SIFT::DescriptorParams& descriptorParams=SIFT::DescriptorParams(),
01629                              const SIFT::CommonParams& commonParams=SIFT::CommonParams() );
01630     SiftDescriptorExtractor( double magnification, bool isNormalize=true, bool recalculateAngles=true,
01631                              int nOctaves=SIFT::CommonParams::DEFAULT_NOCTAVES,
01632                              int nOctaveLayers=SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS,
01633                              int firstOctave=SIFT::CommonParams::DEFAULT_FIRST_OCTAVE,
01634                              int angleMode=SIFT::CommonParams::FIRST_ANGLE );
01635 
01636     virtual void read( const FileNode &fn );
01637     virtual void write( FileStorage &fs ) const;
01638 
01639     virtual int descriptorSize() const;
01640     virtual int descriptorType() const;
01641 
01642 protected:
01643         virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
01644     
01645     SIFT sift;
01646 };
01647 
01648 /*
01649  * SurfDescriptorExtractor
01650  */
01651 class CV_EXPORTS SurfDescriptorExtractor : public DescriptorExtractor
01652 {
01653 public:
01654     SurfDescriptorExtractor( int nOctaves=4, int nOctaveLayers=2, bool extended=false );
01655 
01656     virtual void read( const FileNode &fn );
01657     virtual void write( FileStorage &fs ) const;
01658 
01659     virtual int descriptorSize() const;
01660     virtual int descriptorType() const;
01661 
01662 protected:
01663         virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
01664 
01665     SURF surf;
01666 };
01667 
01668 /*
01669  * CalonderDescriptorExtractor
01670  */
01671 template<typename T>
01672 class CV_EXPORTS CalonderDescriptorExtractor : public DescriptorExtractor
01673 {
01674 public:
01675     CalonderDescriptorExtractor( const string& classifierFile );
01676 
01677     virtual void read( const FileNode &fn );
01678     virtual void write( FileStorage &fs ) const;
01679 
01680     virtual int descriptorSize() const { return classifier_.classes(); }
01681     virtual int descriptorType() const { return DataType<T>::type; }
01682 
01683 protected:
01684         virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
01685 
01686     RTreeClassifier classifier_;
01687     static const int BORDER_SIZE = 16;
01688 };
01689 
01690 template<typename T>
01691 CalonderDescriptorExtractor<T>::CalonderDescriptorExtractor(const std::string& classifier_file)
01692 {
01693     classifier_.read( classifier_file.c_str() );
01694 }
01695 
01696 template<typename T>
01697 void CalonderDescriptorExtractor<T>::computeImpl( const cv::Mat& image,
01698                                               std::vector<cv::KeyPoint>& keypoints,
01699                                               cv::Mat& descriptors) const
01700 {
01701     // Cannot compute descriptors for keypoints on the image border.
01702     removeBorderKeypoints(keypoints, image.size(), BORDER_SIZE);
01703 
01705     descriptors.create(keypoints.size(), classifier_.classes(), cv::DataType<T>::type);
01706 
01707     int patchSize = RandomizedTree::PATCH_SIZE;
01708     int offset = patchSize / 2;
01709     for (size_t i = 0; i < keypoints.size(); ++i)
01710     {
01711         cv::Point2f pt = keypoints[i].pt;
01712         IplImage ipl = image( Rect((int)(pt.x - offset), (int)(pt.y - offset), patchSize, patchSize) );
01713         classifier_.getSignature( &ipl, descriptors.ptr<T>(i));
01714     }
01715 }
01716 
01717 template<typename T>
01718 void CalonderDescriptorExtractor<T>::read( const FileNode& )
01719 {}
01720 
01721 template<typename T>
01722 void CalonderDescriptorExtractor<T>::write( FileStorage& ) const
01723 {}
01724 
01725 /*
01726  * OpponentColorDescriptorExtractor
01727  *
01728  * Adapts a descriptor extractor to compute descripors in Opponent Color Space
01729  * (refer to van de Sande et al., CGIV 2008 "Color Descriptors for Object Category Recognition").
01730  * Input RGB image is transformed in Opponent Color Space. Then unadapted descriptor extractor
01731  * (set in constructor) computes descriptors on each of the three channel and concatenate
01732  * them into a single color descriptor.
01733  */
01734 class CV_EXPORTS OpponentColorDescriptorExtractor : public DescriptorExtractor
01735 {
01736 public:
01737     OpponentColorDescriptorExtractor( const Ptr<DescriptorExtractor>& descriptorExtractor );
01738 
01739     virtual void read( const FileNode& );
01740     virtual void write( FileStorage& ) const;
01741 
01742     virtual int descriptorSize() const;
01743     virtual int descriptorType() const;
01744 
01745 protected:
01746         virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
01747 
01748     Ptr<DescriptorExtractor> descriptorExtractor;
01749 };
01750 
01751 /*
01752  * BRIEF Descriptor
01753  */
01754 class CV_EXPORTS BriefDescriptorExtractor : public DescriptorExtractor
01755 {
01756 public:
01757     static const int PATCH_SIZE = 48;
01758     static const int KERNEL_SIZE = 9;
01759 
01760     // bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.
01761     BriefDescriptorExtractor( int bytes = 32 );
01762 
01763     virtual int descriptorSize() const;
01764     virtual int descriptorType() const;
01765 
01767 
01768 protected:
01769         virtual void computeImpl(const Mat& image, std::vector<KeyPoint>& keypoints, Mat& descriptors) const;
01770 
01771     typedef void(*PixelTestFn)(const Mat&, const std::vector<KeyPoint>&, Mat&);
01772 
01773     int bytes_;
01774     PixelTestFn test_fn_;
01775 };
01776 
01777 /****************************************************************************************\
01778 *                                          Distance                                      *
01779 \****************************************************************************************/
01780 template<typename T>
01781 struct CV_EXPORTS Accumulator
01782 {
01783     typedef T Type;
01784 };
01785 
01786 template<> struct Accumulator<unsigned char>  { typedef float Type; };
01787 template<> struct Accumulator<unsigned short> { typedef float Type; };
01788 template<> struct Accumulator<char>   { typedef float Type; };
01789 template<> struct Accumulator<short>  { typedef float Type; };
01790 
01791 /*
01792  * Squared Euclidean distance functor
01793  */
01794 template<class T>
01795 struct CV_EXPORTS L2
01796 {
01797     typedef T ValueType;
01798     typedef typename Accumulator<T>::Type ResultType;
01799 
01800     ResultType operator()( const T* a, const T* b, int size ) const
01801     {
01802         ResultType result = ResultType();
01803         for( int i = 0; i < size; i++ )
01804         {
01805             ResultType diff = (ResultType)(a[i] - b[i]);
01806             result += diff*diff;
01807         }
01808         return (ResultType)sqrt((double)result);
01809     }
01810 };
01811 
01812 /*
01813  * Manhattan distance (city block distance) functor
01814  */
01815 template<class T>
01816 struct CV_EXPORTS L1
01817 {
01818     typedef T ValueType;
01819     typedef typename Accumulator<T>::Type ResultType;
01820 
01821     ResultType operator()( const T* a, const T* b, int size ) const
01822     {
01823         ResultType result = ResultType();
01824         for( int i = 0; i < size; i++ )
01825         {
01826             ResultType diff = a[i] - b[i];
01827             result += (ResultType)fabs( diff );
01828         }
01829         return result;
01830     }
01831 };
01832 
01833 /*
01834  * Hamming distance functor - counts the bit differences between two strings - useful for the Brief descriptor
01835  * bit count of A exclusive XOR'ed with B
01836  */
01837 struct CV_EXPORTS HammingLUT
01838 {
01839     typedef unsigned char ValueType;
01840     typedef int ResultType;
01841 
01844     ResultType operator()( const unsigned char* a, const unsigned char* b, int size ) const;
01845 
01851     static unsigned char byteBitsLookUp(unsigned char b);
01852 };
01853 
01854 
01858 struct CV_EXPORTS Hamming
01859 {
01860     typedef unsigned char ValueType;
01861 
01863     // in BruteForce if not
01864     typedef int ResultType;
01865 
01868     ResultType operator()(const unsigned char* a, const unsigned char* b, int size) const;
01869 };
01870 
01871 
01872 /****************************************************************************************\
01873 *                                      DMatch                                            *
01874 \****************************************************************************************/
01875 /*
01876  * Struct for matching: query descriptor index, train descriptor index, train image index and distance between descriptors.
01877  */
01878 struct CV_EXPORTS DMatch
01879 {
01880     DMatch() : queryIdx(-1), trainIdx(-1), imgIdx(-1), distance(std::numeric_limits<float>::max()) {}
01881     DMatch( int _queryIdx, int _trainIdx, float _distance ) :
01882             queryIdx(_queryIdx), trainIdx(_trainIdx), imgIdx(-1), distance(_distance) {}
01883     DMatch( int _queryIdx, int _trainIdx, int _imgIdx, float _distance ) :
01884             queryIdx(_queryIdx), trainIdx(_trainIdx), imgIdx(_imgIdx), distance(_distance) {}
01885 
01886     int queryIdx; // query descriptor index
01887     int trainIdx; // train descriptor index
01888     int imgIdx;   // train image index
01889 
01890     float distance;
01891 
01892     // less is better
01893     bool operator<( const DMatch &m ) const
01894     {
01895         return distance < m.distance;
01896     }
01897 };
01898 
01899 /****************************************************************************************\
01900 *                                  DescriptorMatcher                                     *
01901 \****************************************************************************************/
01902 /*
01903  * Abstract base class for matching two sets of descriptors.
01904  */
01905 class CV_EXPORTS DescriptorMatcher
01906 {
01907 public:
01908     virtual ~DescriptorMatcher();
01909 
01910         /*
01911      * Add descriptors to train descriptor collection.
01912      * descriptors      Descriptors to add. Each descriptors[i] is a descriptors set from one image.
01913      */
01914     virtual void add( const vector<Mat>& descriptors );
01915     /*
01916      * Get train descriptors collection.
01917      */
01918     const vector<Mat>& getTrainDescriptors() const;
01919     /*
01920      * Clear train descriptors collection.
01921      */
01922     virtual void clear();
01923 
01924     /*
01925      * Return true if there are not train descriptors in collection.
01926      */
01927         bool empty() const;
01928     /*
01929      * Return true if the matcher supports mask in match methods.
01930      */
01931     virtual bool isMaskSupported() const = 0;
01932 
01933     /*
01934      * Train matcher (e.g. train flann index).
01935      * In all methods to match the method train() is run every time before matching.
01936      * Some descriptor matchers (e.g. BruteForceMatcher) have empty implementation
01937      * of this method, other matchers realy train their inner structures
01938      * (e.g. FlannBasedMatcher trains flann::Index). So nonempty implementation
01939      * of train() should check the class object state and do traing/retraining
01940      * only if the state requires that (e.g. FlannBasedMatcher trains flann::Index
01941      * if it has not trained yet or if new descriptors have been added to the train
01942      * collection).
01943      */
01944     virtual void train();
01945     /*
01946      * Group of methods to match descriptors from image pair.
01947      * Method train() is run in this methods.
01948      */
01949     // Find one best match for each query descriptor (if mask is empty).
01950     void match( const Mat& queryDescriptors, const Mat& trainDescriptors,
01951                 vector<DMatch>& matches, const Mat& mask=Mat() ) const;
01952     // Find k best matches for each query descriptor (in increasing order of distances).
01953     // compactResult is used when mask is not empty. If compactResult is false matches
01954     // vector will have the same size as queryDescriptors rows. If compactResult is true
01955     // matches vector will not contain matches for fully masked out query descriptors.
01956     void knnMatch( const Mat& queryDescriptors, const Mat& trainDescriptors,
01957                    vector<vector<DMatch> >& matches, int k,
01958                    const Mat& mask=Mat(), bool compactResult=false ) const;
01959     // Find best matches for each query descriptor which have distance less than
01960     // maxDistance (in increasing order of distances).
01961     void radiusMatch( const Mat& queryDescriptors, const Mat& trainDescriptors,
01962                       vector<vector<DMatch> >& matches, float maxDistance,
01963                       const Mat& mask=Mat(), bool compactResult=false ) const;
01964     /*
01965      * Group of methods to match descriptors from one image to image set.
01966      * See description of similar methods for matching image pair above.
01967      */
01968     void match( const Mat& queryDescriptors, vector<DMatch>& matches,
01969                 const vector<Mat>& masks=vector<Mat>() );
01970     void knnMatch( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
01971            const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
01972     void radiusMatch( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
01973                    const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
01974 
01975     // Reads matcher object from a file node
01976     virtual void read( const FileNode& );
01977     // Writes matcher object to a file storage
01978     virtual void write( FileStorage& ) const;
01979 
01980     // Clone the matcher. If emptyTrainData is false the method create deep copy of the object, i.e. copies
01981     // both parameters and train data. If emptyTrainData is true the method create object copy with current parameters
01982     // but with empty train data.
01983     virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const = 0;
01984 
01985     static Ptr<DescriptorMatcher> create( const string& descriptorMatcherType );
01986 protected:
01987     /*
01988      * Class to work with descriptors from several images as with one merged matrix.
01989      * It is used e.g. in FlannBasedMatcher.
01990      */
01991     class CV_EXPORTS DescriptorCollection
01992     {
01993     public:
01994         DescriptorCollection();
01995         DescriptorCollection( const DescriptorCollection& collection );
01996         virtual ~DescriptorCollection();
01997 
01998         // Vector of matrices "descriptors" will be merged to one matrix "mergedDescriptors" here.
01999         void set( const vector<Mat>& descriptors );
02000         virtual void clear();
02001 
02002         const Mat& getDescriptors() const;
02003         const Mat getDescriptor( int imgIdx, int localDescIdx ) const;
02004         const Mat getDescriptor( int globalDescIdx ) const;
02005         void getLocalIdx( int globalDescIdx, int& imgIdx, int& localDescIdx ) const;
02006 
02007         int size() const;
02008 
02009     protected:
02010         Mat mergedDescriptors;
02011         vector<int> startIdxs;
02012     };
02013 
02014     // In fact the matching is implemented only by the following two methods. These methods suppose
02015     // that the class object has been trained already. Public match methods call these methods
02016     // after calling train().
02017     virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02018            const vector<Mat>& masks=vector<Mat>(), bool compactResult=false ) = 0;
02019     virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
02020            const vector<Mat>& masks=vector<Mat>(), bool compactResult=false ) = 0;
02021 
02022     static bool isPossibleMatch( const Mat& mask, int queryIdx, int trainIdx );
02023     static bool isMaskedOut( const vector<Mat>& masks, int queryIdx );
02024 
02025     static Mat clone_op( Mat m ) { return m.clone(); }
02026         void checkMasks( const vector<Mat>& masks, int queryDescriptorsCount ) const;
02027 
02028     // Collection of descriptors from train images.
02029     vector<Mat> trainDescCollection;
02030 };
02031 
02032 /*
02033  * Brute-force descriptor matcher.
02034  *
02035  * For each descriptor in the first set, this matcher finds the closest
02036  * descriptor in the second set by trying each one.
02037  *
02038  * For efficiency, BruteForceMatcher is templated on the distance metric.
02039  * For float descriptors, a common choice would be cv::L2<float>.
02040  */
02041 template<class Distance>
02042 class CV_EXPORTS BruteForceMatcher : public DescriptorMatcher
02043 {
02044 public:
02045     BruteForceMatcher( Distance d = Distance() ) : distance(d) {}
02046     virtual ~BruteForceMatcher() {}
02047 
02048     virtual bool isMaskSupported() const { return true; }
02049 
02050     virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const;
02051 
02052 protected:
02053     virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02054            const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02055     virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
02056            const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02057 
02058     Distance distance;
02059 
02060 private:
02061     /*
02062      * Next two methods are used to implement specialization.
02063      */
02064     static void commonKnnMatchImpl( BruteForceMatcher<Distance>& matcher,
02065                     const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02066                     const vector<Mat>& masks, bool compactResult );
02067     static void commonRadiusMatchImpl( BruteForceMatcher<Distance>& matcher,
02068                     const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
02069                     const vector<Mat>& masks, bool compactResult );
02070 };
02071 
02072 template<class Distance>
02073 Ptr<DescriptorMatcher> BruteForceMatcher<Distance>::clone( bool emptyTrainData ) const
02074 {
02075     BruteForceMatcher* matcher = new BruteForceMatcher(distance);
02076     if( !emptyTrainData )
02077     {
02078         std::transform( trainDescCollection.begin(), trainDescCollection.end(),
02079                         matcher->trainDescCollection.begin(), clone_op );
02080     }
02081     return matcher;
02082 }
02083 
02084 template<class Distance>
02085 void BruteForceMatcher<Distance>::knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02086                                                 const vector<Mat>& masks, bool compactResult )
02087 {
02088     commonKnnMatchImpl( *this, queryDescriptors, matches, k, masks, compactResult );
02089 }
02090 
02091 template<class Distance>
02092 void BruteForceMatcher<Distance>::radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches,
02093                                                    float maxDistance, const vector<Mat>& masks, bool compactResult )
02094 {
02095     commonRadiusMatchImpl( *this, queryDescriptors, matches, maxDistance, masks, compactResult );
02096 }
02097 
02098 template<class Distance>
02099 inline void BruteForceMatcher<Distance>::commonKnnMatchImpl( BruteForceMatcher<Distance>& matcher,
02100                           const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int knn,
02101                           const vector<Mat>& masks, bool compactResult )
02102  {
02103      typedef typename Distance::ValueType ValueType;
02104      typedef typename Distance::ResultType DistanceType;
02105          CV_DbgAssert( !queryDescriptors.empty() );
02106      CV_Assert( DataType<ValueType>::type == queryDescriptors.type() );
02107      
02108      int dimension = queryDescriptors.cols;
02109      matches.reserve(queryDescriptors.rows);
02110 
02111      size_t imgCount = matcher.trainDescCollection.size();
02112      vector<Mat> allDists( imgCount ); // distances between one query descriptor and all train descriptors
02113      for( size_t i = 0; i < imgCount; i++ )
02114         allDists[i] = Mat( 1, matcher.trainDescCollection[i].rows, DataType<DistanceType>::type );
02115 
02116      for( int qIdx = 0; qIdx < queryDescriptors.rows; qIdx++ )
02117      {
02118          if( matcher.isMaskedOut( masks, qIdx ) )
02119          {
02120              if( !compactResult ) // push empty vector
02121                  matches.push_back( vector<DMatch>() );
02122          }
02123          else
02124          {
02125              // 1. compute distances between i-th query descriptor and all train descriptors
02126              for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
02127              {
02128                  CV_Assert( DataType<ValueType>::type == matcher.trainDescCollection[iIdx].type() ||  matcher.trainDescCollection[iIdx].empty() );
02129                                  CV_Assert( queryDescriptors.cols == matcher.trainDescCollection[iIdx].cols || 
02130                                             matcher.trainDescCollection[iIdx].empty() );
02131 
02132                  const ValueType* d1 = (const ValueType*)(queryDescriptors.data + queryDescriptors.step*qIdx);
02133                  allDists[iIdx].setTo( Scalar::all(std::numeric_limits<DistanceType>::max()) );
02134                  for( int tIdx = 0; tIdx < matcher.trainDescCollection[iIdx].rows; tIdx++ )
02135                  {
02136                      if( masks.empty() || matcher.isPossibleMatch(masks[iIdx], qIdx, tIdx) )
02137                      {
02138                          const ValueType* d2 = (const ValueType*)(matcher.trainDescCollection[iIdx].data +
02139                                                                   matcher.trainDescCollection[iIdx].step*tIdx);
02140                          allDists[iIdx].at<DistanceType>(0, tIdx) = matcher.distance(d1, d2, dimension);
02141                      }
02142                  }
02143              }
02144 
02145              // 2. choose k nearest matches for query[i]
02146              matches.push_back( vector<DMatch>() );
02147              vector<vector<DMatch> >::reverse_iterator curMatches = matches.rbegin();
02148              for( int k = 0; k < knn; k++ )
02149              {
02150                  DMatch bestMatch;
02151                  bestMatch.distance = std::numeric_limits<float>::max();
02152                  for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
02153                  {
02154                      if( !allDists[iIdx].empty() )
02155                      {
02156                          double minVal;
02157                          Point minLoc;
02158                          minMaxLoc( allDists[iIdx], &minVal, 0, &minLoc, 0 );
02159                          if( minVal < bestMatch.distance )
02160                                  bestMatch = DMatch( qIdx, minLoc.x, (int)iIdx, (float)minVal );
02161                      }
02162                  }
02163                  if( bestMatch.trainIdx == -1 )
02164                      break;
02165 
02166                  allDists[bestMatch.imgIdx].at<DistanceType>(0, bestMatch.trainIdx) = std::numeric_limits<DistanceType>::max();
02167                  curMatches->push_back( bestMatch );
02168              }
02169              //TODO should already be sorted at this point?
02170              std::sort( curMatches->begin(), curMatches->end() );
02171          }
02172      }
02173 }
02174 
02175 template<class Distance>
02176 inline void BruteForceMatcher<Distance>::commonRadiusMatchImpl( BruteForceMatcher<Distance>& matcher,
02177                              const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
02178                              const vector<Mat>& masks, bool compactResult )
02179 {
02180     typedef typename Distance::ValueType ValueType;
02181     typedef typename Distance::ResultType DistanceType;
02182         CV_DbgAssert( !queryDescriptors.empty() );
02183     CV_Assert( DataType<ValueType>::type == queryDescriptors.type() );
02184     
02185     int dimension = queryDescriptors.cols;
02186     matches.reserve(queryDescriptors.rows);
02187 
02188     size_t imgCount = matcher.trainDescCollection.size();
02189     for( int qIdx = 0; qIdx < queryDescriptors.rows; qIdx++ )
02190     {
02191         if( matcher.isMaskedOut( masks, qIdx ) )
02192         {
02193             if( !compactResult ) // push empty vector
02194                 matches.push_back( vector<DMatch>() );
02195         }
02196         else
02197         {
02198             matches.push_back( vector<DMatch>() );
02199             vector<vector<DMatch> >::reverse_iterator curMatches = matches.rbegin();
02200             for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
02201             {
02202                 CV_Assert( DataType<ValueType>::type == matcher.trainDescCollection[iIdx].type() ||
02203                            matcher.trainDescCollection[iIdx].empty() );
02204                 CV_Assert( queryDescriptors.cols == matcher.trainDescCollection[iIdx].cols ||
02205                                                    matcher.trainDescCollection[iIdx].empty() );
02206 
02207                 const ValueType* d1 = (const ValueType*)(queryDescriptors.data + queryDescriptors.step*qIdx);
02208                 for( int tIdx = 0; tIdx < matcher.trainDescCollection[iIdx].rows; tIdx++ )
02209                 {
02210                     if( masks.empty() || matcher.isPossibleMatch(masks[iIdx], qIdx, tIdx) )
02211                     {
02212                         const ValueType* d2 = (const ValueType*)(matcher.trainDescCollection[iIdx].data +
02213                                                                  matcher.trainDescCollection[iIdx].step*tIdx);
02214                         DistanceType d = matcher.distance(d1, d2, dimension);
02215                         if( d < maxDistance )
02216                             curMatches->push_back( DMatch( qIdx, tIdx, (int)iIdx, (float)d ) );
02217                     }
02218                 }
02219             }
02220             std::sort( curMatches->begin(), curMatches->end() );
02221         }
02222     }
02223 }
02224 
02225 /*
02226  * BruteForceMatcher L2 specialization
02227  */
02228 template<>
02229 void BruteForceMatcher<L2<float> >::knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02230                                                   const vector<Mat>& masks, bool compactResult );
02231 template<>
02232 void BruteForceMatcher<L2<float> >::radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches,
02233                                                      float maxDistance, const vector<Mat>& masks, bool compactResult );
02234 
02235 /*
02236  * Flann based matcher
02237  */
02238 class CV_EXPORTS FlannBasedMatcher : public DescriptorMatcher
02239 {
02240 public:
02241     FlannBasedMatcher( const Ptr<flann::IndexParams>& indexParams=new flann::KDTreeIndexParams(),
02242                        const Ptr<flann::SearchParams>& searchParams=new flann::SearchParams() );
02243 
02244     virtual void add( const vector<Mat>& descriptors );
02245     virtual void clear();
02246 
02247     virtual void train();
02248     virtual bool isMaskSupported() const;
02249         
02250     virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const;
02251 
02252 protected:
02253     static void convertToDMatches( const DescriptorCollection& descriptors,
02254                                    const Mat& indices, const Mat& distances,
02255                                    vector<vector<DMatch> >& matches );
02256 
02257     virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
02258                    const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02259     virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
02260                    const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02261 
02262     Ptr<flann::IndexParams> indexParams;
02263     Ptr<flann::SearchParams> searchParams;
02264     Ptr<flann::Index> flannIndex;
02265 
02266     DescriptorCollection mergedDescriptors;
02267     int addedDescCount;
02268 };
02269 
02270 /****************************************************************************************\
02271 *                                GenericDescriptorMatcher                                *
02272 \****************************************************************************************/
02273 /*
02274  *   Abstract interface for a keypoint descriptor and matcher
02275  */
02276 class GenericDescriptorMatcher;
02277 typedef GenericDescriptorMatcher GenericDescriptorMatch;
02278 
02279 class CV_EXPORTS GenericDescriptorMatcher
02280 {
02281 public:
02282     GenericDescriptorMatcher();
02283     virtual ~GenericDescriptorMatcher();
02284 
02285     /*
02286      * Add train collection: images and keypoints from them.
02287      * images       A set of train images.
02288      * ketpoints    Keypoint collection that have been detected on train images.
02289      *
02290      * Keypoints for which a descriptor cannot be computed are removed. Such keypoints
02291      * must be filtered in this method befor adding keypoints to train collection "trainPointCollection".
02292      * If inheritor class need perform such prefiltering the method add() must be overloaded.
02293      * In the other class methods programmer has access to the train keypoints by a constant link.
02294      */
02295     virtual void add( const vector<Mat>& images,
02296                       vector<vector<KeyPoint> >& keypoints );
02297 
02298     const vector<Mat>& getTrainImages() const;
02299     const vector<vector<KeyPoint> >& getTrainKeypoints() const;
02300 
02301     /*
02302      * Clear images and keypoints storing in train collection.
02303      */
02304     virtual void clear();
02305     /*
02306      * Returns true if matcher supports mask to match descriptors.
02307      */
02308     virtual bool isMaskSupported() = 0;
02309     /*
02310      * Train some inner structures (e.g. flann index or decision trees).
02311      * train() methods is run every time in matching methods. So the method implementation
02312      * should has a check whether these inner structures need be trained/retrained or not.
02313      */
02314     virtual void train();
02315 
02316     /*
02317      * Classifies query keypoints.
02318      * queryImage    The query image
02319      * queryKeypoints   Keypoints from the query image
02320      * trainImage    The train image
02321      * trainKeypoints   Keypoints from the train image
02322      */
02323     // Classify keypoints from query image under one train image.
02324     void classify( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02325                            const Mat& trainImage, vector<KeyPoint>& trainKeypoints ) const;
02326     // Classify keypoints from query image under train image collection.
02327     void classify( const Mat& queryImage, vector<KeyPoint>& queryKeypoints );
02328 
02329     /*
02330      * Group of methods to match keypoints from image pair.
02331      * Keypoints for which a descriptor cannot be computed are removed.
02332      * train() method is called here.
02333      */
02334     // Find one best match for each query descriptor (if mask is empty).
02335     void match( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02336                 const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
02337                 vector<DMatch>& matches, const Mat& mask=Mat() ) const;
02338     // Find k best matches for each query keypoint (in increasing order of distances).
02339     // compactResult is used when mask is not empty. If compactResult is false matches
02340     // vector will have the same size as queryDescriptors rows.
02341     // If compactResult is true matches vector will not contain matches for fully masked out query descriptors.
02342     void knnMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02343                    const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
02344                    vector<vector<DMatch> >& matches, int k,
02345                    const Mat& mask=Mat(), bool compactResult=false ) const;
02346     // Find best matches for each query descriptor which have distance less than maxDistance (in increasing order of distances).
02347     void radiusMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02348                       const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
02349                       vector<vector<DMatch> >& matches, float maxDistance,
02350                       const Mat& mask=Mat(), bool compactResult=false ) const;
02351     /*
02352      * Group of methods to match keypoints from one image to image set.
02353      * See description of similar methods for matching image pair above.
02354      */
02355     void match( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02356                 vector<DMatch>& matches, const vector<Mat>& masks=vector<Mat>() );
02357     void knnMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02358                    vector<vector<DMatch> >& matches, int k,
02359                    const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02360     void radiusMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02361                       vector<vector<DMatch> >& matches, float maxDistance,
02362                       const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
02363 
02364     // Reads matcher object from a file node
02365     virtual void read( const FileNode& );
02366     // Writes matcher object to a file storage
02367     virtual void write( FileStorage& ) const;
02368 
02369     // Clone the matcher. If emptyTrainData is false the method create deep copy of the object, i.e. copies
02370     // both parameters and train data. If emptyTrainData is true the method create object copy with current parameters
02371     // but with empty train data.
02372     virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const = 0;
02373 
02374     static Ptr<GenericDescriptorMatcher> create( const string& genericDescritptorMatcherType,
02375                                                  const string &paramsFilename=string() );
02376 
02377 protected:
02378     // In fact the matching is implemented only by the following two methods. These methods suppose
02379     // that the class object has been trained already. Public match methods call these methods
02380     // after calling train().
02381     virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02382                                vector<vector<DMatch> >& matches, int k,
02383                                const vector<Mat>& masks, bool compactResult ) = 0;
02384     virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02385                                   vector<vector<DMatch> >& matches, float maxDistance,
02386                                   const vector<Mat>& masks, bool compactResult ) = 0;
02387     /*
02388      * A storage for sets of keypoints together with corresponding images and class IDs
02389      */
02390     class CV_EXPORTS KeyPointCollection
02391     {
02392     public:
02393         KeyPointCollection();
02394         KeyPointCollection( const KeyPointCollection& collection );
02395         void add( const vector<Mat>& images, const vector<vector<KeyPoint> >& keypoints );
02396         void clear();
02397 
02398         // Returns the total number of keypoints in the collection
02399         size_t keypointCount() const;
02400         size_t imageCount() const;
02401 
02402         const vector<vector<KeyPoint> >& getKeypoints() const;
02403         const vector<KeyPoint>& getKeypoints( int imgIdx ) const;
02404         const KeyPoint& getKeyPoint( int imgIdx, int localPointIdx ) const;
02405         const KeyPoint& getKeyPoint( int globalPointIdx ) const;
02406         void getLocalIdx( int globalPointIdx, int& imgIdx, int& localPointIdx ) const;
02407 
02408         const vector<Mat>& getImages() const;
02409         const Mat& getImage( int imgIdx ) const;
02410 
02411     protected:
02412         int pointCount;
02413 
02414         vector<Mat> images;
02415         vector<vector<KeyPoint> > keypoints;
02416         // global indices of the first points in each image, startIndices.size() = keypoints.size()
02417         vector<int> startIndices;
02418 
02419     private:
02420         static Mat clone_op( Mat m ) { return m.clone(); }
02421     };
02422 
02423     KeyPointCollection trainPointCollection;
02424 };
02425 
02426 /*
02427  *  OneWayDescriptorMatcher
02428  */
02429 class OneWayDescriptorMatcher;
02430 typedef OneWayDescriptorMatcher OneWayDescriptorMatch;
02431 
02432 class CV_EXPORTS OneWayDescriptorMatcher : public GenericDescriptorMatcher
02433 {
02434 public:
02435     class CV_EXPORTS Params
02436     {
02437     public:
02438         static const int POSE_COUNT = 500;
02439         static const int PATCH_WIDTH = 24;
02440         static const int PATCH_HEIGHT = 24;
02441         static float GET_MIN_SCALE() { return 0.7f; }
02442         static float GET_MAX_SCALE() { return 1.5f; }
02443         static float GET_STEP_SCALE() { return 1.2f; }
02444 
02445         Params( int poseCount = POSE_COUNT,
02446                 Size patchSize = Size(PATCH_WIDTH, PATCH_HEIGHT),
02447                 string pcaFilename = string(),
02448                 string trainPath = string(), string trainImagesList = string(),
02449                 float minScale = GET_MIN_SCALE(), float maxScale = GET_MAX_SCALE(),
02450                 float stepScale = GET_STEP_SCALE() );
02451 
02452         int poseCount;
02453         Size patchSize;
02454         string pcaFilename;
02455         string trainPath;
02456         string trainImagesList;
02457 
02458         float minScale, maxScale, stepScale;
02459     };
02460 
02461     OneWayDescriptorMatcher( const Params& params=Params() );
02462     virtual ~OneWayDescriptorMatcher();
02463 
02464     void initialize( const Params& params, const Ptr<OneWayDescriptorBase>& base=Ptr<OneWayDescriptorBase>() );
02465 
02466     // Clears keypoints storing in collection and OneWayDescriptorBase
02467     virtual void clear();
02468 
02469     virtual void train();
02470 
02471     virtual bool isMaskSupported();
02472 
02473     virtual void read( const FileNode &fn );
02474     virtual void write( FileStorage& fs ) const;
02475 
02476     virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
02477 
02478 protected:
02479     // Matches a set of keypoints from a single image of the training set. A rectangle with a center in a keypoint
02480     // and size (patch_width/2*scale, patch_height/2*scale) is cropped from the source image for each
02481     // keypoint. scale is iterated from DescriptorOneWayParams::min_scale to DescriptorOneWayParams::max_scale.
02482     // The minimum distance to each training patch with all its affine poses is found over all scales.
02483     // The class ID of a match is returned for each keypoint. The distance is calculated over PCA components
02484     // loaded with DescriptorOneWay::Initialize, kd tree is used for finding minimum distances.
02485     virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02486                                vector<vector<DMatch> >& matches, int k,
02487                                const vector<Mat>& masks, bool compactResult );
02488     virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02489                                   vector<vector<DMatch> >& matches, float maxDistance,
02490                                   const vector<Mat>& masks, bool compactResult );
02491 
02492     Ptr<OneWayDescriptorBase> base;
02493     Params params;
02494     int prevTrainCount;
02495 };
02496 
02497 /*
02498  *  FernDescriptorMatcher
02499  */
02500 class FernDescriptorMatcher;
02501 typedef FernDescriptorMatcher FernDescriptorMatch;
02502 
02503 class CV_EXPORTS FernDescriptorMatcher : public GenericDescriptorMatcher
02504 {
02505 public:
02506     class CV_EXPORTS Params
02507     {
02508     public:
02509         Params( int nclasses=0,
02510                 int patchSize=FernClassifier::PATCH_SIZE,
02511                 int signatureSize=FernClassifier::DEFAULT_SIGNATURE_SIZE,
02512                 int nstructs=FernClassifier::DEFAULT_STRUCTS,
02513                 int structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
02514                 int nviews=FernClassifier::DEFAULT_VIEWS,
02515                 int compressionMethod=FernClassifier::COMPRESSION_NONE,
02516                 const PatchGenerator& patchGenerator=PatchGenerator() );
02517 
02518         Params( const string& filename );
02519 
02520         int nclasses;
02521         int patchSize;
02522         int signatureSize;
02523         int nstructs;
02524         int structSize;
02525         int nviews;
02526         int compressionMethod;
02527         PatchGenerator patchGenerator;
02528 
02529         string filename;
02530     };
02531 
02532     FernDescriptorMatcher( const Params& params=Params() );
02533     virtual ~FernDescriptorMatcher();
02534 
02535     virtual void clear();
02536 
02537     virtual void train();
02538 
02539     virtual bool isMaskSupported();
02540 
02541     virtual void read( const FileNode &fn );
02542     virtual void write( FileStorage& fs ) const;
02543     
02544     virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
02545 
02546 protected:
02547     virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02548                                vector<vector<DMatch> >& matches, int k,
02549                                const vector<Mat>& masks, bool compactResult );
02550     virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02551                                   vector<vector<DMatch> >& matches, float maxDistance,
02552                                   const vector<Mat>& masks, bool compactResult );
02553 
02554     void trainFernClassifier();
02555     void calcBestProbAndMatchIdx( const Mat& image, const Point2f& pt,
02556                                   float& bestProb, int& bestMatchIdx, vector<float>& signature );
02557     Ptr<FernClassifier> classifier;
02558     Params params;
02559     int prevTrainCount;
02560 };
02561 
02562 /****************************************************************************************\
02563 *                                VectorDescriptorMatcher                                 *
02564 \****************************************************************************************/
02565 
02566 /*
02567  *  A class used for matching descriptors that can be described as vectors in a finite-dimensional space
02568  */
02569 class VectorDescriptorMatcher;
02570 typedef VectorDescriptorMatcher VectorDescriptorMatch;
02571 
02572 class CV_EXPORTS VectorDescriptorMatcher : public GenericDescriptorMatcher
02573 {
02574 public:
02575     VectorDescriptorMatcher( const Ptr<DescriptorExtractor>& extractor, const Ptr<DescriptorMatcher>& matcher );
02576     virtual ~VectorDescriptorMatcher();
02577 
02578     virtual void add( const vector<Mat>& imgCollection,
02579                       vector<vector<KeyPoint> >& pointCollection );
02580 
02581     virtual void clear();
02582 
02583     virtual void train();
02584 
02585     virtual bool isMaskSupported();
02586 
02587     virtual void read( const FileNode& fn );
02588     virtual void write( FileStorage& fs ) const;
02589 
02590     virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
02591 
02592 protected:
02593     virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02594                                vector<vector<DMatch> >& matches, int k,
02595                                const vector<Mat>& masks, bool compactResult );
02596     virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
02597                                   vector<vector<DMatch> >& matches, float maxDistance,
02598                                   const vector<Mat>& masks, bool compactResult );
02599 
02600     Ptr<DescriptorExtractor> extractor;
02601     Ptr<DescriptorMatcher> matcher;
02602 };
02603 
02604 /****************************************************************************************\
02605 *                                   Drawing functions                                    *
02606 \****************************************************************************************/
02607 struct CV_EXPORTS DrawMatchesFlags
02608 {
02609     enum{ DEFAULT = 0, // Output image matrix will be created (Mat::create),
02610                        // i.e. existing memory of output image may be reused.
02611                        // Two source image, matches and single keypoints will be drawn.
02612                        // For each keypoint only the center point will be drawn (without
02613                        // the circle around keypoint with keypoint size and orientation).
02614           DRAW_OVER_OUTIMG = 1, // Output image matrix will not be created (Mat::create).
02615                                 // Matches will be drawn on existing content of output image.
02616           NOT_DRAW_SINGLE_POINTS = 2, // Single keypoints will not be drawn.
02617           DRAW_RICH_KEYPOINTS = 4 // For each keypoint the circle around keypoint with keypoint size and
02618                                   // orientation will be drawn.
02619         };
02620 };
02621 
02622 // Draw keypoints.
02623 CV_EXPORTS void drawKeypoints( const Mat& image, const vector<KeyPoint>& keypoints, Mat& outImg,
02624                                const Scalar& color=Scalar::all(-1), int flags=DrawMatchesFlags::DEFAULT );
02625 
02626 // Draws matches of keypints from two images on output image.
02627 CV_EXPORTS void drawMatches( const Mat& img1, const vector<KeyPoint>& keypoints1,
02628                              const Mat& img2, const vector<KeyPoint>& keypoints2,
02629                              const vector<DMatch>& matches1to2, Mat& outImg,
02630                              const Scalar& matchColor=Scalar::all(-1), const Scalar& singlePointColor=Scalar::all(-1),
02631                              const vector<char>& matchesMask=vector<char>(), int flags=DrawMatchesFlags::DEFAULT );
02632 
02633 CV_EXPORTS void drawMatches( const Mat& img1, const vector<KeyPoint>& keypoints1,
02634                              const Mat& img2, const vector<KeyPoint>& keypoints2,
02635                              const vector<vector<DMatch> >& matches1to2, Mat& outImg,
02636                              const Scalar& matchColor=Scalar::all(-1), const Scalar& singlePointColor=Scalar::all(-1),
02637                              const vector<vector<char> >& matchesMask=vector<vector<char> >(), int flags=DrawMatchesFlags::DEFAULT );
02638 
02639 /****************************************************************************************\
02640 *   Functions to evaluate the feature detectors and [generic] descriptor extractors      *
02641 \****************************************************************************************/
02642 
02643 CV_EXPORTS void evaluateFeatureDetector( const Mat& img1, const Mat& img2, const Mat& H1to2,
02644                                          vector<KeyPoint>* keypoints1, vector<KeyPoint>* keypoints2,
02645                                          float& repeatability, int& correspCount,
02646                                          const Ptr<FeatureDetector>& fdetector=Ptr<FeatureDetector>() );
02647 
02648 CV_EXPORTS void computeRecallPrecisionCurve( const vector<vector<DMatch> >& matches1to2,
02649                                              const vector<vector<uchar> >& correctMatches1to2Mask,
02650                                              vector<Point2f>& recallPrecisionCurve );
02651 CV_EXPORTS float getRecall( const vector<Point2f>& recallPrecisionCurve, float l_precision );
02652 
02653 CV_EXPORTS void evaluateGenericDescriptorMatcher( const Mat& img1, const Mat& img2, const Mat& H1to2,
02654                                                   vector<KeyPoint>& keypoints1, vector<KeyPoint>& keypoints2,
02655                                                   vector<vector<DMatch> >* matches1to2, vector<vector<uchar> >* correctMatches1to2Mask,
02656                                                   vector<Point2f>& recallPrecisionCurve,
02657                                                   const Ptr<GenericDescriptorMatcher>& dmatch=Ptr<GenericDescriptorMatcher>() );
02658 
02659 
02660 /****************************************************************************************\
02661 *                                     Bag of visual words                                *
02662 \****************************************************************************************/
02663 /*
02664  * Abstract base class for training of a 'bag of visual words' vocabulary from a set of descriptors
02665  */
02666 class CV_EXPORTS BOWTrainer
02667 {
02668 public:
02669     BOWTrainer();
02670     virtual ~BOWTrainer();
02671 
02672     void add( const Mat& descriptors );
02673     const vector<Mat>& getDescriptors() const;
02674     int descripotorsCount() const;
02675 
02676     virtual void clear();
02677 
02678     /*
02679      * Train visual words vocabulary, that is cluster training descriptors and
02680      * compute cluster centers.
02681      * Returns cluster centers.
02682      *
02683      * descriptors      Training descriptors computed on images keypoints.
02684      */
02685     virtual Mat cluster() const = 0;
02686     virtual Mat cluster( const Mat& descriptors ) const = 0;
02687 
02688 protected:
02689     vector<Mat> descriptors;
02690     int size;
02691 };
02692 
02693 /*
02694  * This is BOWTrainer using cv::kmeans to get vocabulary.
02695  */
02696 class CV_EXPORTS BOWKMeansTrainer : public BOWTrainer
02697 {
02698 public:
02699     BOWKMeansTrainer( int clusterCount, const TermCriteria& termcrit=TermCriteria(),
02700                       int attempts=3, int flags=KMEANS_PP_CENTERS );
02701     virtual ~BOWKMeansTrainer();
02702 
02703     // Returns trained vocabulary (i.e. cluster centers).
02704     virtual Mat cluster() const;
02705     virtual Mat cluster( const Mat& descriptors ) const;
02706 
02707 protected:
02708 
02709     int clusterCount;
02710     TermCriteria termcrit;
02711     int attempts;
02712     int flags;
02713 };
02714 
02715 /*
02716  * Class to compute image descriptor using bag of visual words.
02717  */
02718 class CV_EXPORTS BOWImgDescriptorExtractor
02719 {
02720 public:
02721     BOWImgDescriptorExtractor( const Ptr<DescriptorExtractor>& dextractor,
02722                                const Ptr<DescriptorMatcher>& dmatcher );
02723     virtual ~BOWImgDescriptorExtractor();
02724 
02725     void setVocabulary( const Mat& vocabulary );
02726     const Mat& getVocabulary() const;
02727     void compute( const Mat& image, vector<KeyPoint>& keypoints, Mat& imgDescriptor,
02728                   vector<vector<int> >* pointIdxsOfClusters=0, Mat* descriptors=0 );
02729     // compute() is not constant because DescriptorMatcher::match is not constant
02730 
02731     int descriptorSize() const;
02732     int descriptorType() const;
02733 
02734 protected:
02735     Mat vocabulary;
02736     Ptr<DescriptorExtractor> dextractor;
02737     Ptr<DescriptorMatcher> dmatcher;
02738 };
02739 
02740 } /* namespace cv */
02741 
02742 #endif /* __cplusplus */
02743 
02744 #endif
02745 
02746 /* End of file. */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines