opencv 2.2.0
/usr/src/RPM/BUILD/libopencv2.2-2.2.0/modules/video/include/opencv2/video/tracking.hpp
Go to the documentation of this file.
00001 
00005 /*M///////////////////////////////////////////////////////////////////////////////////////
00006 //
00007 //  IMPORTANT: READ BEFORE DOWNLOADING, COPYING, INSTALLING OR USING.
00008 //
00009 //  By downloading, copying, installing or using the software you agree to this license.
00010 //  If you do not agree to this license, do not download, install,
00011 //  copy or use the software.
00012 //
00013 //
00014 //                           License Agreement
00015 //                For Open Source Computer Vision Library
00016 //
00017 // Copyright (C) 2000-2008, Intel Corporation, all rights reserved.
00018 // Copyright (C) 2009, Willow Garage Inc., all rights reserved.
00019 // Third party copyrights are property of their respective owners.
00020 //
00021 // Redistribution and use in source and binary forms, with or without modification,
00022 // are permitted provided that the following conditions are met:
00023 //
00024 //   * Redistribution's of source code must retain the above copyright notice,
00025 //     this list of conditions and the following disclaimer.
00026 //
00027 //   * Redistribution's in binary form must reproduce the above copyright notice,
00028 //     this list of conditions and the following disclaimer in the documentation
00029 //     and/or other materials provided with the distribution.
00030 //
00031 //   * The name of the copyright holders may not be used to endorse or promote products
00032 //     derived from this software without specific prior written permission.
00033 //
00034 // This software is provided by the copyright holders and contributors "as is" and
00035 // any express or implied warranties, including, but not limited to, the implied
00036 // warranties of merchantability and fitness for a particular purpose are disclaimed.
00037 // In no event shall the Intel Corporation or contributors be liable for any direct,
00038 // indirect, incidental, special, exemplary, or consequential damages
00039 // (including, but not limited to, procurement of substitute goods or services;
00040 // loss of use, data, or profits; or business interruption) however caused
00041 // and on any theory of liability, whether in contract, strict liability,
00042 // or tort (including negligence or otherwise) arising in any way out of
00043 // the use of this software, even if advised of the possibility of such damage.
00044 //
00045 //M*/
00046 
00047 #ifndef __OPENCV_TRACKING_HPP__
00048 #define __OPENCV_TRACKING_HPP__
00049 
00050 #include "opencv2/core/core.hpp"
00051 #include "opencv2/imgproc/imgproc_c.h"
00052 
00053 #ifdef __cplusplus
00054 extern "C" {
00055 #endif
00056 
00057 /****************************************************************************************\
00058 *                                  Motion Analysis                                       *
00059 \****************************************************************************************/
00060 
00061 /************************************ optical flow ***************************************/
00062 
00063 /* Calculates optical flow for 2 images using classical Lucas & Kanade algorithm */
00064 CVAPI(void)  cvCalcOpticalFlowLK( const CvArr* prev, const CvArr* curr,
00065                                   CvSize win_size, CvArr* velx, CvArr* vely );
00066 
00067 /* Calculates optical flow for 2 images using block matching algorithm */
00068 CVAPI(void)  cvCalcOpticalFlowBM( const CvArr* prev, const CvArr* curr,
00069                                   CvSize block_size, CvSize shift_size,
00070                                   CvSize max_range, int use_previous,
00071                                   CvArr* velx, CvArr* vely );
00072 
00073 /* Calculates Optical flow for 2 images using Horn & Schunck algorithm */
00074 CVAPI(void)  cvCalcOpticalFlowHS( const CvArr* prev, const CvArr* curr,
00075                                   int use_previous, CvArr* velx, CvArr* vely,
00076                                   double lambda, CvTermCriteria criteria );
00077 
00078 #define  CV_LKFLOW_PYR_A_READY       1
00079 #define  CV_LKFLOW_PYR_B_READY       2
00080 #define  CV_LKFLOW_INITIAL_GUESSES   4
00081 #define  CV_LKFLOW_GET_MIN_EIGENVALS 8
00082 
00083 /* It is Lucas & Kanade method, modified to use pyramids.
00084    Also it does several iterations to get optical flow for
00085    every point at every pyramid level.
00086    Calculates optical flow between two images for certain set of points (i.e.
00087    it is a "sparse" optical flow, which is opposite to the previous 3 methods) */
00088 CVAPI(void)  cvCalcOpticalFlowPyrLK( const CvArr*  prev, const CvArr*  curr,
00089                                      CvArr*  prev_pyr, CvArr*  curr_pyr,
00090                                      const CvPoint2D32f* prev_features,
00091                                      CvPoint2D32f* curr_features,
00092                                      int       count,
00093                                      CvSize    win_size,
00094                                      int       level,
00095                                      char*     status,
00096                                      float*    track_error,
00097                                      CvTermCriteria criteria,
00098                                      int       flags );
00099 
00100 
00101 /* Modification of a previous sparse optical flow algorithm to calculate
00102    affine flow */
00103 CVAPI(void)  cvCalcAffineFlowPyrLK( const CvArr*  prev, const CvArr*  curr,
00104                                     CvArr*  prev_pyr, CvArr*  curr_pyr,
00105                                     const CvPoint2D32f* prev_features,
00106                                     CvPoint2D32f* curr_features,
00107                                     float* matrices, int  count,
00108                                     CvSize win_size, int  level,
00109                                     char* status, float* track_error,
00110                                     CvTermCriteria criteria, int flags );
00111 
00112 /* Estimate rigid transformation between 2 images or 2 point sets */
00113 CVAPI(int)  cvEstimateRigidTransform( const CvArr* A, const CvArr* B,
00114                                       CvMat* M, int full_affine );
00115 
00116 /* Estimate optical flow for each pixel using the two-frame G. Farneback algorithm */
00117 CVAPI(void) cvCalcOpticalFlowFarneback( const CvArr* prev, const CvArr* next,
00118                                         CvArr* flow, double pyr_scale, int levels,
00119                                         int winsize, int iterations, int poly_n,
00120                                         double poly_sigma, int flags );
00121 
00122 /********************************* motion templates *************************************/
00123 
00124 /****************************************************************************************\
00125 *        All the motion template functions work only with single channel images.         *
00126 *        Silhouette image must have depth IPL_DEPTH_8U or IPL_DEPTH_8S                   *
00127 *        Motion history image must have depth IPL_DEPTH_32F,                             *
00128 *        Gradient mask - IPL_DEPTH_8U or IPL_DEPTH_8S,                                   *
00129 *        Motion orientation image - IPL_DEPTH_32F                                        *
00130 *        Segmentation mask - IPL_DEPTH_32F                                               *
00131 *        All the angles are in degrees, all the times are in milliseconds                *
00132 \****************************************************************************************/
00133 
00134 /* Updates motion history image given motion silhouette */
00135 CVAPI(void)    cvUpdateMotionHistory( const CvArr* silhouette, CvArr* mhi,
00136                                       double timestamp, double duration );
00137 
00138 /* Calculates gradient of the motion history image and fills
00139    a mask indicating where the gradient is valid */
00140 CVAPI(void)    cvCalcMotionGradient( const CvArr* mhi, CvArr* mask, CvArr* orientation,
00141                                      double delta1, double delta2,
00142                                      int aperture_size CV_DEFAULT(3));
00143 
00144 /* Calculates average motion direction within a selected motion region
00145    (region can be selected by setting ROIs and/or by composing a valid gradient mask
00146    with the region mask) */
00147 CVAPI(double)  cvCalcGlobalOrientation( const CvArr* orientation, const CvArr* mask,
00148                                         const CvArr* mhi, double timestamp,
00149                                         double duration );
00150 
00151 /* Splits a motion history image into a few parts corresponding to separate independent motions
00152    (e.g. left hand, right hand) */
00153 CVAPI(CvSeq*)  cvSegmentMotion( const CvArr* mhi, CvArr* seg_mask,
00154                                 CvMemStorage* storage,
00155                                 double timestamp, double seg_thresh );
00156 
00157 /****************************************************************************************\
00158 *                                       Tracking                                         *
00159 \****************************************************************************************/
00160 
00161 /* Implements CAMSHIFT algorithm - determines object position, size and orientation
00162    from the object histogram back project (extension of meanshift) */
00163 CVAPI(int)  cvCamShift( const CvArr* prob_image, CvRect  window,
00164                         CvTermCriteria criteria, CvConnectedComp* comp,
00165                         CvBox2D* box CV_DEFAULT(NULL) );
00166 
00167 /* Implements MeanShift algorithm - determines object position
00168    from the object histogram back project */
00169 CVAPI(int)  cvMeanShift( const CvArr* prob_image, CvRect  window,
00170                          CvTermCriteria criteria, CvConnectedComp* comp );
00171 
00172 /*
00173 standard Kalman filter (in G. Welch' and G. Bishop's notation):
00174 
00175   x(k)=A*x(k-1)+B*u(k)+w(k)  p(w)~N(0,Q)
00176   z(k)=H*x(k)+v(k),   p(v)~N(0,R)
00177 */
00178 typedef struct CvKalman
00179 {
00180     int MP;                     /* number of measurement vector dimensions */
00181     int DP;                     /* number of state vector dimensions */
00182     int CP;                     /* number of control vector dimensions */
00183 
00184     /* backward compatibility fields */
00185 #if 1
00186     float* PosterState;         /* =state_pre->data.fl */
00187     float* PriorState;          /* =state_post->data.fl */
00188     float* DynamMatr;           /* =transition_matrix->data.fl */
00189     float* MeasurementMatr;     /* =measurement_matrix->data.fl */
00190     float* MNCovariance;        /* =measurement_noise_cov->data.fl */
00191     float* PNCovariance;        /* =process_noise_cov->data.fl */
00192     float* KalmGainMatr;        /* =gain->data.fl */
00193     float* PriorErrorCovariance;/* =error_cov_pre->data.fl */
00194     float* PosterErrorCovariance;/* =error_cov_post->data.fl */
00195     float* Temp1;               /* temp1->data.fl */
00196     float* Temp2;               /* temp2->data.fl */
00197 #endif
00198 
00199     CvMat* state_pre;           /* predicted state (x'(k)):
00200                                     x(k)=A*x(k-1)+B*u(k) */
00201     CvMat* state_post;          /* corrected state (x(k)):
00202                                     x(k)=x'(k)+K(k)*(z(k)-H*x'(k)) */
00203     CvMat* transition_matrix;   /* state transition matrix (A) */
00204     CvMat* control_matrix;      /* control matrix (B)
00205                                    (it is not used if there is no control)*/
00206     CvMat* measurement_matrix;  /* measurement matrix (H) */
00207     CvMat* process_noise_cov;   /* process noise covariance matrix (Q) */
00208     CvMat* measurement_noise_cov; /* measurement noise covariance matrix (R) */
00209     CvMat* error_cov_pre;       /* priori error estimate covariance matrix (P'(k)):
00210                                     P'(k)=A*P(k-1)*At + Q)*/
00211     CvMat* gain;                /* Kalman gain matrix (K(k)):
00212                                     K(k)=P'(k)*Ht*inv(H*P'(k)*Ht+R)*/
00213     CvMat* error_cov_post;      /* posteriori error estimate covariance matrix (P(k)):
00214                                     P(k)=(I-K(k)*H)*P'(k) */
00215     CvMat* temp1;               /* temporary matrices */
00216     CvMat* temp2;
00217     CvMat* temp3;
00218     CvMat* temp4;
00219     CvMat* temp5;
00220 } CvKalman;
00221 
00222 /* Creates Kalman filter and sets A, B, Q, R and state to some initial values */
00223 CVAPI(CvKalman*) cvCreateKalman( int dynam_params, int measure_params,
00224                                  int control_params CV_DEFAULT(0));
00225 
00226 /* Releases Kalman filter state */
00227 CVAPI(void)  cvReleaseKalman( CvKalman** kalman);
00228 
00229 /* Updates Kalman filter by time (predicts future state of the system) */
00230 CVAPI(const CvMat*)  cvKalmanPredict( CvKalman* kalman,
00231                                       const CvMat* control CV_DEFAULT(NULL));
00232 
00233 /* Updates Kalman filter by measurement
00234    (corrects state of the system and internal matrices) */
00235 CVAPI(const CvMat*)  cvKalmanCorrect( CvKalman* kalman, const CvMat* measurement );
00236 
00237 #define cvKalmanUpdateByTime  cvKalmanPredict
00238 #define cvKalmanUpdateByMeasurement cvKalmanCorrect
00239     
00240 #ifdef __cplusplus
00241 }
00242 
00243 namespace cv
00244 {
00245     
00247 CV_EXPORTS_W void updateMotionHistory( const Mat& silhouette, Mat& mhi,
00248                                      double timestamp, double duration );
00249 
00251 CV_EXPORTS_W void calcMotionGradient( const Mat& mhi, CV_OUT Mat& mask,
00252                                       CV_OUT Mat& orientation,
00253                                       double delta1, double delta2,
00254                                       int apertureSize=3 );
00255 
00257 CV_EXPORTS_W double calcGlobalOrientation( const Mat& orientation, const Mat& mask,
00258                                            const Mat& mhi, double timestamp,
00259                                            double duration );
00260 // TODO: need good API for cvSegmentMotion
00261 
00263 CV_EXPORTS_W RotatedRect CamShift( const Mat& probImage, CV_IN_OUT Rect& window,
00264                                    TermCriteria criteria );
00265 
00267 CV_EXPORTS_W int meanShift( const Mat& probImage, CV_IN_OUT Rect& window,
00268                             TermCriteria criteria );
00269 
00277 class CV_EXPORTS_W KalmanFilter
00278 {
00279 public:
00281     CV_WRAP KalmanFilter();
00283     CV_WRAP KalmanFilter(int dynamParams, int measureParams, int controlParams=0, int type=CV_32F);
00285     void init(int dynamParams, int measureParams, int controlParams=0, int type=CV_32F);
00286 
00288     CV_WRAP const Mat& predict(const Mat& control=Mat());
00290     CV_WRAP const Mat& correct(const Mat& measurement);
00291 
00292     Mat statePre;           
00293     Mat statePost;          
00294     Mat transitionMatrix;   
00295     Mat controlMatrix;      
00296     Mat measurementMatrix;  
00297     Mat processNoiseCov;    
00298     Mat measurementNoiseCov;
00299     Mat errorCovPre;        
00300     Mat gain;               
00301     Mat errorCovPost;       
00302     
00303     // temporary matrices
00304     Mat temp1;
00305     Mat temp2;
00306     Mat temp3;
00307     Mat temp4;
00308     Mat temp5;
00309 };
00310 
00311 
00312 enum { OPTFLOW_USE_INITIAL_FLOW=4, OPTFLOW_FARNEBACK_GAUSSIAN=256 };
00313 
00315 CV_EXPORTS_W void calcOpticalFlowPyrLK( const Mat& prevImg, const Mat& nextImg,
00316                            const vector<Point2f>& prevPts, CV_OUT vector<Point2f>& nextPts,
00317                            CV_OUT vector<uchar>& status, CV_OUT vector<float>& err,
00318                            Size winSize=Size(15,15), int maxLevel=3,
00319                            TermCriteria criteria=TermCriteria(
00320                             TermCriteria::COUNT+TermCriteria::EPS,
00321                             30, 0.01),
00322                            double derivLambda=0.5,
00323                            int flags=0 );
00324 
00326 CV_EXPORTS_W void calcOpticalFlowFarneback( const Mat& prev, const Mat& next,
00327                            CV_OUT Mat& flow, double pyr_scale, int levels, int winsize,
00328                            int iterations, int poly_n, double poly_sigma, int flags );
00329 
00330 }
00331 
00332 #endif
00333 
00334 #endif
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines