opencv 2.2.0
/usr/src/RPM/BUILD/libopencv2.2-2.2.0/modules/objdetect/include/opencv2/objdetect/objdetect.hpp
Go to the documentation of this file.
00001 /*M///////////////////////////////////////////////////////////////////////////////////////
00002 //
00003 //  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
00004 //
00005 //  By downloading, copying, installing or using the software you agree to this license.
00006 //  If you do not agree to this license, do not download, install,
00007 //  copy or use the software.
00008 //
00009 //
00010 //                           License Agreement
00011 //                For Open Source Computer Vision Library
00012 //
00013 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
00014 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
00015 // Third party copyrights are property of their respective owners.
00016 //
00017 // Redistribution and use in source and binary forms, with or without modification,
00018 // are permitted provided that the following conditions are met:
00019 //
00020 //   * Redistribution's of source code must retain the above copyright notice,
00021 //     this list of conditions and the following disclaimer.
00022 //
00023 //   * Redistribution's in binary form must reproduce the above copyright notice,
00024 //     this list of conditions and the following disclaimer in the documentation
00025 //     and/or other materials provided with the distribution.
00026 //
00027 //   * The name of the copyright holders may not be used to endorse or promote products
00028 //     derived from this software without specific prior written permission.
00029 //
00030 // This software is provided by the copyright holders and contributors "as is" and
00031 // any express or implied warranties, including, but not limited to, the implied
00032 // warranties of merchantability and fitness for a particular purpose are disclaimed.
00033 // In no event shall the Intel Corporation or contributors be liable for any direct,
00034 // indirect, incidental, special, exemplary, or consequential damages
00035 // (including, but not limited to, procurement of substitute goods or services;
00036 // loss of use, data, or profits; or business interruption) however caused
00037 // and on any theory of liability, whether in contract, strict liability,
00038 // or tort (including negligence or otherwise) arising in any way out of
00039 // the use of this software, even if advised of the possibility of such damage.
00040 //
00041 //M*/
00042 
00043 #ifndef __OPENCV_OBJDETECT_HPP__
00044 #define __OPENCV_OBJDETECT_HPP__
00045 
00046 #include "opencv2/core/core.hpp"
00047 #include "opencv2/features2d/features2d.hpp"
00048 
00049 #ifdef __cplusplus
00050 extern "C" {
00051 #endif
00052 
00053 /****************************************************************************************\
00054 *                         Haar-like Object Detection functions                           *
00055 \****************************************************************************************/
00056 
00057 #define CV_HAAR_MAGIC_VAL    0x42500000
00058 #define CV_TYPE_NAME_HAAR    "opencv-haar-classifier"
00059 
00060 #define CV_IS_HAAR_CLASSIFIER( haar )                                                    \
00061     ((haar) != NULL &&                                                                   \
00062     (((const CvHaarClassifierCascade*)(haar))->flags & CV_MAGIC_MASK)==CV_HAAR_MAGIC_VAL)
00063 
00064 #define CV_HAAR_FEATURE_MAX  3
00065 
00066 typedef struct CvHaarFeature
00067 {
00068     int tilted;
00069     struct
00070     {
00071         CvRect r;
00072         float weight;
00073     } rect[CV_HAAR_FEATURE_MAX];
00074 } CvHaarFeature;
00075 
00076 typedef struct CvHaarClassifier
00077 {
00078     int count;
00079     CvHaarFeature* haar_feature;
00080     float* threshold;
00081     int* left;
00082     int* right;
00083     float* alpha;
00084 } CvHaarClassifier;
00085 
00086 typedef struct CvHaarStageClassifier
00087 {
00088     int  count;
00089     float threshold;
00090     CvHaarClassifier* classifier;
00091 
00092     int next;
00093     int child;
00094     int parent;
00095 } CvHaarStageClassifier;
00096 
00097 typedef struct CvHidHaarClassifierCascade CvHidHaarClassifierCascade;
00098 
00099 typedef struct CvHaarClassifierCascade
00100 {
00101     int  flags;
00102     int  count;
00103     CvSize orig_window_size;
00104     CvSize real_window_size;
00105     double scale;
00106     CvHaarStageClassifier* stage_classifier;
00107     CvHidHaarClassifierCascade* hid_cascade;
00108 } CvHaarClassifierCascade;
00109 
00110 typedef struct CvAvgComp
00111 {
00112     CvRect rect;
00113     int neighbors;
00114 } CvAvgComp;
00115 
00116 /* Loads haar classifier cascade from a directory.
00117    It is obsolete: convert your cascade to xml and use cvLoad instead */
00118 CVAPI(CvHaarClassifierCascade*) cvLoadHaarClassifierCascade(
00119                     const char* directory, CvSize orig_window_size);
00120 
00121 CVAPI(void) cvReleaseHaarClassifierCascade( CvHaarClassifierCascade** cascade );
00122 
00123 #define CV_HAAR_DO_CANNY_PRUNING    1
00124 #define CV_HAAR_SCALE_IMAGE         2
00125 #define CV_HAAR_FIND_BIGGEST_OBJECT 4
00126 #define CV_HAAR_DO_ROUGH_SEARCH     8
00127 
00128 CVAPI(CvSeq*) cvHaarDetectObjects( const CvArr* image,
00129                      CvHaarClassifierCascade* cascade,
00130                      CvMemStorage* storage, double scale_factor CV_DEFAULT(1.1),
00131                      int min_neighbors CV_DEFAULT(3), int flags CV_DEFAULT(0),
00132                      CvSize min_size CV_DEFAULT(cvSize(0,0)), CvSize max_size CV_DEFAULT(cvSize(0,0)));
00133 
00134 /* sets images for haar classifier cascade */
00135 CVAPI(void) cvSetImagesForHaarClassifierCascade( CvHaarClassifierCascade* cascade,
00136                                                 const CvArr* sum, const CvArr* sqsum,
00137                                                 const CvArr* tilted_sum, double scale );
00138 
00139 /* runs the cascade on the specified window */
00140 CVAPI(int) cvRunHaarClassifierCascade( const CvHaarClassifierCascade* cascade,
00141                                        CvPoint pt, int start_stage CV_DEFAULT(0));
00142 
00143 
00144 /****************************************************************************************\
00145 *                         Latent SVM Object Detection functions                          *
00146 \****************************************************************************************/
00147 
00148 // DataType: STRUCT position
00149 // Structure describes the position of the filter in the feature pyramid
00150 // l - level in the feature pyramid
00151 // (x, y) - coordinate in level l
00152 typedef struct
00153 {
00154     unsigned int x;
00155     unsigned int y;
00156     unsigned int l;
00157 } CvLSVMFilterPosition;
00158 
00159 // DataType: STRUCT filterObject
00160 // Description of the filter, which corresponds to the part of the object
00161 // V               - ideal (penalty = 0) position of the partial filter
00162 //                   from the root filter position (V_i in the paper)
00163 // penaltyFunction - vector describes penalty function (d_i in the paper)
00164 //                   pf[0] * x + pf[1] * y + pf[2] * x^2 + pf[3] * y^2
00165 // FILTER DESCRIPTION
00166 //   Rectangular map (sizeX x sizeY), 
00167 //   every cell stores feature vector (dimension = p)
00168 // H               - matrix of feature vectors
00169 //                   to set and get feature vectors (i,j) 
00170 //                   used formula H[(j * sizeX + i) * p + k], where
00171 //                   k - component of feature vector in cell (i, j)
00172 // END OF FILTER DESCRIPTION
00173 // xp              - auxillary parameter for internal use
00174 //                   size of row in feature vectors 
00175 //                   (yp = (int) (p / xp); p = xp * yp)
00176 typedef struct{
00177     CvLSVMFilterPosition V;
00178     float fineFunction[4];
00179     unsigned int sizeX;
00180     unsigned int sizeY;
00181     unsigned int p;
00182     unsigned int xp;
00183     float *H;
00184 } CvLSVMFilterObject;
00185 
00186 // data type: STRUCT CvLatentSvmDetector
00187 // structure contains internal representation of trained Latent SVM detector
00188 // num_filters                  - total number of filters (root plus part) in model 
00189 // num_components               - number of components in model
00190 // num_part_filters             - array containing number of part filters for each component
00191 // filters                              - root and part filters for all model components
00192 // b                                    - biases for all model components
00193 // score_threshold              - confidence level threshold
00194 typedef struct CvLatentSvmDetector
00195 {
00196         int num_filters;
00197         int num_components;
00198         int* num_part_filters;
00199         CvLSVMFilterObject** filters;
00200         float* b;
00201         float score_threshold;
00202 }
00203 CvLatentSvmDetector;
00204 
00205 // data type: STRUCT CvObjectDetection
00206 // structure contains the bounding box and confidence level for detected object 
00207 // rect                                 - bounding box for a detected object
00208 // score                                - confidence level 
00209 typedef struct CvObjectDetection
00210 {
00211         CvRect rect;
00212         float score;
00213 } CvObjectDetection;
00214 
00216 
00217 
00218 /*
00219 // load trained detector from a file
00220 //
00221 // API
00222 // CvLatentSvmDetector* cvLoadLatentSvmDetector(const char* filename);
00223 // INPUT
00224 // filename                             - path to the file containing the parameters of
00225                                                 - trained Latent SVM detector
00226 // OUTPUT
00227 // trained Latent SVM detector in internal representation
00228 */
00229 CVAPI(CvLatentSvmDetector*) cvLoadLatentSvmDetector(const char* filename);
00230 
00231 /*
00232 // release memory allocated for CvLatentSvmDetector structure
00233 //
00234 // API
00235 // void cvReleaseLatentSvmDetector(CvLatentSvmDetector** detector);
00236 // INPUT
00237 // detector                             - CvLatentSvmDetector structure to be released
00238 // OUTPUT
00239 */
00240 CVAPI(void) cvReleaseLatentSvmDetector(CvLatentSvmDetector** detector);
00241 
00242 /*
00243 // find rectangular regions in the given image that are likely 
00244 // to contain objects and corresponding confidence levels
00245 //
00246 // API
00247 // CvSeq* cvLatentSvmDetectObjects(const IplImage* image, 
00248 //                                                                      CvLatentSvmDetector* detector, 
00249 //                                                                      CvMemStorage* storage, 
00250 //                                                                      float overlap_threshold = 0.5f);
00251 // INPUT
00252 // image                                - image to detect objects in
00253 // detector                             - Latent SVM detector in internal representation
00254 // storage                              - memory storage to store the resultant sequence 
00255 //                                                      of the object candidate rectangles
00256 // overlap_threshold    - threshold for the non-maximum suppression algorithm 
00257                            = 0.5f [here will be the reference to original paper]
00258 // OUTPUT
00259 // sequence of detected objects (bounding boxes and confidence levels stored in CvObjectDetection structures)
00260 */
00261 CVAPI(CvSeq*) cvLatentSvmDetectObjects(IplImage* image, 
00262                                                                 CvLatentSvmDetector* detector, 
00263                                                                 CvMemStorage* storage, 
00264                                                                 float overlap_threshold CV_DEFAULT(0.5f));
00265 
00266 #ifdef __cplusplus
00267 }
00268 
00269 namespace cv
00270 {
00271         
00273 
00274 CV_EXPORTS_W void groupRectangles(vector<Rect>& rectList, int groupThreshold, double eps=0.2);
00275 CV_EXPORTS_W void groupRectangles(vector<Rect>& rectList, CV_OUT vector<int>& weights, int groupThreshold, double eps=0.2);
00276         
00277 class CV_EXPORTS FeatureEvaluator
00278 {
00279 public:    
00280     enum { HAAR = 0, LBP = 1 };
00281     virtual ~FeatureEvaluator();
00282 
00283     virtual bool read(const FileNode& node);
00284     virtual Ptr<FeatureEvaluator> clone() const;
00285     virtual int getFeatureType() const;
00286     
00287     virtual bool setImage(const Mat&, Size origWinSize);
00288     virtual bool setWindow(Point p);
00289 
00290     virtual double calcOrd(int featureIdx) const;
00291     virtual int calcCat(int featureIdx) const;
00292 
00293     static Ptr<FeatureEvaluator> create(int type);
00294 };
00295 
00296 template<> CV_EXPORTS void Ptr<CvHaarClassifierCascade>::delete_obj();
00297    
00298 class CV_EXPORTS_W CascadeClassifier
00299 {
00300 public:
00301     CV_WRAP CascadeClassifier();
00302     CV_WRAP CascadeClassifier( const string& filename );
00303     virtual ~CascadeClassifier();
00304     
00305     CV_WRAP virtual bool empty() const;
00306     CV_WRAP bool load( const string& filename );
00307     bool read( const FileNode& node );
00308     CV_WRAP void detectMultiScale( const Mat& image,
00309                                    CV_OUT vector<Rect>& objects,
00310                                    double scaleFactor=1.1,
00311                                    int minNeighbors=3, int flags=0,
00312                                    Size minSize=Size(),
00313                                    Size maxSize=Size() );
00314 
00315     bool isOldFormatCascade() const;
00316     virtual Size getOriginalWindowSize() const;
00317     int getFeatureType() const;
00318     bool setImage( const Mat& );
00319 
00320 protected:
00321     virtual bool detectSingleScale( const Mat& image, int stripCount, Size processingRectSize,
00322                                     int stripSize, int yStep, double factor, vector<Rect>& candidates );
00323 
00324 private:
00325     enum { BOOST = 0 };
00326     enum { DO_CANNY_PRUNING = 1, SCALE_IMAGE = 2,
00327            FIND_BIGGEST_OBJECT = 4, DO_ROUGH_SEARCH = 8 };
00328 
00329     friend struct CascadeClassifierInvoker;
00330 
00331     template<class FEval>
00332     friend int predictOrdered( CascadeClassifier& cascade, Ptr<FeatureEvaluator> &featureEvaluator);
00333 
00334     template<class FEval>
00335     friend int predictCategorical( CascadeClassifier& cascade, Ptr<FeatureEvaluator> &featureEvaluator);
00336 
00337     template<class FEval>
00338     friend int predictOrderedStump( CascadeClassifier& cascade, Ptr<FeatureEvaluator> &featureEvaluator);
00339 
00340     template<class FEval>
00341     friend int predictCategoricalStump( CascadeClassifier& cascade, Ptr<FeatureEvaluator> &featureEvaluator);
00342 
00343     bool setImage( Ptr<FeatureEvaluator>&, const Mat& );
00344     int runAt( Ptr<FeatureEvaluator>&, Point );
00345 
00346     class Data
00347     {
00348     public:
00349         struct CV_EXPORTS DTreeNode
00350         {
00351             int featureIdx;
00352             float threshold; // for ordered features only
00353             int left;
00354             int right;
00355         };
00356 
00357         struct CV_EXPORTS DTree
00358         {
00359             int nodeCount;
00360         };
00361 
00362         struct CV_EXPORTS Stage
00363         {
00364             int first;
00365             int ntrees;
00366             float threshold;
00367         };
00368 
00369         bool read(const FileNode &node);
00370 
00371         bool isStumpBased;
00372 
00373         int stageType;
00374         int featureType;
00375         int ncategories;
00376         Size origWinSize;
00377 
00378         vector<Stage> stages;
00379         vector<DTree> classifiers;
00380         vector<DTreeNode> nodes;
00381         vector<float> leaves;
00382         vector<int> subsets;
00383     };
00384 
00385     Data data;
00386     Ptr<FeatureEvaluator> featureEvaluator;
00387     Ptr<CvHaarClassifierCascade> oldCascade;
00388 };
00389 
00391 
00392 struct CV_EXPORTS_W HOGDescriptor
00393 {
00394 public:
00395     enum { L2Hys=0 };
00396     enum { DEFAULT_NLEVELS=64 };
00397     
00398     CV_WRAP HOGDescriptor() : winSize(64,128), blockSize(16,16), blockStride(8,8),
00399         cellSize(8,8), nbins(9), derivAperture(1), winSigma(-1),
00400         histogramNormType(HOGDescriptor::L2Hys), L2HysThreshold(0.2), gammaCorrection(true), 
00401         nlevels(HOGDescriptor::DEFAULT_NLEVELS)
00402     {}
00403     
00404     CV_WRAP HOGDescriptor(Size _winSize, Size _blockSize, Size _blockStride,
00405                   Size _cellSize, int _nbins, int _derivAperture=1, double _winSigma=-1,
00406                   int _histogramNormType=HOGDescriptor::L2Hys,
00407                   double _L2HysThreshold=0.2, bool _gammaCorrection=false,
00408                   int _nlevels=HOGDescriptor::DEFAULT_NLEVELS)
00409     : winSize(_winSize), blockSize(_blockSize), blockStride(_blockStride), cellSize(_cellSize),
00410     nbins(_nbins), derivAperture(_derivAperture), winSigma(_winSigma),
00411     histogramNormType(_histogramNormType), L2HysThreshold(_L2HysThreshold),
00412     gammaCorrection(_gammaCorrection), nlevels(_nlevels)
00413     {}
00414     
00415     CV_WRAP HOGDescriptor(const String& filename)
00416     {
00417         load(filename);
00418     }
00419     
00420     HOGDescriptor(const HOGDescriptor& d)
00421     {
00422         d.copyTo(*this);
00423     }
00424     
00425     virtual ~HOGDescriptor() {}
00426     
00427     CV_WRAP size_t getDescriptorSize() const;
00428     CV_WRAP bool checkDetectorSize() const;
00429     CV_WRAP double getWinSigma() const;
00430     
00431     CV_WRAP virtual void setSVMDetector(const vector<float>& _svmdetector);
00432     
00433     virtual bool read(FileNode& fn);
00434     virtual void write(FileStorage& fs, const String& objname) const;
00435     
00436     CV_WRAP virtual bool load(const String& filename, const String& objname=String());
00437     CV_WRAP virtual void save(const String& filename, const String& objname=String()) const;
00438     virtual void copyTo(HOGDescriptor& c) const;
00439     
00440     CV_WRAP virtual void compute(const Mat& img,
00441                          CV_OUT vector<float>& descriptors,
00442                          Size winStride=Size(), Size padding=Size(),
00443                          const vector<Point>& locations=vector<Point>()) const;
00444     CV_WRAP virtual void detect(const Mat& img, CV_OUT vector<Point>& foundLocations,
00445                         double hitThreshold=0, Size winStride=Size(),
00446                         Size padding=Size(),
00447                         const vector<Point>& searchLocations=vector<Point>()) const;
00448     CV_WRAP virtual void detectMultiScale(const Mat& img, CV_OUT vector<Rect>& foundLocations,
00449                                   double hitThreshold=0, Size winStride=Size(),
00450                                   Size padding=Size(), double scale=1.05,
00451                                   int groupThreshold=2) const;
00452     CV_WRAP virtual void computeGradient(const Mat& img, CV_OUT Mat& grad, CV_OUT Mat& angleOfs,
00453                                  Size paddingTL=Size(), Size paddingBR=Size()) const;
00454     
00455     static vector<float> getDefaultPeopleDetector();
00456     
00457     CV_PROP Size winSize;
00458     CV_PROP Size blockSize;
00459     CV_PROP Size blockStride;
00460     CV_PROP Size cellSize;
00461     CV_PROP int nbins;
00462     CV_PROP int derivAperture;
00463     CV_PROP double winSigma;
00464     CV_PROP int histogramNormType;
00465     CV_PROP double L2HysThreshold;
00466     CV_PROP bool gammaCorrection;
00467     CV_PROP vector<float> svmDetector;
00468     CV_PROP int nlevels;
00469 };
00470 
00471 /****************************************************************************************\
00472 *                                Planar Object Detection                                 *
00473 \****************************************************************************************/
00474 
00475 class CV_EXPORTS PlanarObjectDetector
00476 {
00477 public:
00478     PlanarObjectDetector();
00479     PlanarObjectDetector(const FileNode& node);
00480     PlanarObjectDetector(const vector<Mat>& pyr, int _npoints=300,
00481                          int _patchSize=FernClassifier::PATCH_SIZE,
00482                          int _nstructs=FernClassifier::DEFAULT_STRUCTS,
00483                          int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
00484                          int _nviews=FernClassifier::DEFAULT_VIEWS,
00485                          const LDetector& detector=LDetector(),
00486                          const PatchGenerator& patchGenerator=PatchGenerator());
00487     virtual ~PlanarObjectDetector();
00488     virtual void train(const vector<Mat>& pyr, int _npoints=300,
00489                        int _patchSize=FernClassifier::PATCH_SIZE,
00490                        int _nstructs=FernClassifier::DEFAULT_STRUCTS,
00491                        int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
00492                        int _nviews=FernClassifier::DEFAULT_VIEWS,
00493                        const LDetector& detector=LDetector(),
00494                        const PatchGenerator& patchGenerator=PatchGenerator());
00495     virtual void train(const vector<Mat>& pyr, const vector<KeyPoint>& keypoints,
00496                        int _patchSize=FernClassifier::PATCH_SIZE,
00497                        int _nstructs=FernClassifier::DEFAULT_STRUCTS,
00498                        int _structSize=FernClassifier::DEFAULT_STRUCT_SIZE,
00499                        int _nviews=FernClassifier::DEFAULT_VIEWS,
00500                        const LDetector& detector=LDetector(),
00501                        const PatchGenerator& patchGenerator=PatchGenerator());
00502     Rect getModelROI() const;
00503     vector<KeyPoint> getModelPoints() const;
00504     const LDetector& getDetector() const;
00505     const FernClassifier& getClassifier() const;
00506     void setVerbose(bool verbose);
00507 
00508     void read(const FileNode& node);
00509     void write(FileStorage& fs, const String& name=String()) const;
00510     bool operator()(const Mat& image, CV_OUT Mat& H, CV_OUT vector<Point2f>& corners) const;
00511     bool operator()(const vector<Mat>& pyr, const vector<KeyPoint>& keypoints,
00512                                        CV_OUT Mat& H, CV_OUT vector<Point2f>& corners,
00513                                        CV_OUT vector<int>* pairs=0) const;
00514 
00515 protected:
00516     bool verbose;
00517     Rect modelROI;
00518     vector<KeyPoint> modelPoints;
00519     LDetector ldetector;
00520     FernClassifier fernClassifier;
00521 };
00522 
00523 }
00524 
00525 #endif
00526 
00527 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines