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