opencv 2.2.0
/usr/src/RPM/BUILD/libopencv2.2-2.2.0/modules/legacy/include/opencv2/legacy/legacy.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 //                        Intel License Agreement
00011 //                For Open Source Computer Vision Library
00012 //
00013 // Copyright (C) 2000, Intel Corporation, all rights reserved.
00014 // Third party copyrights are property of their respective owners.
00015 //
00016 // Redistribution and use in source and binary forms, with or without modification,
00017 // are permitted provided that the following conditions are met:
00018 //
00019 //   * Redistribution's of source code must retain the above copyright notice,
00020 //     this list of conditions and the following disclaimer.
00021 //
00022 //   * Redistribution's in binary form must reproduce the above copyright notice,
00023 //     this list of conditions and the following disclaimer in the documentation
00024 //     and/or other materials provided with the distribution.
00025 //
00026 //   * The name of Intel Corporation may not be used to endorse or promote products
00027 //     derived from this software without specific prior written permission.
00028 //
00029 // This software is provided by the copyright holders and contributors "as is" and
00030 // any express or implied warranties, including, but not limited to, the implied
00031 // warranties of merchantability and fitness for a particular purpose are disclaimed.
00032 // In no event shall the Intel Corporation or contributors be liable for any direct,
00033 // indirect, incidental, special, exemplary, or consequential damages
00034 // (including, but not limited to, procurement of substitute goods or services;
00035 // loss of use, data, or profits; or business interruption) however caused
00036 // and on any theory of liability, whether in contract, strict liability,
00037 // or tort (including negligence or otherwise) arising in any way out of
00038 // the use of this software, even if advised of the possibility of such damage.
00039 //
00040 //M*/
00041 
00042 #ifndef __OPENCV_LEGACY_HPP__
00043 #define __OPENCV_LEGACY_HPP__
00044 
00045 #include "opencv2/imgproc/imgproc.hpp"
00046 #include "opencv2/imgproc/imgproc_c.h"
00047 #include "opencv2/features2d/features2d.hpp"
00048 #include "opencv2/calib3d/calib3d.hpp"
00049 
00050 #ifdef __cplusplus
00051 extern "C" {
00052 #endif
00053 
00054 CVAPI(CvSeq*) cvSegmentImage( const CvArr* srcarr, CvArr* dstarr,
00055                                     double canny_threshold,
00056                                     double ffill_threshold,
00057                                     CvMemStorage* storage );
00058 
00059 /****************************************************************************************\
00060 *                                  Eigen objects                                         *
00061 \****************************************************************************************/
00062 
00063 typedef int (CV_CDECL * CvCallback)(int index, void* buffer, void* user_data);
00064 typedef union
00065 {
00066     CvCallback callback;
00067     void* data;
00068 }
00069 CvInput;
00070 
00071 #define CV_EIGOBJ_NO_CALLBACK     0
00072 #define CV_EIGOBJ_INPUT_CALLBACK  1
00073 #define CV_EIGOBJ_OUTPUT_CALLBACK 2
00074 #define CV_EIGOBJ_BOTH_CALLBACK   3
00075 
00076 /* Calculates covariation matrix of a set of arrays */
00077 CVAPI(void)  cvCalcCovarMatrixEx( int nObjects, void* input, int ioFlags,
00078                                   int ioBufSize, uchar* buffer, void* userData,
00079                                   IplImage* avg, float* covarMatrix );
00080 
00081 /* Calculates eigen values and vectors of covariation matrix of a set of
00082    arrays */
00083 CVAPI(void)  cvCalcEigenObjects( int nObjects, void* input, void* output,
00084                                  int ioFlags, int ioBufSize, void* userData,
00085                                  CvTermCriteria* calcLimit, IplImage* avg,
00086                                  float* eigVals );
00087 
00088 /* Calculates dot product (obj - avg) * eigObj (i.e. projects image to eigen vector) */
00089 CVAPI(double)  cvCalcDecompCoeff( IplImage* obj, IplImage* eigObj, IplImage* avg );
00090 
00091 /* Projects image to eigen space (finds all decomposion coefficients */
00092 CVAPI(void)  cvEigenDecomposite( IplImage* obj, int nEigObjs, void* eigInput,
00093                                  int ioFlags, void* userData, IplImage* avg,
00094                                  float* coeffs );
00095 
00096 /* Projects original objects used to calculate eigen space basis to that space */
00097 CVAPI(void)  cvEigenProjection( void* eigInput, int nEigObjs, int ioFlags,
00098                                 void* userData, float* coeffs, IplImage* avg,
00099                                 IplImage* proj );
00100 
00101 /****************************************************************************************\
00102 *                                       1D/2D HMM                                        *
00103 \****************************************************************************************/
00104 
00105 typedef struct CvImgObsInfo
00106 {
00107     int obs_x;
00108     int obs_y;
00109     int obs_size;
00110     float* obs;//consequtive observations
00111 
00112     int* state;/* arr of pairs superstate/state to which observation belong */
00113     int* mix;  /* number of mixture to which observation belong */
00114 
00115 } CvImgObsInfo;/*struct for 1 image*/
00116 
00117 typedef CvImgObsInfo Cv1DObsInfo;
00118 
00119 typedef struct CvEHMMState
00120 {
00121     int num_mix;        /*number of mixtures in this state*/
00122     float* mu;          /*mean vectors corresponding to each mixture*/
00123     float* inv_var;     /* square root of inversed variances corresp. to each mixture*/
00124     float* log_var_val; /* sum of 0.5 (LN2PI + ln(variance[i]) ) for i=1,n */
00125     float* weight;      /*array of mixture weights. Summ of all weights in state is 1. */
00126 
00127 } CvEHMMState;
00128 
00129 typedef struct CvEHMM
00130 {
00131     int level; /* 0 - lowest(i.e its states are real states), ..... */
00132     int num_states; /* number of HMM states */
00133     float*  transP;/*transition probab. matrices for states */
00134     float** obsProb; /* if level == 0 - array of brob matrices corresponding to hmm
00135                         if level == 1 - martix of matrices */
00136     union
00137     {
00138         CvEHMMState* state; /* if level == 0 points to real states array,
00139                                if not - points to embedded hmms */
00140         struct CvEHMM* ehmm; /* pointer to an embedded model or NULL, if it is a leaf */
00141     } u;
00142 
00143 } CvEHMM;
00144 
00145 /*CVAPI(int)  icvCreate1DHMM( CvEHMM** this_hmm,
00146                                    int state_number, int* num_mix, int obs_size );
00147 
00148 CVAPI(int)  icvRelease1DHMM( CvEHMM** phmm );
00149 
00150 CVAPI(int)  icvUniform1DSegm( Cv1DObsInfo* obs_info, CvEHMM* hmm );
00151 
00152 CVAPI(int)  icvInit1DMixSegm( Cv1DObsInfo** obs_info_array, int num_img, CvEHMM* hmm);
00153 
00154 CVAPI(int)  icvEstimate1DHMMStateParams( CvImgObsInfo** obs_info_array, int num_img, CvEHMM* hmm);
00155 
00156 CVAPI(int)  icvEstimate1DObsProb( CvImgObsInfo* obs_info, CvEHMM* hmm );
00157 
00158 CVAPI(int)  icvEstimate1DTransProb( Cv1DObsInfo** obs_info_array,
00159                                            int num_seq,
00160                                            CvEHMM* hmm );
00161 
00162 CVAPI(float)  icvViterbi( Cv1DObsInfo* obs_info, CvEHMM* hmm);
00163 
00164 CVAPI(int)  icv1DMixSegmL2( CvImgObsInfo** obs_info_array, int num_img, CvEHMM* hmm );*/
00165 
00166 /*********************************** Embedded HMMs *************************************/
00167 
00168 /* Creates 2D HMM */
00169 CVAPI(CvEHMM*)  cvCreate2DHMM( int* stateNumber, int* numMix, int obsSize );
00170 
00171 /* Releases HMM */
00172 CVAPI(void)  cvRelease2DHMM( CvEHMM** hmm );
00173 
00174 #define CV_COUNT_OBS(roi, win, delta, numObs )                                       \
00175 {                                                                                    \
00176    (numObs)->width  =((roi)->width  -(win)->width  +(delta)->width)/(delta)->width;  \
00177    (numObs)->height =((roi)->height -(win)->height +(delta)->height)/(delta)->height;\
00178 }
00179 
00180 /* Creates storage for observation vectors */
00181 CVAPI(CvImgObsInfo*)  cvCreateObsInfo( CvSize numObs, int obsSize );
00182 
00183 /* Releases storage for observation vectors */
00184 CVAPI(void)  cvReleaseObsInfo( CvImgObsInfo** obs_info );
00185 
00186 
00187 /* The function takes an image on input and and returns the sequnce of observations
00188    to be used with an embedded HMM; Each observation is top-left block of DCT
00189    coefficient matrix */
00190 CVAPI(void)  cvImgToObs_DCT( const CvArr* arr, float* obs, CvSize dctSize,
00191                              CvSize obsSize, CvSize delta );
00192 
00193 
00194 /* Uniformly segments all observation vectors extracted from image */
00195 CVAPI(void)  cvUniformImgSegm( CvImgObsInfo* obs_info, CvEHMM* ehmm );
00196 
00197 /* Does mixture segmentation of the states of embedded HMM */
00198 CVAPI(void)  cvInitMixSegm( CvImgObsInfo** obs_info_array,
00199                             int num_img, CvEHMM* hmm );
00200 
00201 /* Function calculates means, variances, weights of every Gaussian mixture
00202    of every low-level state of embedded HMM */
00203 CVAPI(void)  cvEstimateHMMStateParams( CvImgObsInfo** obs_info_array,
00204                                        int num_img, CvEHMM* hmm );
00205 
00206 /* Function computes transition probability matrices of embedded HMM
00207    given observations segmentation */
00208 CVAPI(void)  cvEstimateTransProb( CvImgObsInfo** obs_info_array,
00209                                   int num_img, CvEHMM* hmm );
00210 
00211 /* Function computes probabilities of appearing observations at any state
00212    (i.e. computes P(obs|state) for every pair(obs,state)) */
00213 CVAPI(void)  cvEstimateObsProb( CvImgObsInfo* obs_info,
00214                                 CvEHMM* hmm );
00215 
00216 /* Runs Viterbi algorithm for embedded HMM */
00217 CVAPI(float)  cvEViterbi( CvImgObsInfo* obs_info, CvEHMM* hmm );
00218 
00219 
00220 /* Function clusters observation vectors from several images
00221    given observations segmentation.
00222    Euclidean distance used for clustering vectors.
00223    Centers of clusters are given means of every mixture */
00224 CVAPI(void)  cvMixSegmL2( CvImgObsInfo** obs_info_array,
00225                           int num_img, CvEHMM* hmm );
00226 
00227 /****************************************************************************************\
00228 *               A few functions from old stereo gesture recognition demosions            *
00229 \****************************************************************************************/
00230 
00231 /* Creates hand mask image given several points on the hand */
00232 CVAPI(void)  cvCreateHandMask( CvSeq* hand_points,
00233                                    IplImage *img_mask, CvRect *roi);
00234 
00235 /* Finds hand region in range image data */
00236 CVAPI(void)  cvFindHandRegion (CvPoint3D32f* points, int count,
00237                                 CvSeq* indexs,
00238                                 float* line, CvSize2D32f size, int flag,
00239                                 CvPoint3D32f* center,
00240                                 CvMemStorage* storage, CvSeq **numbers);
00241 
00242 /* Finds hand region in range image data (advanced version) */
00243 CVAPI(void)  cvFindHandRegionA( CvPoint3D32f* points, int count,
00244                                 CvSeq* indexs,
00245                                 float* line, CvSize2D32f size, int jc,
00246                                 CvPoint3D32f* center,
00247                                 CvMemStorage* storage, CvSeq **numbers);
00248 
00249 /* Calculates the cooficients of the homography matrix */
00250 CVAPI(void)  cvCalcImageHomography( float* line, CvPoint3D32f* center,
00251                                     float* intrinsic, float* homography );
00252 
00253 /****************************************************************************************\
00254 *                           Additional operations on Subdivisions                        *
00255 \****************************************************************************************/
00256 
00257 // paints voronoi diagram: just demo function
00258 CVAPI(void)  icvDrawMosaic( CvSubdiv2D* subdiv, IplImage* src, IplImage* dst );
00259 
00260 // checks planar subdivision for correctness. It is not an absolute check,
00261 // but it verifies some relations between quad-edges
00262 CVAPI(int)   icvSubdiv2DCheck( CvSubdiv2D* subdiv );
00263 
00264 // returns squared distance between two 2D points with floating-point coordinates.
00265 CV_INLINE double icvSqDist2D32f( CvPoint2D32f pt1, CvPoint2D32f pt2 )
00266 {
00267     double dx = pt1.x - pt2.x;
00268     double dy = pt1.y - pt2.y;
00269 
00270     return dx*dx + dy*dy;
00271 }
00272 
00273 
00274 /****************************************************************************************\
00275 *                           More operations on sequences                                 *
00276 \****************************************************************************************/
00277 
00278 /*****************************************************************************************/
00279 
00280 #define CV_CURRENT_INT( reader ) (*((int *)(reader).ptr))
00281 #define CV_PREV_INT( reader ) (*((int *)(reader).prev_elem))
00282 
00283 #define  CV_GRAPH_WEIGHTED_VERTEX_FIELDS() CV_GRAPH_VERTEX_FIELDS()\
00284     float weight;
00285 
00286 #define  CV_GRAPH_WEIGHTED_EDGE_FIELDS() CV_GRAPH_EDGE_FIELDS()
00287 
00288 typedef struct CvGraphWeightedVtx
00289 {
00290     CV_GRAPH_WEIGHTED_VERTEX_FIELDS()
00291 } CvGraphWeightedVtx;
00292 
00293 typedef struct CvGraphWeightedEdge
00294 {
00295     CV_GRAPH_WEIGHTED_EDGE_FIELDS()
00296 } CvGraphWeightedEdge;
00297 
00298 typedef enum CvGraphWeightType
00299 {
00300     CV_NOT_WEIGHTED,
00301     CV_WEIGHTED_VTX,
00302     CV_WEIGHTED_EDGE,
00303     CV_WEIGHTED_ALL
00304 } CvGraphWeightType;
00305 
00306 
00307 /* Calculates histogram of a contour */
00308 CVAPI(void)  cvCalcPGH( const CvSeq* contour, CvHistogram* hist );
00309 
00310 #define CV_DOMINANT_IPAN 1
00311 
00312 /* Finds high-curvature points of the contour */
00313 CVAPI(CvSeq*) cvFindDominantPoints( CvSeq* contour, CvMemStorage* storage,
00314                                    int method CV_DEFAULT(CV_DOMINANT_IPAN),
00315                                    double parameter1 CV_DEFAULT(0),
00316                                    double parameter2 CV_DEFAULT(0),
00317                                    double parameter3 CV_DEFAULT(0),
00318                                    double parameter4 CV_DEFAULT(0));
00319 
00320 /*****************************************************************************************/
00321 
00322 
00323 /*******************************Stereo correspondence*************************************/
00324 
00325 typedef struct CvCliqueFinder
00326 {   
00327     CvGraph* graph;
00328     int**    adj_matr;
00329     int N; //graph size
00330 
00331     // stacks, counters etc/
00332     int k; //stack size
00333     int* current_comp;
00334     int** All;
00335     
00336     int* ne;
00337     int* ce;
00338     int* fixp; //node with minimal disconnections
00339     int* nod;
00340     int* s; //for selected candidate
00341     int status;
00342     int best_score;
00343     int weighted;
00344     int weighted_edges;    
00345     float best_weight;
00346     float* edge_weights;
00347     float* vertex_weights;
00348     float* cur_weight;
00349     float* cand_weight;
00350 
00351 } CvCliqueFinder;
00352 
00353 #define CLIQUE_TIME_OFF 2
00354 #define CLIQUE_FOUND 1
00355 #define CLIQUE_END   0
00356 
00357 /*CVAPI(void) cvStartFindCliques( CvGraph* graph, CvCliqueFinder* finder, int reverse, 
00358                                    int weighted CV_DEFAULT(0),  int weighted_edges CV_DEFAULT(0));
00359 CVAPI(int) cvFindNextMaximalClique( CvCliqueFinder* finder, int* clock_rest CV_DEFAULT(0) ); 
00360 CVAPI(void) cvEndFindCliques( CvCliqueFinder* finder );
00361 
00362 CVAPI(void) cvBronKerbosch( CvGraph* graph );*/
00363 
00364 
00365 /*F///////////////////////////////////////////////////////////////////////////////////////
00366 //
00367 //    Name:    cvSubgraphWeight
00368 //    Purpose: finds weight of subgraph in a graph
00369 //    Context:
00370 //    Parameters:
00371 //      graph - input graph.
00372 //      subgraph - sequence of pairwise different ints.  These are indices of vertices of subgraph.
00373 //      weight_type - describes the way we measure weight.
00374 //            one of the following:
00375 //            CV_NOT_WEIGHTED - weight of a clique is simply its size
00376 //            CV_WEIGHTED_VTX - weight of a clique is the sum of weights of its vertices
00377 //            CV_WEIGHTED_EDGE - the same but edges
00378 //            CV_WEIGHTED_ALL - the same but both edges and vertices
00379 //      weight_vtx - optional vector of floats, with size = graph->total.
00380 //            If weight_type is either CV_WEIGHTED_VTX or CV_WEIGHTED_ALL
00381 //            weights of vertices must be provided.  If weight_vtx not zero
00382 //            these weights considered to be here, otherwise function assumes
00383 //            that vertices of graph are inherited from CvGraphWeightedVtx.
00384 //      weight_edge - optional matrix of floats, of width and height = graph->total.
00385 //            If weight_type is either CV_WEIGHTED_EDGE or CV_WEIGHTED_ALL
00386 //            weights of edges ought to be supplied.  If weight_edge is not zero
00387 //            function finds them here, otherwise function expects
00388 //            edges of graph to be inherited from CvGraphWeightedEdge.
00389 //            If this parameter is not zero structure of the graph is determined from matrix
00390 //            rather than from CvGraphEdge's.  In particular, elements corresponding to
00391 //            absent edges should be zero.
00392 //    Returns:
00393 //      weight of subgraph.
00394 //    Notes:
00395 //F*/
00396 /*CVAPI(float) cvSubgraphWeight( CvGraph *graph, CvSeq *subgraph,
00397                                   CvGraphWeightType weight_type CV_DEFAULT(CV_NOT_WEIGHTED),
00398                                   CvVect32f weight_vtx CV_DEFAULT(0),
00399                                   CvMatr32f weight_edge CV_DEFAULT(0) );*/
00400 
00401 
00402 /*F///////////////////////////////////////////////////////////////////////////////////////
00403 //
00404 //    Name:    cvFindCliqueEx
00405 //    Purpose: tries to find clique with maximum possible weight in a graph
00406 //    Context:
00407 //    Parameters:
00408 //      graph - input graph.
00409 //      storage - memory storage to be used by the result.
00410 //      is_complementary - optional flag showing whether function should seek for clique
00411 //            in complementary graph.
00412 //      weight_type - describes our notion about weight.
00413 //            one of the following:
00414 //            CV_NOT_WEIGHTED - weight of a clique is simply its size
00415 //            CV_WEIGHTED_VTX - weight of a clique is the sum of weights of its vertices
00416 //            CV_WEIGHTED_EDGE - the same but edges
00417 //            CV_WEIGHTED_ALL - the same but both edges and vertices
00418 //      weight_vtx - optional vector of floats, with size = graph->total.
00419 //            If weight_type is either CV_WEIGHTED_VTX or CV_WEIGHTED_ALL
00420 //            weights of vertices must be provided.  If weight_vtx not zero
00421 //            these weights considered to be here, otherwise function assumes
00422 //            that vertices of graph are inherited from CvGraphWeightedVtx.
00423 //      weight_edge - optional matrix of floats, of width and height = graph->total.
00424 //            If weight_type is either CV_WEIGHTED_EDGE or CV_WEIGHTED_ALL
00425 //            weights of edges ought to be supplied.  If weight_edge is not zero
00426 //            function finds them here, otherwise function expects
00427 //            edges of graph to be inherited from CvGraphWeightedEdge.
00428 //            Note that in case of CV_WEIGHTED_EDGE or CV_WEIGHTED_ALL
00429 //            nonzero is_complementary implies nonzero weight_edge.
00430 //      start_clique - optional sequence of pairwise different ints.  They are indices of
00431 //            vertices that shall be present in the output clique.
00432 //      subgraph_of_ban - optional sequence of (maybe equal) ints.  They are indices of
00433 //            vertices that shall not be present in the output clique.
00434 //      clique_weight_ptr - optional output parameter.  Weight of found clique stored here.
00435 //      num_generations - optional number of generations in evolutionary part of algorithm,
00436 //            zero forces to return first found clique.
00437 //      quality - optional parameter determining degree of required quality/speed tradeoff.
00438 //            Must be in the range from 0 to 9.
00439 //            0 is fast and dirty, 9 is slow but hopefully yields good clique.
00440 //    Returns:
00441 //      sequence of pairwise different ints.
00442 //      These are indices of vertices that form found clique.
00443 //    Notes:
00444 //      in cases of CV_WEIGHTED_EDGE and CV_WEIGHTED_ALL weights should be nonnegative.
00445 //      start_clique has a priority over subgraph_of_ban.
00446 //F*/
00447 /*CVAPI(CvSeq*) cvFindCliqueEx( CvGraph *graph, CvMemStorage *storage,
00448                                  int is_complementary CV_DEFAULT(0),
00449                                  CvGraphWeightType weight_type CV_DEFAULT(CV_NOT_WEIGHTED),
00450                                  CvVect32f weight_vtx CV_DEFAULT(0),
00451                                  CvMatr32f weight_edge CV_DEFAULT(0),
00452                                  CvSeq *start_clique CV_DEFAULT(0),
00453                                  CvSeq *subgraph_of_ban CV_DEFAULT(0),
00454                                  float *clique_weight_ptr CV_DEFAULT(0),
00455                                  int num_generations CV_DEFAULT(3),
00456                                  int quality CV_DEFAULT(2) );*/
00457 
00458 
00459 #define CV_UNDEF_SC_PARAM         12345 //default value of parameters
00460 
00461 #define CV_IDP_BIRCHFIELD_PARAM1  25    
00462 #define CV_IDP_BIRCHFIELD_PARAM2  5
00463 #define CV_IDP_BIRCHFIELD_PARAM3  12
00464 #define CV_IDP_BIRCHFIELD_PARAM4  15
00465 #define CV_IDP_BIRCHFIELD_PARAM5  25
00466 
00467 
00468 #define  CV_DISPARITY_BIRCHFIELD  0    
00469 
00470 
00471 /*F///////////////////////////////////////////////////////////////////////////
00472 //
00473 //    Name:    cvFindStereoCorrespondence
00474 //    Purpose: find stereo correspondence on stereo-pair
00475 //    Context:
00476 //    Parameters:
00477 //      leftImage - left image of stereo-pair (format 8uC1).
00478 //      rightImage - right image of stereo-pair (format 8uC1).
00479 //   mode - mode of correspondence retrieval (now CV_DISPARITY_BIRCHFIELD only)
00480 //      dispImage - destination disparity image
00481 //      maxDisparity - maximal disparity 
00482 //      param1, param2, param3, param4, param5 - parameters of algorithm
00483 //    Returns:
00484 //    Notes:
00485 //      Images must be rectified.
00486 //      All images must have format 8uC1.
00487 //F*/
00488 CVAPI(void) 
00489 cvFindStereoCorrespondence( 
00490                    const  CvArr* leftImage, const  CvArr* rightImage,
00491                    int     mode,
00492                    CvArr*  dispImage,
00493                    int     maxDisparity,                                
00494                    double  param1 CV_DEFAULT(CV_UNDEF_SC_PARAM), 
00495                    double  param2 CV_DEFAULT(CV_UNDEF_SC_PARAM), 
00496                    double  param3 CV_DEFAULT(CV_UNDEF_SC_PARAM), 
00497                    double  param4 CV_DEFAULT(CV_UNDEF_SC_PARAM), 
00498                    double  param5 CV_DEFAULT(CV_UNDEF_SC_PARAM) );
00499 
00500 /*****************************************************************************************/
00501 /************ Epiline functions *******************/
00502 
00503 
00504 
00505 typedef struct CvStereoLineCoeff
00506 {
00507     double Xcoef;
00508     double XcoefA;
00509     double XcoefB;
00510     double XcoefAB;
00511 
00512     double Ycoef;
00513     double YcoefA;
00514     double YcoefB;
00515     double YcoefAB;
00516 
00517     double Zcoef;
00518     double ZcoefA;
00519     double ZcoefB;
00520     double ZcoefAB;
00521 }CvStereoLineCoeff;
00522 
00523 
00524 typedef struct CvCamera
00525 {
00526     float   imgSize[2]; /* size of the camera view, used during calibration */
00527     float   matrix[9]; /* intinsic camera parameters:  [ fx 0 cx; 0 fy cy; 0 0 1 ] */
00528     float   distortion[4]; /* distortion coefficients - two coefficients for radial distortion
00529                               and another two for tangential: [ k1 k2 p1 p2 ] */
00530     float   rotMatr[9];
00531     float   transVect[3]; /* rotation matrix and transition vector relatively
00532                              to some reference point in the space. */
00533 } CvCamera;
00534 
00535 typedef struct CvStereoCamera
00536 {
00537     CvCamera* camera[2]; /* two individual camera parameters */
00538     float fundMatr[9]; /* fundamental matrix */
00539 
00540     /* New part for stereo */
00541     CvPoint3D32f epipole[2];
00542     CvPoint2D32f quad[2][4]; /* coordinates of destination quadrangle after
00543                                 epipolar geometry rectification */
00544     double coeffs[2][3][3];/* coefficients for transformation */
00545     CvPoint2D32f border[2][4];
00546     CvSize warpSize;
00547     CvStereoLineCoeff* lineCoeffs;
00548     int needSwapCameras;/* flag set to 1 if need to swap cameras for good reconstruction */
00549     float rotMatrix[9];
00550     float transVector[3];
00551 } CvStereoCamera;
00552 
00553 
00554 typedef struct CvContourOrientation
00555 {
00556     float egvals[2];
00557     float egvects[4];
00558 
00559     float max, min; // minimum and maximum projections
00560     int imax, imin;
00561 } CvContourOrientation;
00562 
00563 #define CV_CAMERA_TO_WARP 1
00564 #define CV_WARP_TO_CAMERA 2
00565 
00566 CVAPI(int) icvConvertWarpCoordinates(double coeffs[3][3],
00567                                 CvPoint2D32f* cameraPoint,
00568                                 CvPoint2D32f* warpPoint,
00569                                 int direction);
00570 
00571 CVAPI(int) icvGetSymPoint3D(  CvPoint3D64f pointCorner,
00572                             CvPoint3D64f point1,
00573                             CvPoint3D64f point2,
00574                             CvPoint3D64f *pointSym2);
00575 
00576 CVAPI(void) icvGetPieceLength3D(CvPoint3D64f point1,CvPoint3D64f point2,double* dist);
00577 
00578 CVAPI(int) icvCompute3DPoint(    double alpha,double betta,
00579                             CvStereoLineCoeff* coeffs,
00580                             CvPoint3D64f* point);
00581 
00582 CVAPI(int) icvCreateConvertMatrVect( double*     rotMatr1,
00583                                 double*     transVect1,
00584                                 double*     rotMatr2,
00585                                 double*     transVect2,
00586                                 double*     convRotMatr,
00587                                 double*     convTransVect);
00588 
00589 CVAPI(int) icvConvertPointSystem(CvPoint3D64f  M2,
00590                             CvPoint3D64f* M1,
00591                             double*     rotMatr,
00592                             double*     transVect
00593                             );
00594 
00595 CVAPI(int) icvComputeCoeffForStereo(  CvStereoCamera* stereoCamera);
00596 
00597 CVAPI(int) icvGetCrossPieceVector(CvPoint2D32f p1_start,CvPoint2D32f p1_end,CvPoint2D32f v2_start,CvPoint2D32f v2_end,CvPoint2D32f *cross);
00598 CVAPI(int) icvGetCrossLineDirect(CvPoint2D32f p1,CvPoint2D32f p2,float a,float b,float c,CvPoint2D32f* cross);
00599 CVAPI(float) icvDefinePointPosition(CvPoint2D32f point1,CvPoint2D32f point2,CvPoint2D32f point);
00600 CVAPI(int) icvStereoCalibration( int numImages,
00601                             int* nums,
00602                             CvSize imageSize,
00603                             CvPoint2D32f* imagePoints1,
00604                             CvPoint2D32f* imagePoints2,
00605                             CvPoint3D32f* objectPoints,
00606                             CvStereoCamera* stereoparams
00607                            );
00608 
00609 
00610 CVAPI(int) icvComputeRestStereoParams(CvStereoCamera *stereoparams);
00611 
00612 CVAPI(void) cvComputePerspectiveMap( const double coeffs[3][3], CvArr* rectMapX, CvArr* rectMapY );
00613 
00614 CVAPI(int) icvComCoeffForLine(   CvPoint2D64f point1,
00615                             CvPoint2D64f point2,
00616                             CvPoint2D64f point3,
00617                             CvPoint2D64f point4,
00618                             double*    camMatr1,
00619                             double*    rotMatr1,
00620                             double*    transVect1,
00621                             double*    camMatr2,
00622                             double*    rotMatr2,
00623                             double*    transVect2,
00624                             CvStereoLineCoeff*    coeffs,
00625                             int* needSwapCameras);
00626 
00627 CVAPI(int) icvGetDirectionForPoint(  CvPoint2D64f point,
00628                                 double* camMatr,
00629                                 CvPoint3D64f* direct);
00630 
00631 CVAPI(int) icvGetCrossLines(CvPoint3D64f point11,CvPoint3D64f point12,
00632                        CvPoint3D64f point21,CvPoint3D64f point22,
00633                        CvPoint3D64f* midPoint);
00634 
00635 CVAPI(int) icvComputeStereoLineCoeffs(   CvPoint3D64f pointA,
00636                                     CvPoint3D64f pointB,
00637                                     CvPoint3D64f pointCam1,
00638                                     double gamma,
00639                                     CvStereoLineCoeff*    coeffs);
00640 
00641 /*CVAPI(int) icvComputeFundMatrEpipoles ( double* camMatr1, 
00642                                     double*     rotMatr1, 
00643                                     double*     transVect1,
00644                                     double*     camMatr2,
00645                                     double*     rotMatr2,
00646                                     double*     transVect2,
00647                                     CvPoint2D64f* epipole1,
00648                                     CvPoint2D64f* epipole2,
00649                                     double*     fundMatr);*/
00650 
00651 CVAPI(int) icvGetAngleLine( CvPoint2D64f startPoint, CvSize imageSize,CvPoint2D64f *point1,CvPoint2D64f *point2);
00652 
00653 CVAPI(void) icvGetCoefForPiece(   CvPoint2D64f p_start,CvPoint2D64f p_end,
00654                         double *a,double *b,double *c,
00655                         int* result);
00656 
00657 /*CVAPI(void) icvGetCommonArea( CvSize imageSize,
00658                     CvPoint2D64f epipole1,CvPoint2D64f epipole2,
00659                     double* fundMatr,
00660                     double* coeff11,double* coeff12,
00661                     double* coeff21,double* coeff22,
00662                     int* result);*/
00663 
00664 CVAPI(void) icvComputeeInfiniteProject1(double*    rotMatr,
00665                                      double*    camMatr1,
00666                                      double*    camMatr2,
00667                                      CvPoint2D32f point1,
00668                                      CvPoint2D32f *point2);
00669 
00670 CVAPI(void) icvComputeeInfiniteProject2(double*    rotMatr,
00671                                      double*    camMatr1,
00672                                      double*    camMatr2,
00673                                      CvPoint2D32f* point1,
00674                                      CvPoint2D32f point2);
00675 
00676 CVAPI(void) icvGetCrossDirectDirect(  double* direct1,double* direct2,
00677                             CvPoint2D64f *cross,int* result);
00678 
00679 CVAPI(void) icvGetCrossPieceDirect(   CvPoint2D64f p_start,CvPoint2D64f p_end,
00680                             double a,double b,double c,
00681                             CvPoint2D64f *cross,int* result);
00682 
00683 CVAPI(void) icvGetCrossPiecePiece( CvPoint2D64f p1_start,CvPoint2D64f p1_end,
00684                             CvPoint2D64f p2_start,CvPoint2D64f p2_end,
00685                             CvPoint2D64f* cross,
00686                             int* result);
00687                             
00688 CVAPI(void) icvGetPieceLength(CvPoint2D64f point1,CvPoint2D64f point2,double* dist);
00689 
00690 CVAPI(void) icvGetCrossRectDirect(    CvSize imageSize,
00691                             double a,double b,double c,
00692                             CvPoint2D64f *start,CvPoint2D64f *end,
00693                             int* result);
00694 
00695 CVAPI(void) icvProjectPointToImage(   CvPoint3D64f point,
00696                             double* camMatr,double* rotMatr,double* transVect,
00697                             CvPoint2D64f* projPoint);
00698 
00699 CVAPI(void) icvGetQuadsTransform( CvSize        imageSize,
00700                         double*     camMatr1,
00701                         double*     rotMatr1,
00702                         double*     transVect1,
00703                         double*     camMatr2,
00704                         double*     rotMatr2,
00705                         double*     transVect2,
00706                         CvSize*       warpSize,
00707                         double quad1[4][2],
00708                         double quad2[4][2],
00709                         double*     fundMatr,
00710                         CvPoint3D64f* epipole1,
00711                         CvPoint3D64f* epipole2
00712                         );
00713 
00714 CVAPI(void) icvGetQuadsTransformStruct(  CvStereoCamera* stereoCamera);
00715 
00716 CVAPI(void) icvComputeStereoParamsForCameras(CvStereoCamera* stereoCamera);
00717 
00718 CVAPI(void) icvGetCutPiece(   double* areaLineCoef1,double* areaLineCoef2,
00719                     CvPoint2D64f epipole,
00720                     CvSize imageSize,
00721                     CvPoint2D64f* point11,CvPoint2D64f* point12,
00722                     CvPoint2D64f* point21,CvPoint2D64f* point22,
00723                     int* result);
00724 
00725 CVAPI(void) icvGetMiddleAnglePoint(   CvPoint2D64f basePoint,
00726                             CvPoint2D64f point1,CvPoint2D64f point2,
00727                             CvPoint2D64f* midPoint);
00728 
00729 CVAPI(void) icvGetNormalDirect(double* direct,CvPoint2D64f point,double* normDirect);
00730 
00731 CVAPI(double) icvGetVect(CvPoint2D64f basePoint,CvPoint2D64f point1,CvPoint2D64f point2);
00732 
00733 CVAPI(void) icvProjectPointToDirect(  CvPoint2D64f point,double* lineCoeff,
00734                             CvPoint2D64f* projectPoint);
00735 
00736 CVAPI(void) icvGetDistanceFromPointToDirect( CvPoint2D64f point,double* lineCoef,double*dist);
00737 
00738 CVAPI(IplImage*) icvCreateIsometricImage( IplImage* src, IplImage* dst,
00739                               int desired_depth, int desired_num_channels );
00740 
00741 CVAPI(void) cvDeInterlace( const CvArr* frame, CvArr* fieldEven, CvArr* fieldOdd );
00742 
00743 /*CVAPI(int) icvSelectBestRt(           int           numImages,
00744                                     int*          numPoints,
00745                                     CvSize        imageSize,
00746                                     CvPoint2D32f* imagePoints1,
00747                                     CvPoint2D32f* imagePoints2,
00748                                     CvPoint3D32f* objectPoints,
00749 
00750                                     CvMatr32f     cameraMatrix1,
00751                                     CvVect32f     distortion1,
00752                                     CvMatr32f     rotMatrs1,
00753                                     CvVect32f     transVects1,
00754 
00755                                     CvMatr32f     cameraMatrix2,
00756                                     CvVect32f     distortion2,
00757                                     CvMatr32f     rotMatrs2,
00758                                     CvVect32f     transVects2,
00759 
00760                                     CvMatr32f     bestRotMatr,
00761                                     CvVect32f     bestTransVect
00762                                     );*/
00763 
00764 
00765 /****************************************************************************************\
00766 *                                     Contour Tree                                       *
00767 \****************************************************************************************/
00768 
00769 /* Contour tree header */
00770 typedef struct CvContourTree
00771 {
00772     CV_SEQUENCE_FIELDS()
00773     CvPoint p1;            /* the first point of the binary tree root segment */
00774     CvPoint p2;            /* the last point of the binary tree root segment */
00775 } CvContourTree;
00776 
00777 /* Builds hierarhical representation of a contour */
00778 CVAPI(CvContourTree*)  cvCreateContourTree( const CvSeq* contour,
00779                                             CvMemStorage* storage,
00780                                             double threshold );
00781 
00782 /* Reconstruct (completelly or partially) contour a from contour tree */
00783 CVAPI(CvSeq*)  cvContourFromContourTree( const CvContourTree* tree,
00784                                          CvMemStorage* storage,
00785                                          CvTermCriteria criteria );
00786 
00787 /* Compares two contour trees */
00788 enum { CV_CONTOUR_TREES_MATCH_I1 = 1 };
00789 
00790 CVAPI(double)  cvMatchContourTrees( const CvContourTree* tree1,
00791                                     const CvContourTree* tree2,
00792                                     int method, double threshold );
00793 
00794 /****************************************************************************************\
00795 *                                   Contour Morphing                                     *
00796 \****************************************************************************************/
00797 
00798 /* finds correspondence between two contours */
00799 CvSeq* cvCalcContoursCorrespondence( const CvSeq* contour1,
00800                                      const CvSeq* contour2, 
00801                                      CvMemStorage* storage);
00802 
00803 /* morphs contours using the pre-calculated correspondence:
00804    alpha=0 ~ contour1, alpha=1 ~ contour2 */
00805 CvSeq* cvMorphContours( const CvSeq* contour1, const CvSeq* contour2,
00806                         CvSeq* corr, double alpha,
00807                         CvMemStorage* storage );
00808 
00809 
00810 /****************************************************************************************\
00811 *                                   Active Contours                                      *
00812 \****************************************************************************************/
00813 
00814 #define  CV_VALUE  1
00815 #define  CV_ARRAY  2
00816 /* Updates active contour in order to minimize its cummulative
00817    (internal and external) energy. */
00818 CVAPI(void)  cvSnakeImage( const IplImage* image, CvPoint* points,
00819                            int  length, float* alpha,
00820                            float* beta, float* gamma,
00821                            int coeff_usage, CvSize  win,
00822                            CvTermCriteria criteria, int calc_gradient CV_DEFAULT(1));
00823 
00824 /****************************************************************************************\
00825 *                                    Texture Descriptors                                 *
00826 \****************************************************************************************/
00827 
00828 #define CV_GLCM_OPTIMIZATION_NONE                   -2
00829 #define CV_GLCM_OPTIMIZATION_LUT                    -1
00830 #define CV_GLCM_OPTIMIZATION_HISTOGRAM              0
00831 
00832 #define CV_GLCMDESC_OPTIMIZATION_ALLOWDOUBLENEST    10
00833 #define CV_GLCMDESC_OPTIMIZATION_ALLOWTRIPLENEST    11
00834 #define CV_GLCMDESC_OPTIMIZATION_HISTOGRAM          4
00835 
00836 #define CV_GLCMDESC_ENTROPY                         0
00837 #define CV_GLCMDESC_ENERGY                          1
00838 #define CV_GLCMDESC_HOMOGENITY                      2
00839 #define CV_GLCMDESC_CONTRAST                        3
00840 #define CV_GLCMDESC_CLUSTERTENDENCY                 4
00841 #define CV_GLCMDESC_CLUSTERSHADE                    5
00842 #define CV_GLCMDESC_CORRELATION                     6
00843 #define CV_GLCMDESC_CORRELATIONINFO1                7
00844 #define CV_GLCMDESC_CORRELATIONINFO2                8
00845 #define CV_GLCMDESC_MAXIMUMPROBABILITY              9
00846 
00847 #define CV_GLCM_ALL                                 0
00848 #define CV_GLCM_GLCM                                1
00849 #define CV_GLCM_DESC                                2
00850 
00851 typedef struct CvGLCM CvGLCM;
00852 
00853 CVAPI(CvGLCM*) cvCreateGLCM( const IplImage* srcImage,
00854                                 int stepMagnitude,
00855                                 const int* stepDirections CV_DEFAULT(0),
00856                                 int numStepDirections CV_DEFAULT(0),
00857                                 int optimizationType CV_DEFAULT(CV_GLCM_OPTIMIZATION_NONE));
00858 
00859 CVAPI(void) cvReleaseGLCM( CvGLCM** GLCM, int flag CV_DEFAULT(CV_GLCM_ALL));
00860 
00861 CVAPI(void) cvCreateGLCMDescriptors( CvGLCM* destGLCM,
00862                                         int descriptorOptimizationType
00863                                         CV_DEFAULT(CV_GLCMDESC_OPTIMIZATION_ALLOWDOUBLENEST));
00864 
00865 CVAPI(double) cvGetGLCMDescriptor( CvGLCM* GLCM, int step, int descriptor );
00866 
00867 CVAPI(void) cvGetGLCMDescriptorStatistics( CvGLCM* GLCM, int descriptor,
00868                                               double* average, double* standardDeviation );
00869 
00870 CVAPI(IplImage*) cvCreateGLCMImage( CvGLCM* GLCM, int step );
00871 
00872 /****************************************************************************************\
00873 *                                  Face eyes&mouth tracking                              *
00874 \****************************************************************************************/
00875 
00876 
00877 typedef struct CvFaceTracker CvFaceTracker;
00878 
00879 #define CV_NUM_FACE_ELEMENTS    3 
00880 enum CV_FACE_ELEMENTS
00881 {
00882     CV_FACE_MOUTH = 0,
00883     CV_FACE_LEFT_EYE = 1,
00884     CV_FACE_RIGHT_EYE = 2
00885 };
00886 
00887 CVAPI(CvFaceTracker*) cvInitFaceTracker(CvFaceTracker* pFaceTracking, const IplImage* imgGray,
00888                                                 CvRect* pRects, int nRects);
00889 CVAPI(int) cvTrackFace( CvFaceTracker* pFaceTracker, IplImage* imgGray,
00890                               CvRect* pRects, int nRects,
00891                               CvPoint* ptRotate, double* dbAngleRotate);
00892 CVAPI(void) cvReleaseFaceTracker(CvFaceTracker** ppFaceTracker);
00893 
00894 
00895 typedef struct CvFace
00896 {
00897     CvRect MouthRect;
00898     CvRect LeftEyeRect;
00899     CvRect RightEyeRect;
00900 } CvFaceData;
00901 
00902 CvSeq * cvFindFace(IplImage * Image,CvMemStorage* storage);
00903 CvSeq * cvPostBoostingFindFace(IplImage * Image,CvMemStorage* storage);
00904 
00905 
00906 /****************************************************************************************\
00907 *                                         3D Tracker                                     *
00908 \****************************************************************************************/
00909 
00910 typedef unsigned char CvBool;
00911 
00912 typedef struct
00913 {
00914     int id;
00915     CvPoint2D32f p; // pgruebele: So we do not loose precision, this needs to be float
00916 } Cv3dTracker2dTrackedObject;
00917 
00918 CV_INLINE Cv3dTracker2dTrackedObject cv3dTracker2dTrackedObject(int id, CvPoint2D32f p)
00919 {
00920     Cv3dTracker2dTrackedObject r;
00921     r.id = id;
00922     r.p = p;
00923     return r;
00924 }
00925 
00926 typedef struct
00927 {
00928     int id;
00929     CvPoint3D32f p;             // location of the tracked object
00930 } Cv3dTrackerTrackedObject;
00931 
00932 CV_INLINE Cv3dTrackerTrackedObject cv3dTrackerTrackedObject(int id, CvPoint3D32f p)
00933 {
00934     Cv3dTrackerTrackedObject r;
00935     r.id = id;
00936     r.p = p;
00937     return r;
00938 }
00939 
00940 typedef struct
00941 {
00942     CvBool valid;
00943     float mat[4][4];              /* maps camera coordinates to world coordinates */
00944     CvPoint2D32f principal_point; /* copied from intrinsics so this structure */
00945                                   /* has all the info we need */
00946 } Cv3dTrackerCameraInfo;
00947 
00948 typedef struct
00949 {
00950     CvPoint2D32f principal_point;
00951     float focal_length[2];
00952     float distortion[4];
00953 } Cv3dTrackerCameraIntrinsics;
00954 
00955 CVAPI(CvBool) cv3dTrackerCalibrateCameras(int num_cameras,
00956                      const Cv3dTrackerCameraIntrinsics camera_intrinsics[], /* size is num_cameras */
00957                      CvSize etalon_size,
00958                      float square_size,
00959                      IplImage *samples[],                                   /* size is num_cameras */
00960                      Cv3dTrackerCameraInfo camera_info[]);                  /* size is num_cameras */
00961 
00962 CVAPI(int)  cv3dTrackerLocateObjects(int num_cameras, int num_objects,
00963                    const Cv3dTrackerCameraInfo camera_info[],        /* size is num_cameras */
00964                    const Cv3dTracker2dTrackedObject tracking_info[], /* size is num_objects*num_cameras */
00965                    Cv3dTrackerTrackedObject tracked_objects[]);      /* size is num_objects */
00966 /****************************************************************************************
00967  tracking_info is a rectangular array; one row per camera, num_objects elements per row.
00968  The id field of any unused slots must be -1. Ids need not be ordered or consecutive. On
00969  completion, the return value is the number of objects located; i.e., the number of objects
00970  visible by more than one camera. The id field of any unused slots in tracked objects is
00971  set to -1.
00972 ****************************************************************************************/
00973 
00974 
00975 /****************************************************************************************\
00976 *                           Skeletons and Linear-Contour Models                          *
00977 \****************************************************************************************/
00978 
00979 typedef enum CvLeeParameters
00980 {
00981     CV_LEE_INT = 0,
00982     CV_LEE_FLOAT = 1,
00983     CV_LEE_DOUBLE = 2,
00984     CV_LEE_AUTO = -1,
00985     CV_LEE_ERODE = 0,
00986     CV_LEE_ZOOM = 1,
00987     CV_LEE_NON = 2
00988 } CvLeeParameters;
00989 
00990 #define CV_NEXT_VORONOISITE2D( SITE ) ((SITE)->edge[0]->site[((SITE)->edge[0]->site[0] == (SITE))])
00991 #define CV_PREV_VORONOISITE2D( SITE ) ((SITE)->edge[1]->site[((SITE)->edge[1]->site[0] == (SITE))])
00992 #define CV_FIRST_VORONOIEDGE2D( SITE ) ((SITE)->edge[0])
00993 #define CV_LAST_VORONOIEDGE2D( SITE ) ((SITE)->edge[1])
00994 #define CV_NEXT_VORONOIEDGE2D( EDGE, SITE ) ((EDGE)->next[(EDGE)->site[0] != (SITE)])
00995 #define CV_PREV_VORONOIEDGE2D( EDGE, SITE ) ((EDGE)->next[2 + ((EDGE)->site[0] != (SITE))])
00996 #define CV_VORONOIEDGE2D_BEGINNODE( EDGE, SITE ) ((EDGE)->node[((EDGE)->site[0] != (SITE))])
00997 #define CV_VORONOIEDGE2D_ENDNODE( EDGE, SITE ) ((EDGE)->node[((EDGE)->site[0] == (SITE))])
00998 #define CV_TWIN_VORONOISITE2D( SITE, EDGE ) ( (EDGE)->site[((EDGE)->site[0] == (SITE))]) 
00999 
01000 #define CV_VORONOISITE2D_FIELDS()    \
01001     struct CvVoronoiNode2D *node[2]; \
01002     struct CvVoronoiEdge2D *edge[2];
01003 
01004 typedef struct CvVoronoiSite2D
01005 {
01006     CV_VORONOISITE2D_FIELDS()
01007     struct CvVoronoiSite2D *next[2];
01008 } CvVoronoiSite2D;
01009 
01010 #define CV_VORONOIEDGE2D_FIELDS()    \
01011     struct CvVoronoiNode2D *node[2]; \
01012     struct CvVoronoiSite2D *site[2]; \
01013     struct CvVoronoiEdge2D *next[4];
01014 
01015 typedef struct CvVoronoiEdge2D
01016 {
01017     CV_VORONOIEDGE2D_FIELDS()
01018 } CvVoronoiEdge2D;
01019 
01020 #define CV_VORONOINODE2D_FIELDS()       \
01021     CV_SET_ELEM_FIELDS(CvVoronoiNode2D) \
01022     CvPoint2D32f pt;                    \
01023     float radius;
01024 
01025 typedef struct CvVoronoiNode2D
01026 {
01027     CV_VORONOINODE2D_FIELDS()
01028 } CvVoronoiNode2D;
01029 
01030 #define CV_VORONOIDIAGRAM2D_FIELDS() \
01031     CV_GRAPH_FIELDS()                \
01032     CvSet *sites;
01033 
01034 typedef struct CvVoronoiDiagram2D
01035 {
01036     CV_VORONOIDIAGRAM2D_FIELDS()
01037 } CvVoronoiDiagram2D;
01038 
01039 /* Computes Voronoi Diagram for given polygons with holes */
01040 CVAPI(int)  cvVoronoiDiagramFromContour(CvSeq* ContourSeq,
01041                                            CvVoronoiDiagram2D** VoronoiDiagram,
01042                                            CvMemStorage* VoronoiStorage,
01043                                            CvLeeParameters contour_type CV_DEFAULT(CV_LEE_INT),
01044                                            int contour_orientation CV_DEFAULT(-1),
01045                                            int attempt_number CV_DEFAULT(10));
01046 
01047 /* Computes Voronoi Diagram for domains in given image */
01048 CVAPI(int)  cvVoronoiDiagramFromImage(IplImage* pImage,
01049                                          CvSeq** ContourSeq,
01050                                          CvVoronoiDiagram2D** VoronoiDiagram,
01051                                          CvMemStorage* VoronoiStorage,
01052                                          CvLeeParameters regularization_method CV_DEFAULT(CV_LEE_NON),
01053                                          float approx_precision CV_DEFAULT(CV_LEE_AUTO));
01054 
01055 /* Deallocates the storage */
01056 CVAPI(void) cvReleaseVoronoiStorage(CvVoronoiDiagram2D* VoronoiDiagram,
01057                                           CvMemStorage** pVoronoiStorage);
01058 
01059 /*********************** Linear-Contour Model ****************************/
01060 
01061 struct CvLCMEdge;
01062 struct CvLCMNode;
01063 
01064 typedef struct CvLCMEdge
01065 {
01066     CV_GRAPH_EDGE_FIELDS() 
01067     CvSeq* chain;
01068     float width;
01069     int index1;
01070     int index2;
01071 } CvLCMEdge;
01072 
01073 typedef struct CvLCMNode
01074 {
01075     CV_GRAPH_VERTEX_FIELDS()
01076     CvContour* contour; 
01077 } CvLCMNode;
01078 
01079 
01080 /* Computes hybrid model from Voronoi Diagram */
01081 CVAPI(CvGraph*) cvLinearContorModelFromVoronoiDiagram(CvVoronoiDiagram2D* VoronoiDiagram,
01082                                                          float maxWidth);
01083 
01084 /* Releases hybrid model storage */
01085 CVAPI(int) cvReleaseLinearContorModelStorage(CvGraph** Graph);
01086 
01087 
01088 /* two stereo-related functions */
01089 
01090 CVAPI(void) cvInitPerspectiveTransform( CvSize size, const CvPoint2D32f vertex[4], double matrix[3][3],
01091                                               CvArr* rectMap );
01092 
01093 /*CVAPI(void) cvInitStereoRectification( CvStereoCamera* params,
01094                                              CvArr* rectMap1, CvArr* rectMap2,
01095                                              int do_undistortion );*/
01096 
01097 /*************************** View Morphing Functions ************************/
01098 
01099 typedef struct CvMatrix3
01100 {
01101     float m[3][3];
01102 } CvMatrix3;    
01103     
01104 /* The order of the function corresponds to the order they should appear in
01105    the view morphing pipeline */ 
01106 
01107 /* Finds ending points of scanlines on left and right images of stereo-pair */
01108 CVAPI(void)  cvMakeScanlines( const CvMatrix3* matrix, CvSize  img_size,
01109                               int*  scanlines1, int*  scanlines2,
01110                               int*  lengths1, int*  lengths2,
01111                               int*  line_count );
01112 
01113 /* Grab pixel values from scanlines and stores them sequentially
01114    (some sort of perspective image transform) */
01115 CVAPI(void)  cvPreWarpImage( int       line_count,
01116                              IplImage* img,
01117                              uchar*    dst,
01118                              int*      dst_nums,
01119                              int*      scanlines);
01120 
01121 /* Approximate each grabbed scanline by a sequence of runs
01122    (lossy run-length compression) */
01123 CVAPI(void)  cvFindRuns( int    line_count,
01124                          uchar* prewarp1,
01125                          uchar* prewarp2,
01126                          int*   line_lengths1,
01127                          int*   line_lengths2,
01128                          int*   runs1,
01129                          int*   runs2,
01130                          int*   num_runs1,
01131                          int*   num_runs2);
01132 
01133 /* Compares two sets of compressed scanlines */
01134 CVAPI(void)  cvDynamicCorrespondMulti( int  line_count,
01135                                        int* first,
01136                                        int* first_runs,
01137                                        int* second,
01138                                        int* second_runs,
01139                                        int* first_corr,
01140                                        int* second_corr);
01141 
01142 /* Finds scanline ending coordinates for some intermediate "virtual" camera position */
01143 CVAPI(void)  cvMakeAlphaScanlines( int*  scanlines1,
01144                                    int*  scanlines2,
01145                                    int*  scanlinesA,
01146                                    int*  lengths,
01147                                    int   line_count,
01148                                    float alpha);
01149 
01150 /* Blends data of the left and right image scanlines to get
01151    pixel values of "virtual" image scanlines */
01152 CVAPI(void)  cvMorphEpilinesMulti( int    line_count,
01153                                    uchar* first_pix,
01154                                    int*   first_num,
01155                                    uchar* second_pix,
01156                                    int*   second_num,
01157                                    uchar* dst_pix,
01158                                    int*   dst_num,
01159                                    float  alpha,
01160                                    int*   first,
01161                                    int*   first_runs,
01162                                    int*   second,
01163                                    int*   second_runs,
01164                                    int*   first_corr,
01165                                    int*   second_corr);
01166 
01167 /* Does reverse warping of the morphing result to make
01168    it fill the destination image rectangle */
01169 CVAPI(void)  cvPostWarpImage( int       line_count,
01170                               uchar*    src,
01171                               int*      src_nums,
01172                               IplImage* img,
01173                               int*      scanlines);
01174 
01175 /* Deletes Moire (missed pixels that appear due to discretization) */
01176 CVAPI(void)  cvDeleteMoire( IplImage*  img );
01177 
01178 
01179 typedef struct CvConDensation
01180 {
01181     int MP;
01182     int DP;
01183     float* DynamMatr;       /* Matrix of the linear Dynamics system  */
01184     float* State;           /* Vector of State                       */
01185     int SamplesNum;         /* Number of the Samples                 */
01186     float** flSamples;      /* arr of the Sample Vectors             */
01187     float** flNewSamples;   /* temporary array of the Sample Vectors */
01188     float* flConfidence;    /* Confidence for each Sample            */
01189     float* flCumulative;    /* Cumulative confidence                 */
01190     float* Temp;            /* Temporary vector                      */
01191     float* RandomSample;    /* RandomVector to update sample set     */
01192     struct CvRandState* RandS; /* Array of structures to generate random vectors */
01193 } CvConDensation;
01194                                
01195 /* Creates ConDensation filter state */
01196 CVAPI(CvConDensation*)  cvCreateConDensation( int dynam_params,
01197                                              int measure_params,
01198                                              int sample_count );
01199 
01200 /* Releases ConDensation filter state */
01201 CVAPI(void)  cvReleaseConDensation( CvConDensation** condens );
01202 
01203 /* Updates ConDensation filter by time (predict future state of the system) */
01204 CVAPI(void)  cvConDensUpdateByTime( CvConDensation* condens);
01205 
01206 /* Initializes ConDensation filter samples  */
01207 CVAPI(void)  cvConDensInitSampleSet( CvConDensation* condens, CvMat* lower_bound, CvMat* upper_bound );                               
01208 
01209 CV_INLINE int iplWidth( const IplImage* img )
01210 {
01211     return !img ? 0 : !img->roi ? img->width : img->roi->width;
01212 }
01213 
01214 CV_INLINE int iplHeight( const IplImage* img )
01215 {
01216     return !img ? 0 : !img->roi ? img->height : img->roi->height;
01217 }
01218 
01219 #ifdef __cplusplus
01220 }
01221 #endif
01222 
01223 #ifdef __cplusplus
01224 
01225 /****************************************************************************************\
01226 *                                   Calibration engine                                   *
01227 \****************************************************************************************/
01228 
01229 typedef enum CvCalibEtalonType
01230 {
01231     CV_CALIB_ETALON_USER = -1,
01232     CV_CALIB_ETALON_CHESSBOARD = 0,
01233     CV_CALIB_ETALON_CHECKERBOARD = CV_CALIB_ETALON_CHESSBOARD
01234 }
01235 CvCalibEtalonType;
01236 
01237 class CV_EXPORTS CvCalibFilter
01238 {
01239 public:
01240     /* Constructor & destructor */
01241     CvCalibFilter();
01242     virtual ~CvCalibFilter();
01243 
01244     /* Sets etalon type - one for all cameras.
01245        etalonParams is used in case of pre-defined etalons (such as chessboard).
01246        Number of elements in etalonParams is determined by etalonType.
01247        E.g., if etalon type is CV_ETALON_TYPE_CHESSBOARD then:
01248          etalonParams[0] is number of squares per one side of etalon
01249          etalonParams[1] is number of squares per another side of etalon
01250          etalonParams[2] is linear size of squares in the board in arbitrary units.
01251        pointCount & points are used in case of
01252        CV_CALIB_ETALON_USER (user-defined) etalon. */
01253     virtual bool
01254         SetEtalon( CvCalibEtalonType etalonType, double* etalonParams,
01255                    int pointCount = 0, CvPoint2D32f* points = 0 );
01256 
01257     /* Retrieves etalon parameters/or and points */
01258     virtual CvCalibEtalonType
01259         GetEtalon( int* paramCount = 0, const double** etalonParams = 0,
01260                    int* pointCount = 0, const CvPoint2D32f** etalonPoints = 0 ) const;
01261 
01262     /* Sets number of cameras calibrated simultaneously. It is equal to 1 initially */
01263     virtual void SetCameraCount( int cameraCount );
01264 
01265     /* Retrieves number of cameras */
01266     int GetCameraCount() const { return cameraCount; }
01267 
01268     /* Starts cameras calibration */
01269     virtual bool SetFrames( int totalFrames );
01270     
01271     /* Stops cameras calibration */
01272     virtual void Stop( bool calibrate = false );
01273 
01274     /* Retrieves number of cameras */
01275     bool IsCalibrated() const { return isCalibrated; }
01276 
01277     /* Feeds another serie of snapshots (one per each camera) to filter.
01278        Etalon points on these images are found automatically.
01279        If the function can't locate points, it returns false */
01280     virtual bool FindEtalon( IplImage** imgs );
01281 
01282     /* The same but takes matrices */
01283     virtual bool FindEtalon( CvMat** imgs );
01284 
01285     /* Lower-level function for feeding filter with already found etalon points.
01286        Array of point arrays for each camera is passed. */
01287     virtual bool Push( const CvPoint2D32f** points = 0 );
01288 
01289     /* Returns total number of accepted frames and, optionally,
01290        total number of frames to collect */
01291     virtual int GetFrameCount( int* framesTotal = 0 ) const;
01292 
01293     /* Retrieves camera parameters for specified camera.
01294        If camera is not calibrated the function returns 0 */
01295     virtual const CvCamera* GetCameraParams( int idx = 0 ) const;
01296 
01297     virtual const CvStereoCamera* GetStereoParams() const;
01298 
01299     /* Sets camera parameters for all cameras */
01300     virtual bool SetCameraParams( CvCamera* params );
01301 
01302     /* Saves all camera parameters to file */
01303     virtual bool SaveCameraParams( const char* filename );
01304     
01305     /* Loads all camera parameters from file */
01306     virtual bool LoadCameraParams( const char* filename );
01307 
01308     /* Undistorts images using camera parameters. Some of src pointers can be NULL. */
01309     virtual bool Undistort( IplImage** src, IplImage** dst );
01310 
01311     /* Undistorts images using camera parameters. Some of src pointers can be NULL. */
01312     virtual bool Undistort( CvMat** src, CvMat** dst );
01313 
01314     /* Returns array of etalon points detected/partally detected
01315        on the latest frame for idx-th camera */
01316     virtual bool GetLatestPoints( int idx, CvPoint2D32f** pts,
01317                                                   int* count, bool* found );
01318 
01319     /* Draw the latest detected/partially detected etalon */
01320     virtual void DrawPoints( IplImage** dst );
01321 
01322     /* Draw the latest detected/partially detected etalon */
01323     virtual void DrawPoints( CvMat** dst );
01324 
01325     virtual bool Rectify( IplImage** srcarr, IplImage** dstarr );
01326     virtual bool Rectify( CvMat** srcarr, CvMat** dstarr );
01327 
01328 protected:
01329 
01330     enum { MAX_CAMERAS = 3 };
01331 
01332     /* etalon data */
01333     CvCalibEtalonType  etalonType;
01334     int     etalonParamCount;
01335     double* etalonParams;
01336     int     etalonPointCount;
01337     CvPoint2D32f* etalonPoints;
01338     CvSize  imgSize;
01339     CvMat*  grayImg;
01340     CvMat*  tempImg;
01341     CvMemStorage* storage;
01342 
01343     /* camera data */
01344     int     cameraCount;
01345     CvCamera cameraParams[MAX_CAMERAS];
01346     CvStereoCamera stereo;
01347     CvPoint2D32f* points[MAX_CAMERAS];
01348     CvMat*  undistMap[MAX_CAMERAS][2];
01349     CvMat*  undistImg;
01350     int     latestCounts[MAX_CAMERAS];
01351     CvPoint2D32f* latestPoints[MAX_CAMERAS];
01352     CvMat*  rectMap[MAX_CAMERAS][2];
01353 
01354     /* Added by Valery */
01355     //CvStereoCamera stereoParams;
01356 
01357     int     maxPoints;
01358     int     framesTotal;
01359     int     framesAccepted;
01360     bool    isCalibrated;
01361 };
01362 
01363 #include <iosfwd>
01364 #include <limits>
01365 
01366 class CV_EXPORTS CvImage
01367 {
01368 public:
01369     CvImage() : image(0), refcount(0) {}
01370     CvImage( CvSize size, int depth, int channels )
01371     {
01372         image = cvCreateImage( size, depth, channels );
01373         refcount = image ? new int(1) : 0;
01374     }
01375     
01376     CvImage( IplImage* img ) : image(img)
01377     {
01378         refcount = image ? new int(1) : 0;
01379     }
01380     
01381     CvImage( const CvImage& img ) : image(img.image), refcount(img.refcount)
01382     {
01383         if( refcount ) ++(*refcount);
01384     }
01385     
01386     CvImage( const char* filename, const char* imgname=0, int color=-1 ) : image(0), refcount(0)
01387     { load( filename, imgname, color ); }
01388     
01389     CvImage( CvFileStorage* fs, const char* mapname, const char* imgname ) : image(0), refcount(0)
01390     { read( fs, mapname, imgname ); }
01391     
01392     CvImage( CvFileStorage* fs, const char* seqname, int idx ) : image(0), refcount(0)
01393     { read( fs, seqname, idx ); }
01394     
01395     ~CvImage()
01396     {
01397         if( refcount && !(--*refcount) )
01398         {
01399             cvReleaseImage( &image );
01400             delete refcount;
01401         }
01402     }
01403     
01404     CvImage clone() { return CvImage(image ? cvCloneImage(image) : 0); }
01405     
01406     void create( CvSize size, int depth, int channels )
01407     {
01408         if( !image || !refcount ||
01409            image->width != size.width || image->height != size.height ||
01410            image->depth != depth || image->nChannels != channels )
01411             attach( cvCreateImage( size, depth, channels ));
01412     }
01413     
01414     void release() { detach(); }
01415     void clear() { detach(); }
01416     
01417     void attach( IplImage* img, bool use_refcount=true )
01418     {
01419         if( refcount && --*refcount == 0 )
01420         {
01421             cvReleaseImage( &image );
01422             delete refcount;
01423         }
01424         image = img;
01425         refcount = use_refcount && image ? new int(1) : 0;
01426     }
01427     
01428     void detach()
01429     {
01430         if( refcount && --*refcount == 0 )
01431         {
01432             cvReleaseImage( &image );
01433             delete refcount;
01434         }
01435         image = 0;
01436         refcount = 0;
01437     }
01438     
01439     bool load( const char* filename, const char* imgname=0, int color=-1 );
01440     bool read( CvFileStorage* fs, const char* mapname, const char* imgname );
01441     bool read( CvFileStorage* fs, const char* seqname, int idx );
01442     void save( const char* filename, const char* imgname, const int* params=0 );
01443     void write( CvFileStorage* fs, const char* imgname );
01444     
01445     void show( const char* window_name );
01446     bool is_valid() { return image != 0; }
01447     
01448     int width() const { return image ? image->width : 0; }
01449     int height() const { return image ? image->height : 0; }
01450     
01451     CvSize size() const { return image ? cvSize(image->width, image->height) : cvSize(0,0); }
01452     
01453     CvSize roi_size() const
01454     {
01455         return !image ? cvSize(0,0) :
01456         !image->roi ? cvSize(image->width,image->height) :
01457         cvSize(image->roi->width, image->roi->height);
01458     }
01459     
01460     CvRect roi() const
01461     {
01462         return !image ? cvRect(0,0,0,0) :
01463         !image->roi ? cvRect(0,0,image->width,image->height) :
01464         cvRect(image->roi->xOffset,image->roi->yOffset,
01465                image->roi->width,image->roi->height);
01466     }
01467     
01468     int coi() const { return !image || !image->roi ? 0 : image->roi->coi; }
01469     
01470     void set_roi(CvRect roi) { cvSetImageROI(image,roi); }
01471     void reset_roi() { cvResetImageROI(image); }
01472     void set_coi(int coi) { cvSetImageCOI(image,coi); }
01473     int depth() const { return image ? image->depth : 0; }
01474     int channels() const { return image ? image->nChannels : 0; }
01475     int pix_size() const { return image ? ((image->depth & 255)>>3)*image->nChannels : 0; }
01476     
01477     uchar* data() { return image ? (uchar*)image->imageData : 0; }
01478     const uchar* data() const { return image ? (const uchar*)image->imageData : 0; }
01479     int step() const { return image ? image->widthStep : 0; }
01480     int origin() const { return image ? image->origin : 0; }
01481     
01482     uchar* roi_row(int y)
01483     {
01484         assert(0<=y);
01485         assert(!image ?
01486                1 : image->roi ?
01487                y<image->roi->height : y<image->height);
01488         
01489         return !image ? 0 :
01490         !image->roi ?
01491         (uchar*)(image->imageData + y*image->widthStep) :
01492         (uchar*)(image->imageData + (y+image->roi->yOffset)*image->widthStep +
01493                  image->roi->xOffset*((image->depth & 255)>>3)*image->nChannels);
01494     }
01495     
01496     const uchar* roi_row(int y) const
01497     {
01498         assert(0<=y);
01499         assert(!image ?
01500                1 : image->roi ?
01501                y<image->roi->height : y<image->height);
01502         
01503         return !image ? 0 :
01504         !image->roi ?
01505         (const uchar*)(image->imageData + y*image->widthStep) :
01506         (const uchar*)(image->imageData + (y+image->roi->yOffset)*image->widthStep +
01507                        image->roi->xOffset*((image->depth & 255)>>3)*image->nChannels);
01508     }
01509     
01510     operator const IplImage* () const { return image; }
01511     operator IplImage* () { return image; }
01512     
01513     CvImage& operator = (const CvImage& img)
01514     {
01515         if( img.refcount )
01516             ++*img.refcount;
01517         if( refcount && !(--*refcount) )
01518             cvReleaseImage( &image );
01519         image=img.image;
01520         refcount=img.refcount;
01521         return *this;
01522     }
01523     
01524 protected:
01525     IplImage* image;
01526     int* refcount;
01527 };
01528 
01529 
01530 class CV_EXPORTS CvMatrix
01531 {
01532 public:
01533     CvMatrix() : matrix(0) {}
01534     CvMatrix( int rows, int cols, int type )
01535     { matrix = cvCreateMat( rows, cols, type ); }
01536     
01537     CvMatrix( int rows, int cols, int type, CvMat* hdr,
01538              void* data=0, int step=CV_AUTOSTEP )
01539     { matrix = cvInitMatHeader( hdr, rows, cols, type, data, step ); }
01540     
01541     CvMatrix( int rows, int cols, int type, CvMemStorage* storage, bool alloc_data=true );
01542     
01543     CvMatrix( int rows, int cols, int type, void* data, int step=CV_AUTOSTEP )
01544     { matrix = cvCreateMatHeader( rows, cols, type );
01545         cvSetData( matrix, data, step ); }
01546     
01547     CvMatrix( CvMat* m )
01548     { matrix = m; }
01549     
01550     CvMatrix( const CvMatrix& m )
01551     {
01552         matrix = m.matrix;
01553         addref();
01554     }
01555     
01556     CvMatrix( const char* filename, const char* matname=0, int color=-1 ) : matrix(0)
01557     {  load( filename, matname, color ); }
01558     
01559     CvMatrix( CvFileStorage* fs, const char* mapname, const char* matname ) : matrix(0)
01560     {  read( fs, mapname, matname ); }
01561     
01562     CvMatrix( CvFileStorage* fs, const char* seqname, int idx ) : matrix(0)
01563     {  read( fs, seqname, idx ); }
01564     
01565     ~CvMatrix()
01566     {
01567         release();
01568     }
01569     
01570     CvMatrix clone() { return CvMatrix(matrix ? cvCloneMat(matrix) : 0); }
01571     
01572     void set( CvMat* m, bool add_ref )
01573     {
01574         release();
01575         matrix = m;
01576         if( add_ref )
01577             addref();
01578     }
01579     
01580     void create( int rows, int cols, int type )
01581     {
01582         if( !matrix || !matrix->refcount ||
01583            matrix->rows != rows || matrix->cols != cols ||
01584            CV_MAT_TYPE(matrix->type) != type )
01585             set( cvCreateMat( rows, cols, type ), false );
01586     }
01587     
01588     void addref() const
01589     {
01590         if( matrix )
01591         {
01592             if( matrix->hdr_refcount )
01593                 ++matrix->hdr_refcount;
01594             else if( matrix->refcount )
01595                 ++*matrix->refcount;
01596         }
01597     }
01598     
01599     void release()
01600     {
01601         if( matrix )
01602         {
01603             if( matrix->hdr_refcount )
01604             {
01605                 if( --matrix->hdr_refcount == 0 )
01606                     cvReleaseMat( &matrix );
01607             }
01608             else if( matrix->refcount )
01609             {
01610                 if( --*matrix->refcount == 0 )
01611                     cvFree( &matrix->refcount );
01612             }
01613             matrix = 0;
01614         }
01615     }
01616     
01617     void clear()
01618     {
01619         release();
01620     }
01621     
01622     bool load( const char* filename, const char* matname=0, int color=-1 );
01623     bool read( CvFileStorage* fs, const char* mapname, const char* matname );
01624     bool read( CvFileStorage* fs, const char* seqname, int idx );
01625     void save( const char* filename, const char* matname, const int* params=0 );
01626     void write( CvFileStorage* fs, const char* matname );
01627     
01628     void show( const char* window_name );
01629     
01630     bool is_valid() { return matrix != 0; }
01631     
01632     int rows() const { return matrix ? matrix->rows : 0; }
01633     int cols() const { return matrix ? matrix->cols : 0; }
01634     
01635     CvSize size() const
01636     {
01637         return !matrix ? cvSize(0,0) : cvSize(matrix->rows,matrix->cols);
01638     }
01639     
01640     int type() const { return matrix ? CV_MAT_TYPE(matrix->type) : 0; }
01641     int depth() const { return matrix ? CV_MAT_DEPTH(matrix->type) : 0; }
01642     int channels() const { return matrix ? CV_MAT_CN(matrix->type) : 0; }
01643     int pix_size() const { return matrix ? CV_ELEM_SIZE(matrix->type) : 0; }
01644     
01645     uchar* data() { return matrix ? matrix->data.ptr : 0; }
01646     const uchar* data() const { return matrix ? matrix->data.ptr : 0; }
01647     int step() const { return matrix ? matrix->step : 0; }
01648     
01649     void set_data( void* data, int step=CV_AUTOSTEP )
01650     { cvSetData( matrix, data, step ); }
01651     
01652     uchar* row(int i) { return !matrix ? 0 : matrix->data.ptr + i*matrix->step; }
01653     const uchar* row(int i) const
01654     { return !matrix ? 0 : matrix->data.ptr + i*matrix->step; }
01655     
01656     operator const CvMat* () const { return matrix; }
01657     operator CvMat* () { return matrix; }
01658     
01659     CvMatrix& operator = (const CvMatrix& _m)
01660     {
01661         _m.addref();
01662         release();
01663         matrix = _m.matrix;
01664         return *this;
01665     }
01666     
01667 protected:
01668     CvMat* matrix;
01669 };
01670 
01671 /****************************************************************************************\
01672  *                                       CamShiftTracker                                  *
01673  \****************************************************************************************/
01674 
01675 class CV_EXPORTS CvCamShiftTracker
01676 {
01677 public:
01678     
01679     CvCamShiftTracker();
01680     virtual ~CvCamShiftTracker();
01681     
01682     /**** Characteristics of the object that are calculated by track_object method *****/
01683     float   get_orientation() const // orientation of the object in degrees
01684     { return m_box.angle; }
01685     float   get_length() const // the larger linear size of the object
01686     { return m_box.size.height; }
01687     float   get_width() const // the smaller linear size of the object
01688     { return m_box.size.width; }
01689     CvPoint2D32f get_center() const // center of the object
01690     { return m_box.center; }
01691     CvRect get_window() const // bounding rectangle for the object
01692     { return m_comp.rect; }
01693     
01694     /*********************** Tracking parameters ************************/
01695     int     get_threshold() const // thresholding value that applied to back project
01696     { return m_threshold; }
01697     
01698     int     get_hist_dims( int* dims = 0 ) const // returns number of histogram dimensions and sets
01699     { return m_hist ? cvGetDims( m_hist->bins, dims ) : 0; }
01700     
01701     int     get_min_ch_val( int channel ) const // get the minimum allowed value of the specified channel
01702     { return m_min_ch_val[channel]; }
01703     
01704     int     get_max_ch_val( int channel ) const // get the maximum allowed value of the specified channel
01705     { return m_max_ch_val[channel]; }
01706     
01707     // set initial object rectangle (must be called before initial calculation of the histogram)
01708     bool    set_window( CvRect window)
01709     { m_comp.rect = window; return true; }
01710     
01711     bool    set_threshold( int threshold ) // threshold applied to the histogram bins
01712     { m_threshold = threshold; return true; }
01713     
01714     bool    set_hist_bin_range( int dim, int min_val, int max_val );
01715     
01716     bool    set_hist_dims( int c_dims, int* dims );// set the histogram parameters
01717     
01718     bool    set_min_ch_val( int channel, int val ) // set the minimum allowed value of the specified channel
01719     { m_min_ch_val[channel] = val; return true; }
01720     bool    set_max_ch_val( int channel, int val ) // set the maximum allowed value of the specified channel
01721     { m_max_ch_val[channel] = val; return true; }
01722     
01723     /************************ The processing methods *********************************/
01724     // update object position
01725     virtual bool  track_object( const IplImage* cur_frame );
01726     
01727     // update object histogram
01728     virtual bool  update_histogram( const IplImage* cur_frame );
01729     
01730     // reset histogram
01731     virtual void  reset_histogram();
01732     
01733     /************************ Retrieving internal data *******************************/
01734     // get back project image
01735     virtual IplImage* get_back_project()
01736     { return m_back_project; }
01737     
01738     float query( int* bin ) const
01739     { return m_hist ? (float)cvGetRealND(m_hist->bins, bin) : 0.f; }
01740     
01741 protected:
01742     
01743     // internal method for color conversion: fills m_color_planes group
01744     virtual void color_transform( const IplImage* img );
01745     
01746     CvHistogram* m_hist;
01747     
01748     CvBox2D    m_box;
01749     CvConnectedComp m_comp;
01750     
01751     float      m_hist_ranges_data[CV_MAX_DIM][2];
01752     float*     m_hist_ranges[CV_MAX_DIM];
01753     
01754     int        m_min_ch_val[CV_MAX_DIM];
01755     int        m_max_ch_val[CV_MAX_DIM];
01756     int        m_threshold;
01757     
01758     IplImage*  m_color_planes[CV_MAX_DIM];
01759     IplImage*  m_back_project;
01760     IplImage*  m_temp;
01761     IplImage*  m_mask;
01762 };
01763 
01764 //#include "cvvidsurv.hpp"
01765 #endif
01766 
01767 #endif
01768 
01769 /* End of file. */
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends Defines