opencv  2.2.0
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Macros Pages
features2d.hpp
Go to the documentation of this file.
1 /*M///////////////////////////////////////////////////////////////////////////////////////
2 //
3 // IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
4 //
5 // By downloading, copying, installing or using the software you agree to this license.
6 // If you do not agree to this license, do not download, install,
7 // copy or use the software.
8 //
9 //
10 // License Agreement
11 // For Open Source Computer Vision Library
12 //
13 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
14 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
15 // Third party copyrights are property of their respective owners.
16 //
17 // Redistribution and use in source and binary forms, with or without modification,
18 // are permitted provided that the following conditions are met:
19 //
20 // * Redistribution's of source code must retain the above copyright notice,
21 // this list of conditions and the following disclaimer.
22 //
23 // * Redistribution's in binary form must reproduce the above copyright notice,
24 // this list of conditions and the following disclaimer in the documentation
25 // and/or other materials provided with the distribution.
26 //
27 // * The name of the copyright holders may not be used to endorse or promote products
28 // derived from this software without specific prior written permission.
29 //
30 // This software is provided by the copyright holders and contributors "as is" and
31 // any express or implied warranties, including, but not limited to, the implied
32 // warranties of merchantability and fitness for a particular purpose are disclaimed.
33 // In no event shall the Intel Corporation or contributors be liable for any direct,
34 // indirect, incidental, special, exemplary, or consequential damages
35 // (including, but not limited to, procurement of substitute goods or services;
36 // loss of use, data, or profits; or business interruption) however caused
37 // and on any theory of liability, whether in contract, strict liability,
38 // or tort (including negligence or otherwise) arising in any way out of
39 // the use of this software, even if advised of the possibility of such damage.
40 //
41 //M*/
42 
43 #ifndef __OPENCV_FEATURES_2D_HPP__
44 #define __OPENCV_FEATURES_2D_HPP__
45 
46 #include "opencv2/core/core.hpp"
47 #include "opencv2/flann/flann.hpp"
48 
49 #ifdef __cplusplus
50 #include <limits>
51 
52 extern "C" {
53 #endif
54 
55 typedef struct CvSURFPoint
56 {
58  int laplacian;
59  int size;
60  float dir;
61  float hessian;
62 } CvSURFPoint;
63 
65  int size, float dir CV_DEFAULT(0),
66  float hessian CV_DEFAULT(0))
67 {
68  CvSURFPoint kp;
69  kp.pt = pt;
70  kp.laplacian = laplacian;
71  kp.size = size;
72  kp.dir = dir;
73  kp.hessian = hessian;
74  return kp;
75 }
76 
77 typedef struct CvSURFParams
78 {
79  int extended;
81 
82  int nOctaves;
84 } CvSURFParams;
85 
86 CVAPI(CvSURFParams) cvSURFParams( double hessianThreshold, int extended CV_DEFAULT(0) );
87 
88 // If useProvidedKeyPts!=0, keypoints are not detected, but descriptors are computed
89 // at the locations provided in keypoints (a CvSeq of CvSURFPoint).
90 CVAPI(void) cvExtractSURF( const CvArr* img, const CvArr* mask,
91  CvSeq** keypoints, CvSeq** descriptors,
92  CvMemStorage* storage, CvSURFParams params, int useProvidedKeyPts CV_DEFAULT(0) );
93 
97 typedef struct CvMSERParams
98 {
100  int delta;
102  int maxArea;
104  int minArea;
109 
111 
117  double minMargin;
120 } CvMSERParams;
121 
122 CVAPI(CvMSERParams) cvMSERParams( int delta CV_DEFAULT(5), int min_area CV_DEFAULT(60),
123  int max_area CV_DEFAULT(14400), float max_variation CV_DEFAULT(.25f),
124  float min_diversity CV_DEFAULT(.2f), int max_evolution CV_DEFAULT(200),
125  double area_threshold CV_DEFAULT(1.01),
126  double min_margin CV_DEFAULT(.003),
127  int edge_blur_size CV_DEFAULT(5) );
128 
129 // Extracts the contours of Maximally Stable Extremal Regions
130 CVAPI(void) cvExtractMSER( CvArr* _img, CvArr* _mask, CvSeq** contours, CvMemStorage* storage, CvMSERParams params );
131 
132 
133 typedef struct CvStarKeypoint
134 {
136  int size;
137  float response;
139 
140 CV_INLINE CvStarKeypoint cvStarKeypoint(CvPoint pt, int size, float response)
141 {
142  CvStarKeypoint kpt;
143  kpt.pt = pt;
144  kpt.size = size;
145  kpt.response = response;
146  return kpt;
147 }
148 
149 typedef struct CvStarDetectorParams
150 {
151  int maxSize;
157 
159  int maxSize CV_DEFAULT(45),
160  int responseThreshold CV_DEFAULT(30),
161  int lineThresholdProjected CV_DEFAULT(10),
162  int lineThresholdBinarized CV_DEFAULT(8),
163  int suppressNonmaxSize CV_DEFAULT(5))
164 {
165  CvStarDetectorParams params;
166  params.maxSize = maxSize;
167  params.responseThreshold = responseThreshold;
168  params.lineThresholdProjected = lineThresholdProjected;
169  params.lineThresholdBinarized = lineThresholdBinarized;
170  params.suppressNonmaxSize = suppressNonmaxSize;
171 
172  return params;
173 }
174 
175 CVAPI(CvSeq*) cvGetStarKeypoints( const CvArr* img, CvMemStorage* storage,
177 
178 #ifdef __cplusplus
179 }
180 
181 namespace cv
182 {
184  {
186 
187  DefaultRngAuto() : old_state(theRNG().state) { theRNG().state = (uint64)-1; }
188  ~DefaultRngAuto() { theRNG().state = old_state; }
189 
190  DefaultRngAuto& operator=(const DefaultRngAuto&);
191  };
192 
193 
194 // CvAffinePose: defines a parameterized affine transformation of an image patch.
195 // An image patch is rotated on angle phi (in degrees), then scaled lambda1 times
196 // along horizontal and lambda2 times along vertical direction, and then rotated again
197 // on angle (theta - phi).
199 {
200 public:
201  float phi;
202  float theta;
203  float lambda1;
204  float lambda2;
205 };
206 
220 {
221 public:
223  CV_WRAP KeyPoint() : pt(0,0), size(0), angle(-1), response(0), octave(0), class_id(-1) {}
225  KeyPoint(Point2f _pt, float _size, float _angle=-1,
226  float _response=0, int _octave=0, int _class_id=-1)
227  : pt(_pt), size(_size), angle(_angle),
228  response(_response), octave(_octave), class_id(_class_id) {}
230  CV_WRAP KeyPoint(float x, float y, float _size, float _angle=-1,
231  float _response=0, int _octave=0, int _class_id=-1)
232  : pt(x, y), size(_size), angle(_angle),
233  response(_response), octave(_octave), class_id(_class_id) {}
235  static void convert(const std::vector<KeyPoint>& keypoints,
236  CV_OUT std::vector<Point2f>& points2f,
237  const std::vector<int>& keypointIndexes=std::vector<int>());
239  static void convert(const std::vector<Point2f>& points2f,
240  CV_OUT std::vector<KeyPoint>& keypoints,
241  float size=1, float response=1, int octave=0, int class_id=-1);
242 
246  static float overlap(const KeyPoint& kp1, const KeyPoint& kp2);
247 
249  CV_PROP_RW float size;
254 };
255 
257 CV_EXPORTS void write(FileStorage& fs, const string& name, const vector<KeyPoint>& keypoints);
259 CV_EXPORTS void read(const FileNode& node, CV_OUT vector<KeyPoint>& keypoints);
260 
267 {
268 public:
270  {
271  static const int DEFAULT_NOCTAVES = 4;
272  static const int DEFAULT_NOCTAVE_LAYERS = 3;
273  static const int DEFAULT_FIRST_OCTAVE = -1;
274  enum{ FIRST_ANGLE = 0, AVERAGE_ANGLE = 1 };
275 
276  CommonParams();
277  CommonParams( int _nOctaves, int _nOctaveLayers, int _firstOctave, int _angleMode );
278  int nOctaves, nOctaveLayers, firstOctave;
280  };
281 
283  {
284  static double GET_DEFAULT_THRESHOLD() { return 0.04 / SIFT::CommonParams::DEFAULT_NOCTAVE_LAYERS / 2.0; }
285  static double GET_DEFAULT_EDGE_THRESHOLD() { return 10.0; }
286 
287  DetectorParams();
288  DetectorParams( double _threshold, double _edgeThreshold );
289  double threshold, edgeThreshold;
290  };
291 
293  {
294  static double GET_DEFAULT_MAGNIFICATION() { return 3.0; }
295  static const bool DEFAULT_IS_NORMALIZE = true;
296  static const int DESCRIPTOR_SIZE = 128;
297 
299  DescriptorParams( double _magnification, bool _isNormalize, bool _recalculateAngles );
303  };
304 
305  SIFT();
307  SIFT( double _threshold, double _edgeThreshold,
308  int _nOctaves=CommonParams::DEFAULT_NOCTAVES,
309  int _nOctaveLayers=CommonParams::DEFAULT_NOCTAVE_LAYERS,
310  int _firstOctave=CommonParams::DEFAULT_FIRST_OCTAVE,
311  int _angleMode=CommonParams::FIRST_ANGLE );
313  SIFT( double _magnification, bool _isNormalize=true,
314  bool _recalculateAngles = true,
315  int _nOctaves=CommonParams::DEFAULT_NOCTAVES,
316  int _nOctaveLayers=CommonParams::DEFAULT_NOCTAVE_LAYERS,
317  int _firstOctave=CommonParams::DEFAULT_FIRST_OCTAVE,
318  int _angleMode=CommonParams::FIRST_ANGLE );
319  SIFT( const CommonParams& _commParams,
320  const DetectorParams& _detectorParams = DetectorParams(),
321  const DescriptorParams& _descriptorParams = DescriptorParams() );
322 
324  int descriptorSize() const { return DescriptorParams::DESCRIPTOR_SIZE; }
326  void operator()(const Mat& img, const Mat& mask,
327  vector<KeyPoint>& keypoints) const;
330  void operator()(const Mat& img, const Mat& mask,
331  vector<KeyPoint>& keypoints,
332  Mat& descriptors,
333  bool useProvidedKeypoints=false) const;
334 
335  CommonParams getCommonParams () const { return commParams; }
336  DetectorParams getDetectorParams () const { return detectorParams; }
337  DescriptorParams getDescriptorParams () const { return descriptorParams; }
338 protected:
342 };
343 
344 
351 {
352 public:
354  CV_WRAP SURF();
356  CV_WRAP SURF(double _hessianThreshold, int _nOctaves=4,
357  int _nOctaveLayers=2, bool _extended=false);
358 
360  CV_WRAP int descriptorSize() const;
362  CV_WRAP_AS(detect) void operator()(const Mat& img, const Mat& mask,
363  CV_OUT vector<KeyPoint>& keypoints) const;
365  CV_WRAP_AS(detect) void operator()(const Mat& img, const Mat& mask,
366  CV_OUT vector<KeyPoint>& keypoints,
367  CV_OUT vector<float>& descriptors,
368  bool useProvidedKeypoints=false) const;
369 };
370 
381 {
382 public:
384  CV_WRAP MSER();
386  CV_WRAP MSER( int _delta, int _min_area, int _max_area,
387  double _max_variation, double _min_diversity,
388  int _max_evolution, double _area_threshold,
389  double _min_margin, int _edge_blur_size );
391  CV_WRAP_AS(detect) void operator()( const Mat& image,
392  CV_OUT vector<vector<Point> >& msers, const Mat& mask ) const;
393 };
394 
401 {
402 public:
406  CV_WRAP StarDetector(int _maxSize, int _responseThreshold,
407  int _lineThresholdProjected,
408  int _lineThresholdBinarized,
409  int _suppressNonmaxSize);
411  CV_WRAP_AS(detect) void operator()(const Mat& image,
412  CV_OUT vector<KeyPoint>& keypoints) const;
413 };
414 
416 CV_EXPORTS void FAST( const Mat& image, CV_OUT vector<KeyPoint>& keypoints,
417  int threshold, bool nonmaxSupression=true );
418 
423 {
424 public:
425  PatchGenerator();
426  PatchGenerator(double _backgroundMin, double _backgroundMax,
427  double _noiseRange, bool _randomBlur=true,
428  double _lambdaMin=0.6, double _lambdaMax=1.5,
429  double _thetaMin=-CV_PI, double _thetaMax=CV_PI,
430  double _phiMin=-CV_PI, double _phiMax=CV_PI );
431  void operator()(const Mat& image, Point2f pt, Mat& patch, Size patchSize, RNG& rng) const;
432  void operator()(const Mat& image, const Mat& transform, Mat& patch,
433  Size patchSize, RNG& rng) const;
434  void warpWholeImage(const Mat& image, Mat& matT, Mat& buf,
435  CV_OUT Mat& warped, int border, RNG& rng) const;
436  void generateRandomTransform(Point2f srcCenter, Point2f dstCenter,
437  CV_OUT Mat& transform, RNG& rng,
438  bool inverse=false) const;
439  void setAffineParam(double lambda, double theta, double phi);
440 
441  double backgroundMin, backgroundMax;
442  double noiseRange;
444  double lambdaMin, lambdaMax;
445  double thetaMin, thetaMax;
446  double phiMin, phiMax;
447 };
448 
449 
451 {
452 public:
453  LDetector();
454  LDetector(int _radius, int _threshold, int _nOctaves,
455  int _nViews, double _baseFeatureSize, double _clusteringDistance);
456  void operator()(const Mat& image,
457  CV_OUT vector<KeyPoint>& keypoints,
458  int maxCount=0, bool scaleCoords=true) const;
459  void operator()(const vector<Mat>& pyr,
460  CV_OUT vector<KeyPoint>& keypoints,
461  int maxCount=0, bool scaleCoords=true) const;
462  void getMostStable2D(const Mat& image, CV_OUT vector<KeyPoint>& keypoints,
463  int maxCount, const PatchGenerator& patchGenerator) const;
464  void setVerbose(bool verbose);
465 
466  void read(const FileNode& node);
467  void write(FileStorage& fs, const String& name=String()) const;
468 
469  int radius;
471  int nOctaves;
472  int nViews;
473  bool verbose;
474 
477 };
478 
479 typedef LDetector YAPE;
480 
482 {
483 public:
484  FernClassifier();
485  FernClassifier(const FileNode& node);
486  FernClassifier(const vector<vector<Point2f> >& points,
487  const vector<Mat>& refimgs,
488  const vector<vector<int> >& labels=vector<vector<int> >(),
489  int _nclasses=0, int _patchSize=PATCH_SIZE,
490  int _signatureSize=DEFAULT_SIGNATURE_SIZE,
491  int _nstructs=DEFAULT_STRUCTS,
492  int _structSize=DEFAULT_STRUCT_SIZE,
493  int _nviews=DEFAULT_VIEWS,
494  int _compressionMethod=COMPRESSION_NONE,
495  const PatchGenerator& patchGenerator=PatchGenerator());
496  virtual ~FernClassifier();
497  virtual void read(const FileNode& n);
498  virtual void write(FileStorage& fs, const String& name=String()) const;
499  virtual void trainFromSingleView(const Mat& image,
500  const vector<KeyPoint>& keypoints,
501  int _patchSize=PATCH_SIZE,
502  int _signatureSize=DEFAULT_SIGNATURE_SIZE,
503  int _nstructs=DEFAULT_STRUCTS,
504  int _structSize=DEFAULT_STRUCT_SIZE,
505  int _nviews=DEFAULT_VIEWS,
506  int _compressionMethod=COMPRESSION_NONE,
507  const PatchGenerator& patchGenerator=PatchGenerator());
508  virtual void train(const vector<vector<Point2f> >& points,
509  const vector<Mat>& refimgs,
510  const vector<vector<int> >& labels=vector<vector<int> >(),
511  int _nclasses=0, int _patchSize=PATCH_SIZE,
512  int _signatureSize=DEFAULT_SIGNATURE_SIZE,
513  int _nstructs=DEFAULT_STRUCTS,
514  int _structSize=DEFAULT_STRUCT_SIZE,
515  int _nviews=DEFAULT_VIEWS,
516  int _compressionMethod=COMPRESSION_NONE,
517  const PatchGenerator& patchGenerator=PatchGenerator());
518  virtual int operator()(const Mat& img, Point2f kpt, vector<float>& signature) const;
519  virtual int operator()(const Mat& patch, vector<float>& signature) const;
520  virtual void clear();
521  void setVerbose(bool verbose);
522 
523  int getClassCount() const;
524  int getStructCount() const;
525  int getStructSize() const;
526  int getSignatureSize() const;
527  int getCompressionMethod() const;
528  Size getPatchSize() const;
529 
530  struct Feature
531  {
532  uchar x1, y1, x2, y2;
533  Feature() : x1(0), y1(0), x2(0), y2(0) {}
534  Feature(int _x1, int _y1, int _x2, int _y2)
535  : x1((uchar)_x1), y1((uchar)_y1), x2((uchar)_x2), y2((uchar)_y2)
536  {}
537  template<typename _Tp> bool operator ()(const Mat_<_Tp>& patch) const
538  { return patch(y1,x1) > patch(y2, x2); }
539  };
540 
541  enum
542  {
543  PATCH_SIZE = 31,
544  DEFAULT_STRUCTS = 50,
545  DEFAULT_STRUCT_SIZE = 9,
546  DEFAULT_VIEWS = 5000,
547  DEFAULT_SIGNATURE_SIZE = 176,
548  COMPRESSION_NONE = 0,
549  COMPRESSION_RANDOM_PROJ = 1,
550  COMPRESSION_PCA = 2,
551  DEFAULT_COMPRESSION_METHOD = COMPRESSION_NONE
552  };
553 
554 protected:
555  virtual void prepare(int _nclasses, int _patchSize, int _signatureSize,
556  int _nstructs, int _structSize,
557  int _nviews, int _compressionMethod);
558  virtual void finalize(RNG& rng);
559  virtual int getLeaf(int fidx, const Mat& patch) const;
560 
561  bool verbose;
562  int nstructs;
564  int nclasses;
569  vector<Feature> features;
570  vector<int> classCounters;
571  vector<float> posteriors;
572 };
573 
574 
576 {
577 public:
579  PlanarObjectDetector(const FileNode& node);
580  PlanarObjectDetector(const vector<Mat>& pyr, int _npoints=300,
581  int _patchSize=FernClassifier::PATCH_SIZE,
582  int _nstructs=FernClassifier::DEFAULT_STRUCTS,
583  int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
584  int _nviews=FernClassifier::DEFAULT_VIEWS,
585  const LDetector& detector=LDetector(),
586  const PatchGenerator& patchGenerator=PatchGenerator());
587  virtual ~PlanarObjectDetector();
588  virtual void train(const vector<Mat>& pyr, int _npoints=300,
589  int _patchSize=FernClassifier::PATCH_SIZE,
590  int _nstructs=FernClassifier::DEFAULT_STRUCTS,
591  int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
592  int _nviews=FernClassifier::DEFAULT_VIEWS,
593  const LDetector& detector=LDetector(),
594  const PatchGenerator& patchGenerator=PatchGenerator());
595  virtual void train(const vector<Mat>& pyr, const vector<KeyPoint>& keypoints,
596  int _patchSize=FernClassifier::PATCH_SIZE,
597  int _nstructs=FernClassifier::DEFAULT_STRUCTS,
598  int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
599  int _nviews=FernClassifier::DEFAULT_VIEWS,
600  const LDetector& detector=LDetector(),
601  const PatchGenerator& patchGenerator=PatchGenerator());
602  Rect getModelROI() const;
603  vector<KeyPoint> getModelPoints() const;
604  const LDetector& getDetector() const;
605  const FernClassifier& getClassifier() const;
606  void setVerbose(bool verbose);
607 
608  void read(const FileNode& node);
609  void write(FileStorage& fs, const String& name=String()) const;
610  bool operator()(const Mat& image, CV_OUT Mat& H, CV_OUT vector<Point2f>& corners) const;
611  bool operator()(const vector<Mat>& pyr, const vector<KeyPoint>& keypoints,
612  CV_OUT Mat& H, CV_OUT vector<Point2f>& corners,
613  CV_OUT vector<int>* pairs=0) const;
614 
615 protected:
616  bool verbose;
618  vector<KeyPoint> modelPoints;
621 };
622 
623 /****************************************************************************************\
624 * Calonder Classifier *
625 \****************************************************************************************/
626 
627 struct RTreeNode;
628 
630 {
631  int x;
632  int y;
634 
636  : x(0), y(0), image(NULL)
637  {}
638 
639  BaseKeypoint(int x, int y, IplImage* image)
640  : x(x), y(y), image(image)
641  {}
642 };
643 
645 {
646 public:
647  friend class RTreeClassifier;
648 
649  static const uchar PATCH_SIZE = 32;
650  static const int DEFAULT_DEPTH = 9;
651  static const int DEFAULT_VIEWS = 5000;
652  static const size_t DEFAULT_REDUCED_NUM_DIM = 176;
653  static float GET_LOWER_QUANT_PERC() { return .03f; }
654  static float GET_UPPER_QUANT_PERC() { return .92f; }
655 
656  RandomizedTree();
657  ~RandomizedTree();
658 
659  void train(std::vector<BaseKeypoint> const& base_set, RNG &rng,
660  int depth, int views, size_t reduced_num_dim, int num_quant_bits);
661  void train(std::vector<BaseKeypoint> const& base_set, RNG &rng,
662  PatchGenerator &make_patch, int depth, int views, size_t reduced_num_dim,
663  int num_quant_bits);
664 
665  // following two funcs are EXPERIMENTAL (do not use unless you know exactly what you do)
666  static void quantizeVector(float *vec, int dim, int N, float bnds[2], int clamp_mode=0);
667  static void quantizeVector(float *src, int dim, int N, float bnds[2], uchar *dst);
668 
669  // patch_data must be a 32x32 array (no row padding)
670  float* getPosterior(uchar* patch_data);
671  const float* getPosterior(uchar* patch_data) const;
672  uchar* getPosterior2(uchar* patch_data);
673  const uchar* getPosterior2(uchar* patch_data) const;
674 
675  void read(const char* file_name, int num_quant_bits);
676  void read(std::istream &is, int num_quant_bits);
677  void write(const char* file_name) const;
678  void write(std::ostream &os) const;
679 
680  int classes() { return classes_; }
681  int depth() { return depth_; }
682 
683  //void setKeepFloatPosteriors(bool b) { keep_float_posteriors_ = b; }
684  void discardFloatPosteriors() { freePosteriors(1); }
685 
686  inline void applyQuantization(int num_quant_bits) { makePosteriors2(num_quant_bits); }
687 
688  // debug
689  void savePosteriors(std::string url, bool append=false);
690  void savePosteriors2(std::string url, bool append=false);
691 
692 private:
693  int classes_;
694  int depth_;
695  int num_leaves_;
696  std::vector<RTreeNode> nodes_;
697  float **posteriors_; // 16-bytes aligned posteriors
698  uchar **posteriors2_; // 16-bytes aligned posteriors
699  std::vector<int> leaf_counts_;
700 
701  void createNodes(int num_nodes, RNG &rng);
702  void allocPosteriorsAligned(int num_leaves, int num_classes);
703  void freePosteriors(int which); // which: 1=posteriors_, 2=posteriors2_, 3=both
704  void init(int classes, int depth, RNG &rng);
705  void addExample(int class_id, uchar* patch_data);
706  void finalize(size_t reduced_num_dim, int num_quant_bits);
707  int getIndex(uchar* patch_data) const;
708  inline float* getPosteriorByIndex(int index);
709  inline const float* getPosteriorByIndex(int index) const;
710  inline uchar* getPosteriorByIndex2(int index);
711  inline const uchar* getPosteriorByIndex2(int index) const;
712  //void makeRandomMeasMatrix(float *cs_phi, PHI_DISTR_TYPE dt, size_t reduced_num_dim);
713  void convertPosteriorsToChar();
714  void makePosteriors2(int num_quant_bits);
715  void compressLeaves(size_t reduced_num_dim);
716  void estimateQuantPercForPosteriors(float perc[2]);
717 };
718 
719 
720 inline uchar* getData(IplImage* image)
721 {
722  return reinterpret_cast<uchar*>(image->imageData);
723 }
724 
725 inline float* RandomizedTree::getPosteriorByIndex(int index)
726 {
727  return const_cast<float*>(const_cast<const RandomizedTree*>(this)->getPosteriorByIndex(index));
728 }
729 
730 inline const float* RandomizedTree::getPosteriorByIndex(int index) const
731 {
732  return posteriors_[index];
733 }
734 
735 inline uchar* RandomizedTree::getPosteriorByIndex2(int index)
736 {
737  return const_cast<uchar*>(const_cast<const RandomizedTree*>(this)->getPosteriorByIndex2(index));
738 }
739 
740 inline const uchar* RandomizedTree::getPosteriorByIndex2(int index) const
741 {
742  return posteriors2_[index];
743 }
744 
746 {
747  short offset1, offset2;
748 
750  RTreeNode(uchar x1, uchar y1, uchar x2, uchar y2)
751  : offset1(y1*RandomizedTree::PATCH_SIZE + x1),
752  offset2(y2*RandomizedTree::PATCH_SIZE + x2)
753  {}
754 
756  inline bool operator() (uchar* patch_data) const
757  {
758  return patch_data[offset1] > patch_data[offset2];
759  }
760 };
761 
763 {
764 public:
765  static const int DEFAULT_TREES = 48;
766  static const size_t DEFAULT_NUM_QUANT_BITS = 4;
767 
768  RTreeClassifier();
769  void train(std::vector<BaseKeypoint> const& base_set,
770  RNG &rng,
771  int num_trees = RTreeClassifier::DEFAULT_TREES,
772  int depth = RandomizedTree::DEFAULT_DEPTH,
773  int views = RandomizedTree::DEFAULT_VIEWS,
774  size_t reduced_num_dim = RandomizedTree::DEFAULT_REDUCED_NUM_DIM,
775  int num_quant_bits = DEFAULT_NUM_QUANT_BITS);
776  void train(std::vector<BaseKeypoint> const& base_set,
777  RNG &rng,
778  PatchGenerator &make_patch,
779  int num_trees = RTreeClassifier::DEFAULT_TREES,
780  int depth = RandomizedTree::DEFAULT_DEPTH,
781  int views = RandomizedTree::DEFAULT_VIEWS,
782  size_t reduced_num_dim = RandomizedTree::DEFAULT_REDUCED_NUM_DIM,
783  int num_quant_bits = DEFAULT_NUM_QUANT_BITS);
784 
785  // sig must point to a memory block of at least classes()*sizeof(float|uchar) bytes
786  void getSignature(IplImage *patch, uchar *sig) const;
787  void getSignature(IplImage *patch, float *sig) const;
788  void getSparseSignature(IplImage *patch, float *sig, float thresh) const;
789  // TODO: deprecated in favor of getSignature overload, remove
790  void getFloatSignature(IplImage *patch, float *sig) const { getSignature(patch, sig); }
791 
792  static int countNonZeroElements(float *vec, int n, double tol=1e-10);
793  static inline void safeSignatureAlloc(uchar **sig, int num_sig=1, int sig_len=176);
794  static inline uchar* safeSignatureAlloc(int num_sig=1, int sig_len=176);
795 
796  inline int classes() const { return classes_; }
797  inline int original_num_classes() const { return original_num_classes_; }
798 
799  void setQuantization(int num_quant_bits);
800  void discardFloatPosteriors();
801 
802  void read(const char* file_name);
803  void read(std::istream &is);
804  void write(const char* file_name) const;
805  void write(std::ostream &os) const;
806 
807  // experimental and debug
808  void saveAllFloatPosteriors(std::string file_url);
809  void saveAllBytePosteriors(std::string file_url);
810  void setFloatPosteriorsFromTextfile_176(std::string url);
811  float countZeroElements();
812 
813  std::vector<RandomizedTree> trees_;
814 
815 private:
816  int classes_;
817  int num_quant_bits_;
818  mutable uchar **posteriors_;
819  mutable unsigned short *ptemp_;
820  int original_num_classes_;
821  bool keep_floats_;
822 };
823 
824 /****************************************************************************************\
825 * One-Way Descriptor *
826 \****************************************************************************************/
827 
829 {
830 public:
832  ~OneWayDescriptor();
833 
834  // allocates memory for given descriptor parameters
835  void Allocate(int pose_count, CvSize size, int nChannels);
836 
837  // GenerateSamples: generates affine transformed patches with averaging them over small transformation variations.
838  // If external poses and transforms were specified, uses them instead of generating random ones
839  // - pose_count: the number of poses to be generated
840  // - frontal: the input patch (can be a roi in a larger image)
841  // - norm: if nonzero, normalizes the output patch so that the sum of pixel intensities is 1
842  void GenerateSamples(int pose_count, IplImage* frontal, int norm = 0);
843 
844  // GenerateSamplesFast: generates affine transformed patches with averaging them over small transformation variations.
845  // Uses precalculated transformed pca components.
846  // - frontal: the input patch (can be a roi in a larger image)
847  // - pca_hr_avg: pca average vector
848  // - pca_hr_eigenvectors: pca eigenvectors
849  // - pca_descriptors: an array of precomputed descriptors of pca components containing their affine transformations
850  // pca_descriptors[0] corresponds to the average, pca_descriptors[1]-pca_descriptors[pca_dim] correspond to eigenvectors
851  void GenerateSamplesFast(IplImage* frontal, CvMat* pca_hr_avg,
852  CvMat* pca_hr_eigenvectors, OneWayDescriptor* pca_descriptors);
853 
854  // sets the poses and corresponding transforms
855  void SetTransforms(CvAffinePose* poses, CvMat** transforms);
856 
857  // Initialize: builds a descriptor.
858  // - pose_count: the number of poses to build. If poses were set externally, uses them rather than generating random ones
859  // - frontal: input patch. Can be a roi in a larger image
860  // - feature_name: the feature name to be associated with the descriptor
861  // - norm: if 1, the affine transformed patches are normalized so that their sum is 1
862  void Initialize(int pose_count, IplImage* frontal, const char* feature_name = 0, int norm = 0);
863 
864  // InitializeFast: builds a descriptor using precomputed descriptors of pca components
865  // - pose_count: the number of poses to build
866  // - frontal: input patch. Can be a roi in a larger image
867  // - feature_name: the feature name to be associated with the descriptor
868  // - pca_hr_avg: average vector for PCA
869  // - pca_hr_eigenvectors: PCA eigenvectors (one vector per row)
870  // - pca_descriptors: precomputed descriptors of PCA components, the first descriptor for the average vector
871  // followed by the descriptors for eigenvectors
872  void InitializeFast(int pose_count, IplImage* frontal, const char* feature_name,
873  CvMat* pca_hr_avg, CvMat* pca_hr_eigenvectors, OneWayDescriptor* pca_descriptors);
874 
875  // ProjectPCASample: unwarps an image patch into a vector and projects it into PCA space
876  // - patch: input image patch
877  // - avg: PCA average vector
878  // - eigenvectors: PCA eigenvectors, one per row
879  // - pca_coeffs: output PCA coefficients
880  void ProjectPCASample(IplImage* patch, CvMat* avg, CvMat* eigenvectors, CvMat* pca_coeffs) const;
881 
882  // InitializePCACoeffs: projects all warped patches into PCA space
883  // - avg: PCA average vector
884  // - eigenvectors: PCA eigenvectors, one per row
885  void InitializePCACoeffs(CvMat* avg, CvMat* eigenvectors);
886 
887  // EstimatePose: finds the closest match between an input patch and a set of patches with different poses
888  // - patch: input image patch
889  // - pose_idx: the output index of the closest pose
890  // - distance: the distance to the closest pose (L2 distance)
891  void EstimatePose(IplImage* patch, int& pose_idx, float& distance) const;
892 
893  // EstimatePosePCA: finds the closest match between an input patch and a set of patches with different poses.
894  // The distance between patches is computed in PCA space
895  // - patch: input image patch
896  // - pose_idx: the output index of the closest pose
897  // - distance: distance to the closest pose (L2 distance in PCA space)
898  // - avg: PCA average vector. If 0, matching without PCA is used
899  // - eigenvectors: PCA eigenvectors, one per row
900  void EstimatePosePCA(CvArr* patch, int& pose_idx, float& distance, CvMat* avg, CvMat* eigenvalues) const;
901 
902  // GetPatchSize: returns the size of each image patch after warping (2 times smaller than the input patch)
903  CvSize GetPatchSize() const
904  {
905  return m_patch_size;
906  }
907 
908  // GetInputPatchSize: returns the required size of the patch that the descriptor is built from
909  // (2 time larger than the patch after warping)
910  CvSize GetInputPatchSize() const
911  {
912  return cvSize(m_patch_size.width*2, m_patch_size.height*2);
913  }
914 
915  // GetPatch: returns a patch corresponding to specified pose index
916  // - index: pose index
917  // - return value: the patch corresponding to specified pose index
918  IplImage* GetPatch(int index);
919 
920  // GetPose: returns a pose corresponding to specified pose index
921  // - index: pose index
922  // - return value: the pose corresponding to specified pose index
923  CvAffinePose GetPose(int index) const;
924 
925  // Save: saves all patches with different poses to a specified path
926  void Save(const char* path);
927 
928  // ReadByName: reads a descriptor from a file storage
929  // - fs: file storage
930  // - parent: parent node
931  // - name: node name
932  // - return value: 1 if succeeded, 0 otherwise
933  int ReadByName(CvFileStorage* fs, CvFileNode* parent, const char* name);
934 
935  // ReadByName: reads a descriptor from a file node
936  // - parent: parent node
937  // - name: node name
938  // - return value: 1 if succeeded, 0 otherwise
939  int ReadByName(const FileNode &parent, const char* name);
940 
941  // Write: writes a descriptor into a file storage
942  // - fs: file storage
943  // - name: node name
944  void Write(CvFileStorage* fs, const char* name);
945 
946  // GetFeatureName: returns a name corresponding to a feature
947  const char* GetFeatureName() const;
948 
949  // GetCenter: returns the center of the feature
950  CvPoint GetCenter() const;
951 
952  void SetPCADimHigh(int pca_dim_high) {m_pca_dim_high = pca_dim_high;};
953  void SetPCADimLow(int pca_dim_low) {m_pca_dim_low = pca_dim_low;};
954 
955  int GetPCADimLow() const;
956  int GetPCADimHigh() const;
957 
958  CvMat** GetPCACoeffs() const {return m_pca_coeffs;}
959 
960 protected:
961  int m_pose_count; // the number of poses
962  CvSize m_patch_size; // size of each image
963  IplImage** m_samples; // an array of length m_pose_count containing the patch in different poses
966  CvMat** m_pca_coeffs; // an array of length m_pose_count containing pca decomposition of the patch in different poses
967  CvAffinePose* m_affine_poses; // an array of poses
968  CvMat** m_transforms; // an array of affine transforms corresponding to poses
969 
970  string m_feature_name; // the name of the feature associated with the descriptor
971  CvPoint m_center; // the coordinates of the feature (the center of the input image ROI)
972 
973  int m_pca_dim_high; // the number of descriptor pca components to use for generating affine poses
974  int m_pca_dim_low; // the number of pca components to use for comparison
975 };
976 
977 
978 // OneWayDescriptorBase: encapsulates functionality for training/loading a set of one way descriptors
979 // and finding the nearest closest descriptor to an input feature
981 {
982 public:
983 
984  // creates an instance of OneWayDescriptor from a set of training files
985  // - patch_size: size of the input (large) patch
986  // - pose_count: the number of poses to generate for each descriptor
987  // - train_path: path to training files
988  // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
989  // than patch_size each dimension
990  // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
991  // - pca_desc_config: the name of the file that contains descriptors of PCA components
992  OneWayDescriptorBase(CvSize patch_size, int pose_count, const char* train_path = 0, const char* pca_config = 0,
993  const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1,
994  int pca_dim_high = 100, int pca_dim_low = 100);
995 
996  OneWayDescriptorBase(CvSize patch_size, int pose_count, const string &pca_filename, const string &train_path = string(), const string &images_list = string(),
997  float _scale_min = 0.7f, float _scale_max=1.5f, float _scale_step=1.2f, int pyr_levels = 1,
998  int pca_dim_high = 100, int pca_dim_low = 100);
999 
1000 
1001  virtual ~OneWayDescriptorBase();
1002  void clear ();
1003 
1004 
1005  // Allocate: allocates memory for a given number of descriptors
1006  void Allocate(int train_feature_count);
1007 
1008  // AllocatePCADescriptors: allocates memory for pca descriptors
1009  void AllocatePCADescriptors();
1010 
1011  // returns patch size
1012  CvSize GetPatchSize() const {return m_patch_size;};
1013  // returns the number of poses for each descriptor
1014  int GetPoseCount() const {return m_pose_count;};
1015 
1016  // returns the number of pyramid levels
1017  int GetPyrLevels() const {return m_pyr_levels;};
1018 
1019  // returns the number of descriptors
1020  int GetDescriptorCount() const {return m_train_feature_count;};
1021 
1022  // CreateDescriptorsFromImage: creates descriptors for each of the input features
1023  // - src: input image
1024  // - features: input features
1025  // - pyr_levels: the number of pyramid levels
1026  void CreateDescriptorsFromImage(IplImage* src, const std::vector<cv::KeyPoint>& features);
1027 
1028  // CreatePCADescriptors: generates descriptors for PCA components, needed for fast generation of feature descriptors
1029  void CreatePCADescriptors();
1030 
1031  // returns a feature descriptor by feature index
1032  const OneWayDescriptor* GetDescriptor(int desc_idx) const {return &m_descriptors[desc_idx];};
1033 
1034  // FindDescriptor: finds the closest descriptor
1035  // - patch: input image patch
1036  // - desc_idx: output index of the closest descriptor to the input patch
1037  // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
1038  // - distance: distance from the input patch to the closest feature pose
1039  // - _scales: scales of the input patch for each descriptor
1040  // - scale_ranges: input scales variation (float[2])
1041  void FindDescriptor(IplImage* patch, int& desc_idx, int& pose_idx, float& distance, float* _scale = 0, float* scale_ranges = 0) const;
1042 
1043  // - patch: input image patch
1044  // - n: number of the closest indexes
1045  // - desc_idxs: output indexes of the closest descriptor to the input patch (n)
1046  // - pose_idx: output indexes of the closest pose of the closest descriptor to the input patch (n)
1047  // - distances: distance from the input patch to the closest feature pose (n)
1048  // - _scales: scales of the input patch
1049  // - scale_ranges: input scales variation (float[2])
1050  void FindDescriptor(IplImage* patch, int n, std::vector<int>& desc_idxs, std::vector<int>& pose_idxs,
1051  std::vector<float>& distances, std::vector<float>& _scales, float* scale_ranges = 0) const;
1052 
1053  // FindDescriptor: finds the closest descriptor
1054  // - src: input image
1055  // - pt: center of the feature
1056  // - desc_idx: output index of the closest descriptor to the input patch
1057  // - pose_idx: output index of the closest pose of the closest descriptor to the input patch
1058  // - distance: distance from the input patch to the closest feature pose
1059  void FindDescriptor(IplImage* src, cv::Point2f pt, int& desc_idx, int& pose_idx, float& distance) const;
1060 
1061  // InitializePoses: generates random poses
1062  void InitializePoses();
1063 
1064  // InitializeTransformsFromPoses: generates 2x3 affine matrices from poses (initializes m_transforms)
1065  void InitializeTransformsFromPoses();
1066 
1067  // InitializePoseTransforms: subsequently calls InitializePoses and InitializeTransformsFromPoses
1068  void InitializePoseTransforms();
1069 
1070  // InitializeDescriptor: initializes a descriptor
1071  // - desc_idx: descriptor index
1072  // - train_image: image patch (ROI is supported)
1073  // - feature_label: feature textual label
1074  void InitializeDescriptor(int desc_idx, IplImage* train_image, const char* feature_label);
1075 
1076  void InitializeDescriptor(int desc_idx, IplImage* train_image, const cv::KeyPoint& keypoint, const char* feature_label);
1077 
1078  // InitializeDescriptors: load features from an image and create descriptors for each of them
1079  void InitializeDescriptors(IplImage* train_image, const vector<cv::KeyPoint>& features,
1080  const char* feature_label = "", int desc_start_idx = 0);
1081 
1082  // Write: writes this object to a file storage
1083  // - fs: output filestorage
1084  void Write (FileStorage &fs) const;
1085 
1086  // Read: reads OneWayDescriptorBase object from a file node
1087  // - fn: input file node
1088  void Read (const FileNode &fn);
1089 
1090  // LoadPCADescriptors: loads PCA descriptors from a file
1091  // - filename: input filename
1092  int LoadPCADescriptors(const char* filename);
1093 
1094  // LoadPCADescriptors: loads PCA descriptors from a file node
1095  // - fn: input file node
1096  int LoadPCADescriptors(const FileNode &fn);
1097 
1098  // SavePCADescriptors: saves PCA descriptors to a file
1099  // - filename: output filename
1100  void SavePCADescriptors(const char* filename);
1101 
1102  // SavePCADescriptors: saves PCA descriptors to a file storage
1103  // - fs: output file storage
1104  void SavePCADescriptors(CvFileStorage* fs) const;
1105 
1106  // GeneratePCA: calculate and save PCA components and descriptors
1107  // - img_path: path to training PCA images directory
1108  // - images_list: filename with filenames of training PCA images
1109  void GeneratePCA(const char* img_path, const char* images_list, int pose_count=500);
1110 
1111  // SetPCAHigh: sets the high resolution pca matrices (copied to internal structures)
1112  void SetPCAHigh(CvMat* avg, CvMat* eigenvectors);
1113 
1114  // SetPCALow: sets the low resolution pca matrices (copied to internal structures)
1115  void SetPCALow(CvMat* avg, CvMat* eigenvectors);
1116 
1117  int GetLowPCA(CvMat** avg, CvMat** eigenvectors)
1118  {
1119  *avg = m_pca_avg;
1120  *eigenvectors = m_pca_eigenvectors;
1121  return m_pca_dim_low;
1122  };
1123 
1124  int GetPCADimLow() const {return m_pca_dim_low;};
1125  int GetPCADimHigh() const {return m_pca_dim_high;};
1126 
1127  void ConvertDescriptorsArrayToTree(); // Converting pca_descriptors array to KD tree
1128 
1129  // GetPCAFilename: get default PCA filename
1130  static string GetPCAFilename () { return "pca.yml"; }
1131 
1132 protected:
1133  CvSize m_patch_size; // patch size
1134  int m_pose_count; // the number of poses for each descriptor
1135  int m_train_feature_count; // the number of the training features
1136  OneWayDescriptor* m_descriptors; // array of train feature descriptors
1137  CvMat* m_pca_avg; // PCA average Vector for small patches
1138  CvMat* m_pca_eigenvectors; // PCA eigenvectors for small patches
1139  CvMat* m_pca_hr_avg; // PCA average Vector for large patches
1140  CvMat* m_pca_hr_eigenvectors; // PCA eigenvectors for large patches
1141  OneWayDescriptor* m_pca_descriptors; // an array of PCA descriptors
1142 
1143  cv::flann::Index* m_pca_descriptors_tree;
1145 
1146  CvAffinePose* m_poses; // array of poses
1147  CvMat** m_transforms; // array of affine transformations corresponding to poses
1148 
1151 
1153  float scale_min;
1154  float scale_max;
1155  float scale_step;
1156 
1157  // SavePCAall: saves PCA components and descriptors to a file storage
1158  // - fs: output file storage
1159  void SavePCAall (FileStorage &fs) const;
1160 
1161  // LoadPCAall: loads PCA components and descriptors from a file node
1162  // - fn: input file node
1163  void LoadPCAall (const FileNode &fn);
1164 };
1165 
1167 {
1168 public:
1169  // creates an instance of OneWayDescriptorObject from a set of training files
1170  // - patch_size: size of the input (large) patch
1171  // - pose_count: the number of poses to generate for each descriptor
1172  // - train_path: path to training files
1173  // - pca_config: the name of the file that contains PCA for small patches (2 times smaller
1174  // than patch_size each dimension
1175  // - pca_hr_config: the name of the file that contains PCA for large patches (of patch_size size)
1176  // - pca_desc_config: the name of the file that contains descriptors of PCA components
1177  OneWayDescriptorObject(CvSize patch_size, int pose_count, const char* train_path, const char* pca_config,
1178  const char* pca_hr_config = 0, const char* pca_desc_config = 0, int pyr_levels = 1);
1179 
1180  OneWayDescriptorObject(CvSize patch_size, int pose_count, const string &pca_filename,
1181  const string &train_path = string (), const string &images_list = string (),
1182  float _scale_min = 0.7f, float _scale_max=1.5f, float _scale_step=1.2f, int pyr_levels = 1);
1183 
1184 
1185  virtual ~OneWayDescriptorObject();
1186 
1187  // Allocate: allocates memory for a given number of features
1188  // - train_feature_count: the total number of features
1189  // - object_feature_count: the number of features extracted from the object
1190  void Allocate(int train_feature_count, int object_feature_count);
1191 
1192 
1193  void SetLabeledFeatures(const vector<cv::KeyPoint>& features) {m_train_features = features;};
1194  vector<cv::KeyPoint>& GetLabeledFeatures() {return m_train_features;};
1195  const vector<cv::KeyPoint>& GetLabeledFeatures() const {return m_train_features;};
1196  vector<cv::KeyPoint> _GetLabeledFeatures() const;
1197 
1198  // IsDescriptorObject: returns 1 if descriptor with specified index is positive, otherwise 0
1199  int IsDescriptorObject(int desc_idx) const;
1200 
1201  // MatchPointToPart: returns the part number of a feature if it matches one of the object parts, otherwise -1
1202  int MatchPointToPart(CvPoint pt) const;
1203 
1204  // GetDescriptorPart: returns the part number of the feature corresponding to a specified descriptor
1205  // - desc_idx: descriptor index
1206  int GetDescriptorPart(int desc_idx) const;
1207 
1208 
1209  void InitializeObjectDescriptors(IplImage* train_image, const vector<cv::KeyPoint>& features,
1210  const char* feature_label, int desc_start_idx = 0, float scale = 1.0f,
1211  int is_background = 0);
1212 
1213  // GetObjectFeatureCount: returns the number of object features
1214  int GetObjectFeatureCount() const {return m_object_feature_count;};
1215 
1216 protected:
1217  int* m_part_id; // contains part id for each of object descriptors
1218  vector<cv::KeyPoint> m_train_features; // train features
1219  int m_object_feature_count; // the number of the positive features
1220 
1221 };
1222 
1223 
1224 /****************************************************************************************\
1225 * FeatureDetector *
1226 \****************************************************************************************/
1227 
1228 /*
1229  * Abstract base class for 2D image feature detectors.
1230  */
1232 {
1233 public:
1234  virtual ~FeatureDetector();
1235 
1236  /*
1237  * Detect keypoints in an image.
1238  * image The image.
1239  * keypoints The detected keypoints.
1240  * mask Mask specifying where to look for keypoints (optional). Must be a char
1241  * matrix with non-zero values in the region of interest.
1242  */
1243  void detect( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1244 
1245  /*
1246  * Detect keypoints in an image set.
1247  * images Image collection.
1248  * keypoints Collection of keypoints detected in an input images. keypoints[i] is a set of keypoints detected in an images[i].
1249  * masks Masks for image set. masks[i] is a mask for images[i].
1250  */
1251  void detect( const vector<Mat>& images, vector<vector<KeyPoint> >& keypoints, const vector<Mat>& masks=vector<Mat>() ) const;
1252 
1253  // Read detector object from a file node.
1254  virtual void read( const FileNode& );
1255  // Read detector object from a file node.
1256  virtual void write( FileStorage& ) const;
1257 
1258  // Create feature detector by detector name.
1259  static Ptr<FeatureDetector> create( const string& detectorType );
1260 
1261 protected:
1262  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const = 0;
1263  /*
1264  * Remove keypoints that are not in the mask.
1265  * Helper function, useful when wrapping a library call for keypoint detection that
1266  * does not support a mask argument.
1267  */
1268  static void removeInvalidPoints( const Mat& mask, vector<KeyPoint>& keypoints );
1269 };
1270 
1272 {
1273 public:
1274  FastFeatureDetector( int threshold=10, bool nonmaxSuppression=true );
1275  virtual void read( const FileNode& fn );
1276  virtual void write( FileStorage& fs ) const;
1277 
1278 protected:
1279  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1280 
1283 };
1284 
1285 
1287 {
1288 public:
1290  {
1291  public:
1292  Params( int maxCorners=1000, double qualityLevel=0.01, double minDistance=1.,
1293  int blockSize=3, bool useHarrisDetector=false, double k=0.04 );
1294  void read( const FileNode& fn );
1295  void write( FileStorage& fs ) const;
1296 
1299  double minDistance;
1302  double k;
1303  };
1304 
1306  GoodFeaturesToTrackDetector( int maxCorners, double qualityLevel, double minDistance,
1307  int blockSize=3, bool useHarrisDetector=false, double k=0.04 );
1308  virtual void read( const FileNode& fn );
1309  virtual void write( FileStorage& fs ) const;
1310 
1311 protected:
1312  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1313 
1315 };
1316 
1318 {
1319 public:
1321  MserFeatureDetector( int delta, int minArea, int maxArea, double maxVariation, double minDiversity,
1322  int maxEvolution, double areaThreshold, double minMargin, int edgeBlurSize );
1323  virtual void read( const FileNode& fn );
1324  virtual void write( FileStorage& fs ) const;
1325 
1326 protected:
1327  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1328 
1330 };
1331 
1333 {
1334 public:
1336  StarFeatureDetector( int maxSize, int responseThreshold=30, int lineThresholdProjected = 10,
1337  int lineThresholdBinarized=8, int suppressNonmaxSize=5 );
1338  virtual void read( const FileNode& fn );
1339  virtual void write( FileStorage& fs ) const;
1340 
1341 protected:
1342  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1343 
1345 };
1346 
1348 {
1349 public:
1351  const SIFT::CommonParams& commonParams=SIFT::CommonParams() );
1352  SiftFeatureDetector( double threshold, double edgeThreshold,
1356  int angleMode=SIFT::CommonParams::FIRST_ANGLE );
1357  virtual void read( const FileNode& fn );
1358  virtual void write( FileStorage& fs ) const;
1359 
1360 protected:
1361  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1362 
1364 };
1365 
1367 {
1368 public:
1369  SurfFeatureDetector( double hessianThreshold=400., int octaves=3, int octaveLayers=4 );
1370  virtual void read( const FileNode& fn );
1371  virtual void write( FileStorage& fs ) const;
1372 
1373 protected:
1374  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1375 
1377 };
1378 
1380 {
1381 public:
1383  {
1384  public:
1385  Params( float initFeatureScale=1.f, int featureScaleLevels=1, float featureScaleMul=0.1f,
1386  int initXyStep=6, int initImgBound=0, bool varyXyStepWithScale=true, bool varyImgBoundWithScale=false );
1390 
1393 
1396  };
1397 
1399 
1400  // TODO implement read/write
1401 
1402 protected:
1403  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1404 
1406 };
1407 
1408 /*
1409  * Adapts a detector to partition the source image into a grid and detect
1410  * points in each cell.
1411  */
1413 {
1414 public:
1415  /*
1416  * detector Detector that will be adapted.
1417  * maxTotalKeypoints Maximum count of keypoints detected on the image. Only the strongest keypoints
1418  * will be keeped.
1419  * gridRows Grid rows count.
1420  * gridCols Grid column count.
1421  */
1422  GridAdaptedFeatureDetector( const Ptr<FeatureDetector>& detector, int maxTotalKeypoints=1000,
1423  int gridRows=4, int gridCols=4 );
1424 
1425  // TODO implement read/write
1426 
1427 protected:
1428  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1429 
1434 };
1435 
1436 /*
1437  * Adapts a detector to detect points over multiple levels of a Gaussian
1438  * pyramid. Useful for detectors that are not inherently scaled.
1439  */
1441 {
1442 public:
1443  PyramidAdaptedFeatureDetector( const Ptr<FeatureDetector>& detector, int levels=2 );
1444 
1445  // TODO implement read/write
1446 
1447 protected:
1448  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1449 
1451  int levels;
1452 };
1453 
1458 {
1459 public:
1462  virtual ~AdjusterAdapter() {}
1467  virtual void tooFew(int min, int n_detected) = 0;
1472  virtual void tooMany(int max, int n_detected) = 0;
1476  virtual bool good() const = 0;
1477 
1478  static Ptr<AdjusterAdapter> create( const string& detectorType );
1479 };
1493 {
1494 public:
1495 
1502  DynamicAdaptedFeatureDetector( const Ptr<AdjusterAdapter>& adjaster, int min_features=400, int max_features=500, int max_iters=5 );
1503 
1504 protected:
1505  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1506 
1507 private:
1508  int escape_iters_;
1509  int min_features_, max_features_;
1510  Ptr<AdjusterAdapter> adjuster_;
1511 };
1512 
1517 {
1518 public:
1522  FastAdjuster(int init_thresh = 20, bool nonmax = true);
1523  virtual void tooFew(int min, int n_detected);
1524  virtual void tooMany(int max, int n_detected);
1525  virtual bool good() const;
1526 
1527 protected:
1528  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1529 
1530  int thresh_;
1531  bool nonmax_;
1532 };
1533 
1534 
1539 {
1540 public:
1541  StarAdjuster(double initial_thresh = 30.0);
1542  virtual void tooFew(int min, int n_detected);
1543  virtual void tooMany(int max, int n_detected);
1544  virtual bool good() const;
1545 
1546 protected:
1547  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1548 
1549  double thresh_;
1550  CvStarDetectorParams params_; //todo use these instead of thresh_
1551 };
1552 
1554 {
1555 public:
1556  SurfAdjuster();
1557  virtual void tooFew(int min, int n_detected);
1558  virtual void tooMany(int max, int n_detected);
1559  virtual bool good() const;
1560 
1561 protected:
1562  virtual void detectImpl( const Mat& image, vector<KeyPoint>& keypoints, const Mat& mask=Mat() ) const;
1563 
1564  double thresh_;
1565 };
1566 
1567 CV_EXPORTS Mat windowedMatchingMask( const vector<KeyPoint>& keypoints1, const vector<KeyPoint>& keypoints2,
1568  float maxDeltaX, float maxDeltaY );
1569 
1570 /****************************************************************************************\
1571 * DescriptorExtractor *
1572 \****************************************************************************************/
1573 
1574 /*
1575  * Abstract base class for computing descriptors for image keypoints.
1576  *
1577  * In this interface we assume a keypoint descriptor can be represented as a
1578  * dense, fixed-dimensional vector of some basic type. Most descriptors used
1579  * in practice follow this pattern, as it makes it very easy to compute
1580  * distances between descriptors. Therefore we represent a collection of
1581  * descriptors as a cv::Mat, where each row is one keypoint descriptor.
1582  */
1584 {
1585 public:
1586  virtual ~DescriptorExtractor();
1587 
1588  /*
1589  * Compute the descriptors for a set of keypoints in an image.
1590  * image The image.
1591  * keypoints The input keypoints. Keypoints for which a descriptor cannot be computed are removed.
1592  * descriptors Copmputed descriptors. Row i is the descriptor for keypoint i.
1593  */
1594  void compute( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
1595 
1596  /*
1597  * Compute the descriptors for a keypoints collection detected in image collection.
1598  * images Image collection.
1599  * keypoints Input keypoints collection. keypoints[i] is keypoints detected in images[i].
1600  * Keypoints for which a descriptor cannot be computed are removed.
1601  * descriptors Descriptor collection. descriptors[i] are descriptors computed for set keypoints[i].
1602  */
1603  void compute( const vector<Mat>& images, vector<vector<KeyPoint> >& keypoints, vector<Mat>& descriptors ) const;
1604 
1605  virtual void read( const FileNode& );
1606  virtual void write( FileStorage& ) const;
1607 
1608  virtual int descriptorSize() const = 0;
1609  virtual int descriptorType() const = 0;
1610 
1611  static Ptr<DescriptorExtractor> create( const string& descriptorExtractorType );
1612 
1613 protected:
1614  virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const = 0;
1615 
1616  /*
1617  * Remove keypoints within borderPixels of an image edge.
1618  */
1619  static void removeBorderKeypoints( vector<KeyPoint>& keypoints,
1620  Size imageSize, int borderSize );
1621 };
1622 
1623 /*
1624  * SiftDescriptorExtractor
1625  */
1627 {
1628 public:
1630  const SIFT::CommonParams& commonParams=SIFT::CommonParams() );
1631  SiftDescriptorExtractor( double magnification, bool isNormalize=true, bool recalculateAngles=true,
1635  int angleMode=SIFT::CommonParams::FIRST_ANGLE );
1636 
1637  virtual void read( const FileNode &fn );
1638  virtual void write( FileStorage &fs ) const;
1639 
1640  virtual int descriptorSize() const;
1641  virtual int descriptorType() const;
1642 
1643 protected:
1644  virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
1645 
1647 };
1648 
1649 /*
1650  * SurfDescriptorExtractor
1651  */
1653 {
1654 public:
1655  SurfDescriptorExtractor( int nOctaves=4, int nOctaveLayers=2, bool extended=false );
1656 
1657  virtual void read( const FileNode &fn );
1658  virtual void write( FileStorage &fs ) const;
1659 
1660  virtual int descriptorSize() const;
1661  virtual int descriptorType() const;
1662 
1663 protected:
1664  virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
1665 
1667 };
1668 
1669 /*
1670  * CalonderDescriptorExtractor
1671  */
1672 template<typename T>
1674 {
1675 public:
1676  CalonderDescriptorExtractor( const string& classifierFile );
1677 
1678  virtual void read( const FileNode &fn );
1679  virtual void write( FileStorage &fs ) const;
1680 
1681  virtual int descriptorSize() const { return classifier_.classes(); }
1682  virtual int descriptorType() const { return DataType<T>::type; }
1683 
1684 protected:
1685  virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
1686 
1688  static const int BORDER_SIZE = 16;
1689 };
1690 
1691 template<typename T>
1693 {
1694  classifier_.read( classifier_file.c_str() );
1695 }
1696 
1697 template<typename T>
1699  std::vector<cv::KeyPoint>& keypoints,
1700  cv::Mat& descriptors) const
1701 {
1702  // Cannot compute descriptors for keypoints on the image border.
1703  removeBorderKeypoints(keypoints, image.size(), BORDER_SIZE);
1704 
1706  descriptors.create(keypoints.size(), classifier_.classes(), cv::DataType<T>::type);
1707 
1708  int patchSize = RandomizedTree::PATCH_SIZE;
1709  int offset = patchSize / 2;
1710  for (size_t i = 0; i < keypoints.size(); ++i)
1711  {
1712  cv::Point2f pt = keypoints[i].pt;
1713  IplImage ipl = image( Rect((int)(pt.x - offset), (int)(pt.y - offset), patchSize, patchSize) );
1714  classifier_.getSignature( &ipl, descriptors.ptr<T>(i));
1715  }
1716 }
1717 
1718 template<typename T>
1720 {}
1721 
1722 template<typename T>
1724 {}
1725 
1726 /*
1727  * OpponentColorDescriptorExtractor
1728  *
1729  * Adapts a descriptor extractor to compute descripors in Opponent Color Space
1730  * (refer to van de Sande et al., CGIV 2008 "Color Descriptors for Object Category Recognition").
1731  * Input RGB image is transformed in Opponent Color Space. Then unadapted descriptor extractor
1732  * (set in constructor) computes descriptors on each of the three channel and concatenate
1733  * them into a single color descriptor.
1734  */
1736 {
1737 public:
1738  OpponentColorDescriptorExtractor( const Ptr<DescriptorExtractor>& descriptorExtractor );
1739 
1740  virtual void read( const FileNode& );
1741  virtual void write( FileStorage& ) const;
1742 
1743  virtual int descriptorSize() const;
1744  virtual int descriptorType() const;
1745 
1746 protected:
1747  virtual void computeImpl( const Mat& image, vector<KeyPoint>& keypoints, Mat& descriptors ) const;
1748 
1750 };
1751 
1752 /*
1753  * BRIEF Descriptor
1754  */
1756 {
1757 public:
1758  static const int PATCH_SIZE = 48;
1759  static const int KERNEL_SIZE = 9;
1760 
1761  // bytes is a length of descriptor in bytes. It can be equal 16, 32 or 64 bytes.
1762  BriefDescriptorExtractor( int bytes = 32 );
1763 
1764  virtual int descriptorSize() const;
1765  virtual int descriptorType() const;
1766 
1768 
1769 protected:
1770  virtual void computeImpl(const Mat& image, std::vector<KeyPoint>& keypoints, Mat& descriptors) const;
1771 
1772  typedef void(*PixelTestFn)(const Mat&, const std::vector<KeyPoint>&, Mat&);
1773 
1774  int bytes_;
1775  PixelTestFn test_fn_;
1776 };
1777 
1778 /****************************************************************************************\
1779 * Distance *
1780 \****************************************************************************************/
1781 template<typename T>
1783 {
1784  typedef T Type;
1785 };
1786 
1787 template<> struct Accumulator<unsigned char> { typedef float Type; };
1788 template<> struct Accumulator<unsigned short> { typedef float Type; };
1789 template<> struct Accumulator<char> { typedef float Type; };
1790 template<> struct Accumulator<short> { typedef float Type; };
1791 
1792 /*
1793  * Squared Euclidean distance functor
1794  */
1795 template<class T>
1797 {
1798  typedef T ValueType;
1800 
1801  ResultType operator()( const T* a, const T* b, int size ) const
1802  {
1803  ResultType result = ResultType();
1804  for( int i = 0; i < size; i++ )
1805  {
1806  ResultType diff = (ResultType)(a[i] - b[i]);
1807  result += diff*diff;
1808  }
1809  return (ResultType)sqrt((double)result);
1810  }
1811 };
1812 
1813 /*
1814  * Manhattan distance (city block distance) functor
1815  */
1816 template<class T>
1818 {
1819  typedef T ValueType;
1821 
1822  ResultType operator()( const T* a, const T* b, int size ) const
1823  {
1824  ResultType result = ResultType();
1825  for( int i = 0; i < size; i++ )
1826  {
1827  ResultType diff = a[i] - b[i];
1828  result += (ResultType)fabs( diff );
1829  }
1830  return result;
1831  }
1832 };
1833 
1834 /*
1835  * Hamming distance functor - counts the bit differences between two strings - useful for the Brief descriptor
1836  * bit count of A exclusive XOR'ed with B
1837  */
1839 {
1840  typedef unsigned char ValueType;
1841  typedef int ResultType;
1842 
1845  ResultType operator()( const unsigned char* a, const unsigned char* b, int size ) const;
1846 
1852  static unsigned char byteBitsLookUp(unsigned char b);
1853 };
1854 
1855 
1860 {
1861  typedef unsigned char ValueType;
1862 
1864  // in BruteForce if not
1865  typedef int ResultType;
1866 
1869  ResultType operator()(const unsigned char* a, const unsigned char* b, int size) const;
1870 };
1871 
1872 
1873 /****************************************************************************************\
1874 * DMatch *
1875 \****************************************************************************************/
1876 /*
1877  * Struct for matching: query descriptor index, train descriptor index, train image index and distance between descriptors.
1878  */
1880 {
1881  DMatch() : queryIdx(-1), trainIdx(-1), imgIdx(-1), distance(std::numeric_limits<float>::max()) {}
1882  DMatch( int _queryIdx, int _trainIdx, float _distance ) :
1883  queryIdx(_queryIdx), trainIdx(_trainIdx), imgIdx(-1), distance(_distance) {}
1884  DMatch( int _queryIdx, int _trainIdx, int _imgIdx, float _distance ) :
1885  queryIdx(_queryIdx), trainIdx(_trainIdx), imgIdx(_imgIdx), distance(_distance) {}
1886 
1887  int queryIdx; // query descriptor index
1888  int trainIdx; // train descriptor index
1889  int imgIdx; // train image index
1890 
1891  float distance;
1892 
1893  // less is better
1894  bool operator<( const DMatch &m ) const
1895  {
1896  return distance < m.distance;
1897  }
1898 };
1899 
1900 /****************************************************************************************\
1901 * DescriptorMatcher *
1902 \****************************************************************************************/
1903 /*
1904  * Abstract base class for matching two sets of descriptors.
1905  */
1907 {
1908 public:
1909  virtual ~DescriptorMatcher();
1910 
1911  /*
1912  * Add descriptors to train descriptor collection.
1913  * descriptors Descriptors to add. Each descriptors[i] is a descriptors set from one image.
1914  */
1915  virtual void add( const vector<Mat>& descriptors );
1916  /*
1917  * Get train descriptors collection.
1918  */
1919  const vector<Mat>& getTrainDescriptors() const;
1920  /*
1921  * Clear train descriptors collection.
1922  */
1923  virtual void clear();
1924 
1925  /*
1926  * Return true if there are not train descriptors in collection.
1927  */
1928  bool empty() const;
1929  /*
1930  * Return true if the matcher supports mask in match methods.
1931  */
1932  virtual bool isMaskSupported() const = 0;
1933 
1934  /*
1935  * Train matcher (e.g. train flann index).
1936  * In all methods to match the method train() is run every time before matching.
1937  * Some descriptor matchers (e.g. BruteForceMatcher) have empty implementation
1938  * of this method, other matchers realy train their inner structures
1939  * (e.g. FlannBasedMatcher trains flann::Index). So nonempty implementation
1940  * of train() should check the class object state and do traing/retraining
1941  * only if the state requires that (e.g. FlannBasedMatcher trains flann::Index
1942  * if it has not trained yet or if new descriptors have been added to the train
1943  * collection).
1944  */
1945  virtual void train();
1946  /*
1947  * Group of methods to match descriptors from image pair.
1948  * Method train() is run in this methods.
1949  */
1950  // Find one best match for each query descriptor (if mask is empty).
1951  void match( const Mat& queryDescriptors, const Mat& trainDescriptors,
1952  vector<DMatch>& matches, const Mat& mask=Mat() ) const;
1953  // Find k best matches for each query descriptor (in increasing order of distances).
1954  // compactResult is used when mask is not empty. If compactResult is false matches
1955  // vector will have the same size as queryDescriptors rows. If compactResult is true
1956  // matches vector will not contain matches for fully masked out query descriptors.
1957  void knnMatch( const Mat& queryDescriptors, const Mat& trainDescriptors,
1958  vector<vector<DMatch> >& matches, int k,
1959  const Mat& mask=Mat(), bool compactResult=false ) const;
1960  // Find best matches for each query descriptor which have distance less than
1961  // maxDistance (in increasing order of distances).
1962  void radiusMatch( const Mat& queryDescriptors, const Mat& trainDescriptors,
1963  vector<vector<DMatch> >& matches, float maxDistance,
1964  const Mat& mask=Mat(), bool compactResult=false ) const;
1965  /*
1966  * Group of methods to match descriptors from one image to image set.
1967  * See description of similar methods for matching image pair above.
1968  */
1969  void match( const Mat& queryDescriptors, vector<DMatch>& matches,
1970  const vector<Mat>& masks=vector<Mat>() );
1971  void knnMatch( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
1972  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
1973  void radiusMatch( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
1974  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
1975 
1976  // Reads matcher object from a file node
1977  virtual void read( const FileNode& );
1978  // Writes matcher object to a file storage
1979  virtual void write( FileStorage& ) const;
1980 
1981  // Clone the matcher. If emptyTrainData is false the method create deep copy of the object, i.e. copies
1982  // both parameters and train data. If emptyTrainData is true the method create object copy with current parameters
1983  // but with empty train data.
1984  virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const = 0;
1985 
1986  static Ptr<DescriptorMatcher> create( const string& descriptorMatcherType );
1987 protected:
1988  /*
1989  * Class to work with descriptors from several images as with one merged matrix.
1990  * It is used e.g. in FlannBasedMatcher.
1991  */
1993  {
1994  public:
1996  DescriptorCollection( const DescriptorCollection& collection );
1997  virtual ~DescriptorCollection();
1998 
1999  // Vector of matrices "descriptors" will be merged to one matrix "mergedDescriptors" here.
2000  void set( const vector<Mat>& descriptors );
2001  virtual void clear();
2002 
2003  const Mat& getDescriptors() const;
2004  const Mat getDescriptor( int imgIdx, int localDescIdx ) const;
2005  const Mat getDescriptor( int globalDescIdx ) const;
2006  void getLocalIdx( int globalDescIdx, int& imgIdx, int& localDescIdx ) const;
2007 
2008  int size() const;
2009 
2010  protected:
2012  vector<int> startIdxs;
2013  };
2014 
2015  // In fact the matching is implemented only by the following two methods. These methods suppose
2016  // that the class object has been trained already. Public match methods call these methods
2017  // after calling train().
2018  virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2019  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false ) = 0;
2020  virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
2021  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false ) = 0;
2022 
2023  static bool isPossibleMatch( const Mat& mask, int queryIdx, int trainIdx );
2024  static bool isMaskedOut( const vector<Mat>& masks, int queryIdx );
2025 
2026  static Mat clone_op( Mat m ) { return m.clone(); }
2027  void checkMasks( const vector<Mat>& masks, int queryDescriptorsCount ) const;
2028 
2029  // Collection of descriptors from train images.
2030  vector<Mat> trainDescCollection;
2031 };
2032 
2033 /*
2034  * Brute-force descriptor matcher.
2035  *
2036  * For each descriptor in the first set, this matcher finds the closest
2037  * descriptor in the second set by trying each one.
2038  *
2039  * For efficiency, BruteForceMatcher is templated on the distance metric.
2040  * For float descriptors, a common choice would be cv::L2<float>.
2041  */
2042 template<class Distance>
2044 {
2045 public:
2046  BruteForceMatcher( Distance d = Distance() ) : distance(d) {}
2047  virtual ~BruteForceMatcher() {}
2048 
2049  virtual bool isMaskSupported() const { return true; }
2050 
2051  virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const;
2052 
2053 protected:
2054  virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2055  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2056  virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
2057  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2058 
2059  Distance distance;
2060 
2061 private:
2062  /*
2063  * Next two methods are used to implement specialization.
2064  */
2065  static void commonKnnMatchImpl( BruteForceMatcher<Distance>& matcher,
2066  const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2067  const vector<Mat>& masks, bool compactResult );
2068  static void commonRadiusMatchImpl( BruteForceMatcher<Distance>& matcher,
2069  const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
2070  const vector<Mat>& masks, bool compactResult );
2071 };
2072 
2073 template<class Distance>
2075 {
2076  BruteForceMatcher* matcher = new BruteForceMatcher(distance);
2077  if( !emptyTrainData )
2078  {
2079  transform( trainDescCollection.begin(), trainDescCollection.end(),
2080  matcher->trainDescCollection.begin(), clone_op );
2081  }
2082  return matcher;
2083 }
2084 
2085 template<class Distance>
2086 void BruteForceMatcher<Distance>::knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2087  const vector<Mat>& masks, bool compactResult )
2088 {
2089  commonKnnMatchImpl( *this, queryDescriptors, matches, k, masks, compactResult );
2090 }
2091 
2092 template<class Distance>
2093 void BruteForceMatcher<Distance>::radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches,
2094  float maxDistance, const vector<Mat>& masks, bool compactResult )
2095 {
2096  commonRadiusMatchImpl( *this, queryDescriptors, matches, maxDistance, masks, compactResult );
2097 }
2098 
2099 template<class Distance>
2101  const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int knn,
2102  const vector<Mat>& masks, bool compactResult )
2103  {
2104  typedef typename Distance::ValueType ValueType;
2105  typedef typename Distance::ResultType DistanceType;
2106  CV_DbgAssert( !queryDescriptors.empty() );
2107  CV_Assert( DataType<ValueType>::type == queryDescriptors.type() );
2108 
2109  int dimension = queryDescriptors.cols;
2110  matches.reserve(queryDescriptors.rows);
2111 
2112  size_t imgCount = matcher.trainDescCollection.size();
2113  vector<Mat> allDists( imgCount ); // distances between one query descriptor and all train descriptors
2114  for( size_t i = 0; i < imgCount; i++ )
2115  allDists[i] = Mat( 1, matcher.trainDescCollection[i].rows, DataType<DistanceType>::type );
2116 
2117  for( int qIdx = 0; qIdx < queryDescriptors.rows; qIdx++ )
2118  {
2119  if( matcher.isMaskedOut( masks, qIdx ) )
2120  {
2121  if( !compactResult ) // push empty vector
2122  matches.push_back( vector<DMatch>() );
2123  }
2124  else
2125  {
2126  // 1. compute distances between i-th query descriptor and all train descriptors
2127  for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
2128  {
2129  CV_Assert( DataType<ValueType>::type == matcher.trainDescCollection[iIdx].type() || matcher.trainDescCollection[iIdx].empty() );
2130  CV_Assert( queryDescriptors.cols == matcher.trainDescCollection[iIdx].cols ||
2131  matcher.trainDescCollection[iIdx].empty() );
2132 
2133  const ValueType* d1 = (const ValueType*)(queryDescriptors.data + queryDescriptors.step*qIdx);
2134  allDists[iIdx].setTo( Scalar::all(std::numeric_limits<DistanceType>::max()) );
2135  for( int tIdx = 0; tIdx < matcher.trainDescCollection[iIdx].rows; tIdx++ )
2136  {
2137  if( masks.empty() || matcher.isPossibleMatch(masks[iIdx], qIdx, tIdx) )
2138  {
2139  const ValueType* d2 = (const ValueType*)(matcher.trainDescCollection[iIdx].data +
2140  matcher.trainDescCollection[iIdx].step*tIdx);
2141  allDists[iIdx].at<DistanceType>(0, tIdx) = matcher.distance(d1, d2, dimension);
2142  }
2143  }
2144  }
2145 
2146  // 2. choose k nearest matches for query[i]
2147  matches.push_back( vector<DMatch>() );
2148  vector<vector<DMatch> >::reverse_iterator curMatches = matches.rbegin();
2149  for( int k = 0; k < knn; k++ )
2150  {
2151  DMatch bestMatch;
2152  bestMatch.distance = std::numeric_limits<float>::max();
2153  for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
2154  {
2155  if( !allDists[iIdx].empty() )
2156  {
2157  double minVal;
2158  Point minLoc;
2159  minMaxLoc( allDists[iIdx], &minVal, 0, &minLoc, 0 );
2160  if( minVal < bestMatch.distance )
2161  bestMatch = DMatch( qIdx, minLoc.x, (int)iIdx, (float)minVal );
2162  }
2163  }
2164  if( bestMatch.trainIdx == -1 )
2165  break;
2166 
2167  allDists[bestMatch.imgIdx].at<DistanceType>(0, bestMatch.trainIdx) = std::numeric_limits<DistanceType>::max();
2168  curMatches->push_back( bestMatch );
2169  }
2170  //TODO should already be sorted at this point?
2171  std::sort( curMatches->begin(), curMatches->end() );
2172  }
2173  }
2174 }
2175 
2176 template<class Distance>
2177 inline void BruteForceMatcher<Distance>::commonRadiusMatchImpl( BruteForceMatcher<Distance>& matcher,
2178  const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
2179  const vector<Mat>& masks, bool compactResult )
2180 {
2181  typedef typename Distance::ValueType ValueType;
2182  typedef typename Distance::ResultType DistanceType;
2183  CV_DbgAssert( !queryDescriptors.empty() );
2184  CV_Assert( DataType<ValueType>::type == queryDescriptors.type() );
2185 
2186  int dimension = queryDescriptors.cols;
2187  matches.reserve(queryDescriptors.rows);
2188 
2189  size_t imgCount = matcher.trainDescCollection.size();
2190  for( int qIdx = 0; qIdx < queryDescriptors.rows; qIdx++ )
2191  {
2192  if( matcher.isMaskedOut( masks, qIdx ) )
2193  {
2194  if( !compactResult ) // push empty vector
2195  matches.push_back( vector<DMatch>() );
2196  }
2197  else
2198  {
2199  matches.push_back( vector<DMatch>() );
2200  vector<vector<DMatch> >::reverse_iterator curMatches = matches.rbegin();
2201  for( size_t iIdx = 0; iIdx < imgCount; iIdx++ )
2202  {
2203  CV_Assert( DataType<ValueType>::type == matcher.trainDescCollection[iIdx].type() ||
2204  matcher.trainDescCollection[iIdx].empty() );
2205  CV_Assert( queryDescriptors.cols == matcher.trainDescCollection[iIdx].cols ||
2206  matcher.trainDescCollection[iIdx].empty() );
2207 
2208  const ValueType* d1 = (const ValueType*)(queryDescriptors.data + queryDescriptors.step*qIdx);
2209  for( int tIdx = 0; tIdx < matcher.trainDescCollection[iIdx].rows; tIdx++ )
2210  {
2211  if( masks.empty() || matcher.isPossibleMatch(masks[iIdx], qIdx, tIdx) )
2212  {
2213  const ValueType* d2 = (const ValueType*)(matcher.trainDescCollection[iIdx].data +
2214  matcher.trainDescCollection[iIdx].step*tIdx);
2215  DistanceType d = matcher.distance(d1, d2, dimension);
2216  if( d < maxDistance )
2217  curMatches->push_back( DMatch( qIdx, tIdx, (int)iIdx, (float)d ) );
2218  }
2219  }
2220  }
2221  std::sort( curMatches->begin(), curMatches->end() );
2222  }
2223  }
2224 }
2225 
2226 /*
2227  * BruteForceMatcher L2 specialization
2228  */
2229 template<>
2230 void BruteForceMatcher<L2<float> >::knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2231  const vector<Mat>& masks, bool compactResult );
2232 template<>
2233 void BruteForceMatcher<L2<float> >::radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches,
2234  float maxDistance, const vector<Mat>& masks, bool compactResult );
2235 
2236 /*
2237  * Flann based matcher
2238  */
2240 {
2241 public:
2242  FlannBasedMatcher( const Ptr<flann::IndexParams>& indexParams=new flann::KDTreeIndexParams(),
2243  const Ptr<flann::SearchParams>& searchParams=new flann::SearchParams() );
2244 
2245  virtual void add( const vector<Mat>& descriptors );
2246  virtual void clear();
2247 
2248  virtual void train();
2249  virtual bool isMaskSupported() const;
2250 
2251  virtual Ptr<DescriptorMatcher> clone( bool emptyTrainData=false ) const;
2252 
2253 protected:
2254  static void convertToDMatches( const DescriptorCollection& descriptors,
2255  const Mat& indices, const Mat& distances,
2256  vector<vector<DMatch> >& matches );
2257 
2258  virtual void knnMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, int k,
2259  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2260  virtual void radiusMatchImpl( const Mat& queryDescriptors, vector<vector<DMatch> >& matches, float maxDistance,
2261  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2262 
2266 
2267  DescriptorCollection mergedDescriptors;
2269 };
2270 
2271 /****************************************************************************************\
2272 * GenericDescriptorMatcher *
2273 \****************************************************************************************/
2274 /*
2275  * Abstract interface for a keypoint descriptor and matcher
2276  */
2279 
2281 {
2282 public:
2284  virtual ~GenericDescriptorMatcher();
2285 
2286  /*
2287  * Add train collection: images and keypoints from them.
2288  * images A set of train images.
2289  * ketpoints Keypoint collection that have been detected on train images.
2290  *
2291  * Keypoints for which a descriptor cannot be computed are removed. Such keypoints
2292  * must be filtered in this method befor adding keypoints to train collection "trainPointCollection".
2293  * If inheritor class need perform such prefiltering the method add() must be overloaded.
2294  * In the other class methods programmer has access to the train keypoints by a constant link.
2295  */
2296  virtual void add( const vector<Mat>& images,
2297  vector<vector<KeyPoint> >& keypoints );
2298 
2299  const vector<Mat>& getTrainImages() const;
2300  const vector<vector<KeyPoint> >& getTrainKeypoints() const;
2301 
2302  /*
2303  * Clear images and keypoints storing in train collection.
2304  */
2305  virtual void clear();
2306  /*
2307  * Returns true if matcher supports mask to match descriptors.
2308  */
2309  virtual bool isMaskSupported() = 0;
2310  /*
2311  * Train some inner structures (e.g. flann index or decision trees).
2312  * train() methods is run every time in matching methods. So the method implementation
2313  * should has a check whether these inner structures need be trained/retrained or not.
2314  */
2315  virtual void train();
2316 
2317  /*
2318  * Classifies query keypoints.
2319  * queryImage The query image
2320  * queryKeypoints Keypoints from the query image
2321  * trainImage The train image
2322  * trainKeypoints Keypoints from the train image
2323  */
2324  // Classify keypoints from query image under one train image.
2325  void classify( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2326  const Mat& trainImage, vector<KeyPoint>& trainKeypoints ) const;
2327  // Classify keypoints from query image under train image collection.
2328  void classify( const Mat& queryImage, vector<KeyPoint>& queryKeypoints );
2329 
2330  /*
2331  * Group of methods to match keypoints from image pair.
2332  * Keypoints for which a descriptor cannot be computed are removed.
2333  * train() method is called here.
2334  */
2335  // Find one best match for each query descriptor (if mask is empty).
2336  void match( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2337  const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
2338  vector<DMatch>& matches, const Mat& mask=Mat() ) const;
2339  // Find k best matches for each query keypoint (in increasing order of distances).
2340  // compactResult is used when mask is not empty. If compactResult is false matches
2341  // vector will have the same size as queryDescriptors rows.
2342  // If compactResult is true matches vector will not contain matches for fully masked out query descriptors.
2343  void knnMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2344  const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
2345  vector<vector<DMatch> >& matches, int k,
2346  const Mat& mask=Mat(), bool compactResult=false ) const;
2347  // Find best matches for each query descriptor which have distance less than maxDistance (in increasing order of distances).
2348  void radiusMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2349  const Mat& trainImage, vector<KeyPoint>& trainKeypoints,
2350  vector<vector<DMatch> >& matches, float maxDistance,
2351  const Mat& mask=Mat(), bool compactResult=false ) const;
2352  /*
2353  * Group of methods to match keypoints from one image to image set.
2354  * See description of similar methods for matching image pair above.
2355  */
2356  void match( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2357  vector<DMatch>& matches, const vector<Mat>& masks=vector<Mat>() );
2358  void knnMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2359  vector<vector<DMatch> >& matches, int k,
2360  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2361  void radiusMatch( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2362  vector<vector<DMatch> >& matches, float maxDistance,
2363  const vector<Mat>& masks=vector<Mat>(), bool compactResult=false );
2364 
2365  // Reads matcher object from a file node
2366  virtual void read( const FileNode& );
2367  // Writes matcher object to a file storage
2368  virtual void write( FileStorage& ) const;
2369 
2370  // Clone the matcher. If emptyTrainData is false the method create deep copy of the object, i.e. copies
2371  // both parameters and train data. If emptyTrainData is true the method create object copy with current parameters
2372  // but with empty train data.
2373  virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const = 0;
2374 
2375  static Ptr<GenericDescriptorMatcher> create( const string& genericDescritptorMatcherType,
2376  const string &paramsFilename=string() );
2377 
2378 protected:
2379  // In fact the matching is implemented only by the following two methods. These methods suppose
2380  // that the class object has been trained already. Public match methods call these methods
2381  // after calling train().
2382  virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2383  vector<vector<DMatch> >& matches, int k,
2384  const vector<Mat>& masks, bool compactResult ) = 0;
2385  virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2386  vector<vector<DMatch> >& matches, float maxDistance,
2387  const vector<Mat>& masks, bool compactResult ) = 0;
2388  /*
2389  * A storage for sets of keypoints together with corresponding images and class IDs
2390  */
2392  {
2393  public:
2395  KeyPointCollection( const KeyPointCollection& collection );
2396  void add( const vector<Mat>& images, const vector<vector<KeyPoint> >& keypoints );
2397  void clear();
2398 
2399  // Returns the total number of keypoints in the collection
2400  size_t keypointCount() const;
2401  size_t imageCount() const;
2402 
2403  const vector<vector<KeyPoint> >& getKeypoints() const;
2404  const vector<KeyPoint>& getKeypoints( int imgIdx ) const;
2405  const KeyPoint& getKeyPoint( int imgIdx, int localPointIdx ) const;
2406  const KeyPoint& getKeyPoint( int globalPointIdx ) const;
2407  void getLocalIdx( int globalPointIdx, int& imgIdx, int& localPointIdx ) const;
2408 
2409  const vector<Mat>& getImages() const;
2410  const Mat& getImage( int imgIdx ) const;
2411 
2412  protected:
2414 
2415  vector<Mat> images;
2416  vector<vector<KeyPoint> > keypoints;
2417  // global indices of the first points in each image, startIndices.size() = keypoints.size()
2418  vector<int> startIndices;
2419 
2420  private:
2421  static Mat clone_op( Mat m ) { return m.clone(); }
2422  };
2423 
2425 };
2426 
2427 /*
2428  * OneWayDescriptorMatcher
2429  */
2432 
2434 {
2435 public:
2437  {
2438  public:
2439  static const int POSE_COUNT = 500;
2440  static const int PATCH_WIDTH = 24;
2441  static const int PATCH_HEIGHT = 24;
2442  static float GET_MIN_SCALE() { return 0.7f; }
2443  static float GET_MAX_SCALE() { return 1.5f; }
2444  static float GET_STEP_SCALE() { return 1.2f; }
2445 
2446  Params( int poseCount = POSE_COUNT,
2447  Size patchSize = Size(PATCH_WIDTH, PATCH_HEIGHT),
2448  string pcaFilename = string(),
2449  string trainPath = string(), string trainImagesList = string(),
2450  float minScale = GET_MIN_SCALE(), float maxScale = GET_MAX_SCALE(),
2451  float stepScale = GET_STEP_SCALE() );
2452 
2455  string pcaFilename;
2456  string trainPath;
2458 
2459  float minScale, maxScale, stepScale;
2460  };
2461 
2462  OneWayDescriptorMatcher( const Params& params=Params() );
2463  virtual ~OneWayDescriptorMatcher();
2464 
2465  void initialize( const Params& params, const Ptr<OneWayDescriptorBase>& base=Ptr<OneWayDescriptorBase>() );
2466 
2467  // Clears keypoints storing in collection and OneWayDescriptorBase
2468  virtual void clear();
2469 
2470  virtual void train();
2471 
2472  virtual bool isMaskSupported();
2473 
2474  virtual void read( const FileNode &fn );
2475  virtual void write( FileStorage& fs ) const;
2476 
2477  virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
2478 
2479 protected:
2480  // Matches a set of keypoints from a single image of the training set. A rectangle with a center in a keypoint
2481  // and size (patch_width/2*scale, patch_height/2*scale) is cropped from the source image for each
2482  // keypoint. scale is iterated from DescriptorOneWayParams::min_scale to DescriptorOneWayParams::max_scale.
2483  // The minimum distance to each training patch with all its affine poses is found over all scales.
2484  // The class ID of a match is returned for each keypoint. The distance is calculated over PCA components
2485  // loaded with DescriptorOneWay::Initialize, kd tree is used for finding minimum distances.
2486  virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2487  vector<vector<DMatch> >& matches, int k,
2488  const vector<Mat>& masks, bool compactResult );
2489  virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2490  vector<vector<DMatch> >& matches, float maxDistance,
2491  const vector<Mat>& masks, bool compactResult );
2492 
2496 };
2497 
2498 /*
2499  * FernDescriptorMatcher
2500  */
2503 
2505 {
2506 public:
2508  {
2509  public:
2510  Params( int nclasses=0,
2511  int patchSize=FernClassifier::PATCH_SIZE,
2512  int signatureSize=FernClassifier::DEFAULT_SIGNATURE_SIZE,
2513  int nstructs=FernClassifier::DEFAULT_STRUCTS,
2514  int structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
2515  int nviews=FernClassifier::DEFAULT_VIEWS,
2516  int compressionMethod=FernClassifier::COMPRESSION_NONE,
2517  const PatchGenerator& patchGenerator=PatchGenerator() );
2518 
2519  Params( const string& filename );
2520 
2526  int nviews;
2529 
2530  string filename;
2531  };
2532 
2533  FernDescriptorMatcher( const Params& params=Params() );
2534  virtual ~FernDescriptorMatcher();
2535 
2536  virtual void clear();
2537 
2538  virtual void train();
2539 
2540  virtual bool isMaskSupported();
2541 
2542  virtual void read( const FileNode &fn );
2543  virtual void write( FileStorage& fs ) const;
2544 
2545  virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
2546 
2547 protected:
2548  virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2549  vector<vector<DMatch> >& matches, int k,
2550  const vector<Mat>& masks, bool compactResult );
2551  virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2552  vector<vector<DMatch> >& matches, float maxDistance,
2553  const vector<Mat>& masks, bool compactResult );
2554 
2555  void trainFernClassifier();
2556  void calcBestProbAndMatchIdx( const Mat& image, const Point2f& pt,
2557  float& bestProb, int& bestMatchIdx, vector<float>& signature );
2561 };
2562 
2563 /****************************************************************************************\
2564 * VectorDescriptorMatcher *
2565 \****************************************************************************************/
2566 
2567 /*
2568  * A class used for matching descriptors that can be described as vectors in a finite-dimensional space
2569  */
2572 
2574 {
2575 public:
2576  VectorDescriptorMatcher( const Ptr<DescriptorExtractor>& extractor, const Ptr<DescriptorMatcher>& matcher );
2577  virtual ~VectorDescriptorMatcher();
2578 
2579  virtual void add( const vector<Mat>& imgCollection,
2580  vector<vector<KeyPoint> >& pointCollection );
2581 
2582  virtual void clear();
2583 
2584  virtual void train();
2585 
2586  virtual bool isMaskSupported();
2587 
2588  virtual void read( const FileNode& fn );
2589  virtual void write( FileStorage& fs ) const;
2590 
2591  virtual Ptr<GenericDescriptorMatcher> clone( bool emptyTrainData=false ) const;
2592 
2593 protected:
2594  virtual void knnMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2595  vector<vector<DMatch> >& matches, int k,
2596  const vector<Mat>& masks, bool compactResult );
2597  virtual void radiusMatchImpl( const Mat& queryImage, vector<KeyPoint>& queryKeypoints,
2598  vector<vector<DMatch> >& matches, float maxDistance,
2599  const vector<Mat>& masks, bool compactResult );
2600 
2603 };
2604 
2605 /****************************************************************************************\
2606 * Drawing functions *
2607 \****************************************************************************************/
2609 {
2610  enum{ DEFAULT = 0, // Output image matrix will be created (Mat::create),
2611  // i.e. existing memory of output image may be reused.
2612  // Two source image, matches and single keypoints will be drawn.
2613  // For each keypoint only the center point will be drawn (without
2614  // the circle around keypoint with keypoint size and orientation).
2615  DRAW_OVER_OUTIMG = 1, // Output image matrix will not be created (Mat::create).
2616  // Matches will be drawn on existing content of output image.
2617  NOT_DRAW_SINGLE_POINTS = 2, // Single keypoints will not be drawn.
2618  DRAW_RICH_KEYPOINTS = 4 // For each keypoint the circle around keypoint with keypoint size and
2619  // orientation will be drawn.
2620  };
2621 };
2622 
2623 // Draw keypoints.
2624 CV_EXPORTS void drawKeypoints( const Mat& image, const vector<KeyPoint>& keypoints, Mat& outImg,
2625  const Scalar& color=Scalar::all(-1), int flags=DrawMatchesFlags::DEFAULT );
2626 
2627 // Draws matches of keypints from two images on output image.
2628 CV_EXPORTS void drawMatches( const Mat& img1, const vector<KeyPoint>& keypoints1,
2629  const Mat& img2, const vector<KeyPoint>& keypoints2,
2630  const vector<DMatch>& matches1to2, Mat& outImg,
2631  const Scalar& matchColor=Scalar::all(-1), const Scalar& singlePointColor=Scalar::all(-1),
2632  const vector<char>& matchesMask=vector<char>(), int flags=DrawMatchesFlags::DEFAULT );
2633 
2634 CV_EXPORTS void drawMatches( const Mat& img1, const vector<KeyPoint>& keypoints1,
2635  const Mat& img2, const vector<KeyPoint>& keypoints2,
2636  const vector<vector<DMatch> >& matches1to2, Mat& outImg,
2637  const Scalar& matchColor=Scalar::all(-1), const Scalar& singlePointColor=Scalar::all(-1),
2638  const vector<vector<char> >& matchesMask=vector<vector<char> >(), int flags=DrawMatchesFlags::DEFAULT );
2639 
2640 /****************************************************************************************\
2641 * Functions to evaluate the feature detectors and [generic] descriptor extractors *
2642 \****************************************************************************************/
2643 
2644 CV_EXPORTS void evaluateFeatureDetector( const Mat& img1, const Mat& img2, const Mat& H1to2,
2645  vector<KeyPoint>* keypoints1, vector<KeyPoint>* keypoints2,
2646  float& repeatability, int& correspCount,
2647  const Ptr<FeatureDetector>& fdetector=Ptr<FeatureDetector>() );
2648 
2649 CV_EXPORTS void computeRecallPrecisionCurve( const vector<vector<DMatch> >& matches1to2,
2650  const vector<vector<uchar> >& correctMatches1to2Mask,
2651  vector<Point2f>& recallPrecisionCurve );
2652 CV_EXPORTS float getRecall( const vector<Point2f>& recallPrecisionCurve, float l_precision );
2653 
2654 CV_EXPORTS void evaluateGenericDescriptorMatcher( const Mat& img1, const Mat& img2, const Mat& H1to2,
2655  vector<KeyPoint>& keypoints1, vector<KeyPoint>& keypoints2,
2656  vector<vector<DMatch> >* matches1to2, vector<vector<uchar> >* correctMatches1to2Mask,
2657  vector<Point2f>& recallPrecisionCurve,
2658  const Ptr<GenericDescriptorMatcher>& dmatch=Ptr<GenericDescriptorMatcher>() );
2659 
2660 
2661 /****************************************************************************************\
2662 * Bag of visual words *
2663 \****************************************************************************************/
2664 /*
2665  * Abstract base class for training of a 'bag of visual words' vocabulary from a set of descriptors
2666  */
2668 {
2669 public:
2670  BOWTrainer();
2671  virtual ~BOWTrainer();
2672 
2673  void add( const Mat& descriptors );
2674  const vector<Mat>& getDescriptors() const;
2675  int descripotorsCount() const;
2676 
2677  virtual void clear();
2678 
2679  /*
2680  * Train visual words vocabulary, that is cluster training descriptors and
2681  * compute cluster centers.
2682  * Returns cluster centers.
2683  *
2684  * descriptors Training descriptors computed on images keypoints.
2685  */
2686  virtual Mat cluster() const = 0;
2687  virtual Mat cluster( const Mat& descriptors ) const = 0;
2688 
2689 protected:
2690  vector<Mat> descriptors;
2691  int size;
2692 };
2693 
2694 /*
2695  * This is BOWTrainer using cv::kmeans to get vocabulary.
2696  */
2698 {
2699 public:
2700  BOWKMeansTrainer( int clusterCount, const TermCriteria& termcrit=TermCriteria(),
2701  int attempts=3, int flags=KMEANS_PP_CENTERS );
2702  virtual ~BOWKMeansTrainer();
2703 
2704  // Returns trained vocabulary (i.e. cluster centers).
2705  virtual Mat cluster() const;
2706  virtual Mat cluster( const Mat& descriptors ) const;
2707 
2708 protected:
2709 
2713  int flags;
2714 };
2715 
2716 /*
2717  * Class to compute image descriptor using bag of visual words.
2718  */
2720 {
2721 public:
2723  const Ptr<DescriptorMatcher>& dmatcher );
2724  virtual ~BOWImgDescriptorExtractor();
2725 
2726  void setVocabulary( const Mat& vocabulary );
2727  const Mat& getVocabulary() const;
2728  void compute( const Mat& image, vector<KeyPoint>& keypoints, Mat& imgDescriptor,
2729  vector<vector<int> >* pointIdxsOfClusters=0, Mat* descriptors=0 );
2730  // compute() is not constant because DescriptorMatcher::match is not constant
2731 
2732  int descriptorSize() const;
2733  int descriptorType() const;
2734 
2735 protected:
2739 };
2740 
2741 } /* namespace cv */
2742 
2743 #endif /* __cplusplus */
2744 
2745 #endif
2746 
2747 /* End of file. */