00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037
00038
00039
00040
00041
00042
00043 #ifndef __OPENCV_CALIB3D_HPP__
00044 #define __OPENCV_CALIB3D_HPP__
00045
00046 #include "opencv2/core/core.hpp"
00047
00048 #ifdef __cplusplus
00049 extern "C" {
00050 #endif
00051
00052
00053
00054
00055
00056 typedef struct CvPOSITObject CvPOSITObject;
00057
00058
00059 CVAPI(CvPOSITObject*) cvCreatePOSITObject( CvPoint3D32f* points, int point_count );
00060
00061
00062
00063
00064 CVAPI(void) cvPOSIT( CvPOSITObject* posit_object, CvPoint2D32f* image_points,
00065 double focal_length, CvTermCriteria criteria,
00066 float* rotation_matrix, float* translation_vector);
00067
00068
00069 CVAPI(void) cvReleasePOSITObject( CvPOSITObject** posit_object );
00070
00071
00072 CVAPI(int) cvRANSACUpdateNumIters( double p, double err_prob,
00073 int model_points, int max_iters );
00074
00075 CVAPI(void) cvConvertPointsHomogeneous( const CvMat* src, CvMat* dst );
00076
00077
00078 #define CV_FM_7POINT 1
00079 #define CV_FM_8POINT 2
00080
00081 #define CV_LMEDS 4
00082 #define CV_RANSAC 8
00083
00084 #define CV_FM_LMEDS_ONLY CV_LMEDS
00085 #define CV_FM_RANSAC_ONLY CV_RANSAC
00086 #define CV_FM_LMEDS CV_LMEDS
00087 #define CV_FM_RANSAC CV_RANSAC
00088
00089 CVAPI(int) cvFindFundamentalMat( const CvMat* points1, const CvMat* points2,
00090 CvMat* fundamental_matrix,
00091 int method CV_DEFAULT(CV_FM_RANSAC),
00092 double param1 CV_DEFAULT(3.), double param2 CV_DEFAULT(0.99),
00093 CvMat* status CV_DEFAULT(NULL) );
00094
00095
00096
00097
00098 CVAPI(void) cvComputeCorrespondEpilines( const CvMat* points,
00099 int which_image,
00100 const CvMat* fundamental_matrix,
00101 CvMat* correspondent_lines );
00102
00103
00104
00105 CVAPI(void) cvTriangulatePoints(CvMat* projMatr1, CvMat* projMatr2,
00106 CvMat* projPoints1, CvMat* projPoints2,
00107 CvMat* points4D);
00108
00109 CVAPI(void) cvCorrectMatches(CvMat* F, CvMat* points1, CvMat* points2,
00110 CvMat* new_points1, CvMat* new_points2);
00111
00112
00113
00114
00115
00116
00117 CVAPI(void) cvGetOptimalNewCameraMatrix( const CvMat* camera_matrix,
00118 const CvMat* dist_coeffs,
00119 CvSize image_size, double alpha,
00120 CvMat* new_camera_matrix,
00121 CvSize new_imag_size CV_DEFAULT(cvSize(0,0)),
00122 CvRect* valid_pixel_ROI CV_DEFAULT(0) );
00123
00124
00125 CVAPI(int) cvRodrigues2( const CvMat* src, CvMat* dst,
00126 CvMat* jacobian CV_DEFAULT(0) );
00127
00128
00129 CVAPI(int) cvFindHomography( const CvMat* src_points,
00130 const CvMat* dst_points,
00131 CvMat* homography,
00132 int method CV_DEFAULT(0),
00133 double ransacReprojThreshold CV_DEFAULT(3),
00134 CvMat* mask CV_DEFAULT(0));
00135
00136
00137 CVAPI(void) cvRQDecomp3x3( const CvMat *matrixM, CvMat *matrixR, CvMat *matrixQ,
00138 CvMat *matrixQx CV_DEFAULT(NULL),
00139 CvMat *matrixQy CV_DEFAULT(NULL),
00140 CvMat *matrixQz CV_DEFAULT(NULL),
00141 CvPoint3D64f *eulerAngles CV_DEFAULT(NULL));
00142
00143
00144 CVAPI(void) cvDecomposeProjectionMatrix( const CvMat *projMatr, CvMat *calibMatr,
00145 CvMat *rotMatr, CvMat *posVect,
00146 CvMat *rotMatrX CV_DEFAULT(NULL),
00147 CvMat *rotMatrY CV_DEFAULT(NULL),
00148 CvMat *rotMatrZ CV_DEFAULT(NULL),
00149 CvPoint3D64f *eulerAngles CV_DEFAULT(NULL));
00150
00151
00152 CVAPI(void) cvCalcMatMulDeriv( const CvMat* A, const CvMat* B, CvMat* dABdA, CvMat* dABdB );
00153
00154
00155
00156 CVAPI(void) cvComposeRT( const CvMat* _rvec1, const CvMat* _tvec1,
00157 const CvMat* _rvec2, const CvMat* _tvec2,
00158 CvMat* _rvec3, CvMat* _tvec3,
00159 CvMat* dr3dr1 CV_DEFAULT(0), CvMat* dr3dt1 CV_DEFAULT(0),
00160 CvMat* dr3dr2 CV_DEFAULT(0), CvMat* dr3dt2 CV_DEFAULT(0),
00161 CvMat* dt3dr1 CV_DEFAULT(0), CvMat* dt3dt1 CV_DEFAULT(0),
00162 CvMat* dt3dr2 CV_DEFAULT(0), CvMat* dt3dt2 CV_DEFAULT(0) );
00163
00164
00165
00166 CVAPI(void) cvProjectPoints2( const CvMat* object_points, const CvMat* rotation_vector,
00167 const CvMat* translation_vector, const CvMat* camera_matrix,
00168 const CvMat* distortion_coeffs, CvMat* image_points,
00169 CvMat* dpdrot CV_DEFAULT(NULL), CvMat* dpdt CV_DEFAULT(NULL),
00170 CvMat* dpdf CV_DEFAULT(NULL), CvMat* dpdc CV_DEFAULT(NULL),
00171 CvMat* dpddist CV_DEFAULT(NULL),
00172 double aspect_ratio CV_DEFAULT(0));
00173
00174
00175
00176 CVAPI(void) cvFindExtrinsicCameraParams2( const CvMat* object_points,
00177 const CvMat* image_points,
00178 const CvMat* camera_matrix,
00179 const CvMat* distortion_coeffs,
00180 CvMat* rotation_vector,
00181 CvMat* translation_vector,
00182 int use_extrinsic_guess CV_DEFAULT(0) );
00183
00184
00185
00186 CVAPI(void) cvInitIntrinsicParams2D( const CvMat* object_points,
00187 const CvMat* image_points,
00188 const CvMat* npoints, CvSize image_size,
00189 CvMat* camera_matrix,
00190 double aspect_ratio CV_DEFAULT(1.) );
00191
00192 #define CV_CALIB_CB_ADAPTIVE_THRESH 1
00193 #define CV_CALIB_CB_NORMALIZE_IMAGE 2
00194 #define CV_CALIB_CB_FILTER_QUADS 4
00195 #define CV_CALIB_CB_FAST_CHECK 8
00196
00197
00198
00199
00200
00201
00202
00203 CVAPI(int) cvCheckChessboard(IplImage* src, CvSize size);
00204
00205
00206 CVAPI(int) cvFindChessboardCorners( const void* image, CvSize pattern_size,
00207 CvPoint2D32f* corners,
00208 int* corner_count CV_DEFAULT(NULL),
00209 int flags CV_DEFAULT(CV_CALIB_CB_ADAPTIVE_THRESH+
00210 CV_CALIB_CB_NORMALIZE_IMAGE) );
00211
00212
00213 CVAPI(void) cvDrawChessboardCorners( CvArr* image, CvSize pattern_size,
00214 CvPoint2D32f* corners,
00215 int count, int pattern_was_found );
00216
00217 #define CV_CALIB_USE_INTRINSIC_GUESS 1
00218 #define CV_CALIB_FIX_ASPECT_RATIO 2
00219 #define CV_CALIB_FIX_PRINCIPAL_POINT 4
00220 #define CV_CALIB_ZERO_TANGENT_DIST 8
00221 #define CV_CALIB_FIX_FOCAL_LENGTH 16
00222 #define CV_CALIB_FIX_K1 32
00223 #define CV_CALIB_FIX_K2 64
00224 #define CV_CALIB_FIX_K3 128
00225 #define CV_CALIB_FIX_K4 2048
00226 #define CV_CALIB_FIX_K5 4096
00227 #define CV_CALIB_FIX_K6 8192
00228 #define CV_CALIB_RATIONAL_MODEL 16384
00229
00230
00231
00232 CVAPI(double) cvCalibrateCamera2( const CvMat* object_points,
00233 const CvMat* image_points,
00234 const CvMat* point_counts,
00235 CvSize image_size,
00236 CvMat* camera_matrix,
00237 CvMat* distortion_coeffs,
00238 CvMat* rotation_vectors CV_DEFAULT(NULL),
00239 CvMat* translation_vectors CV_DEFAULT(NULL),
00240 int flags CV_DEFAULT(0) );
00241
00242
00243
00244 CVAPI(void) cvCalibrationMatrixValues( const CvMat *camera_matrix,
00245 CvSize image_size,
00246 double aperture_width CV_DEFAULT(0),
00247 double aperture_height CV_DEFAULT(0),
00248 double *fovx CV_DEFAULT(NULL),
00249 double *fovy CV_DEFAULT(NULL),
00250 double *focal_length CV_DEFAULT(NULL),
00251 CvPoint2D64f *principal_point CV_DEFAULT(NULL),
00252 double *pixel_aspect_ratio CV_DEFAULT(NULL));
00253
00254 #define CV_CALIB_FIX_INTRINSIC 256
00255 #define CV_CALIB_SAME_FOCAL_LENGTH 512
00256
00257
00258
00259
00260 CVAPI(double) cvStereoCalibrate( const CvMat* object_points, const CvMat* image_points1,
00261 const CvMat* image_points2, const CvMat* npoints,
00262 CvMat* camera_matrix1, CvMat* dist_coeffs1,
00263 CvMat* camera_matrix2, CvMat* dist_coeffs2,
00264 CvSize image_size, CvMat* R, CvMat* T,
00265 CvMat* E CV_DEFAULT(0), CvMat* F CV_DEFAULT(0),
00266 CvTermCriteria term_crit CV_DEFAULT(cvTermCriteria(
00267 CV_TERMCRIT_ITER+CV_TERMCRIT_EPS,30,1e-6)),
00268 int flags CV_DEFAULT(CV_CALIB_FIX_INTRINSIC));
00269
00270 #define CV_CALIB_ZERO_DISPARITY 1024
00271
00272
00273
00274 CVAPI(void) cvStereoRectify( const CvMat* camera_matrix1, const CvMat* camera_matrix2,
00275 const CvMat* dist_coeffs1, const CvMat* dist_coeffs2,
00276 CvSize image_size, const CvMat* R, const CvMat* T,
00277 CvMat* R1, CvMat* R2, CvMat* P1, CvMat* P2,
00278 CvMat* Q CV_DEFAULT(0),
00279 int flags CV_DEFAULT(CV_CALIB_ZERO_DISPARITY),
00280 double alpha CV_DEFAULT(-1),
00281 CvSize new_image_size CV_DEFAULT(cvSize(0,0)),
00282 CvRect* valid_pix_ROI1 CV_DEFAULT(0),
00283 CvRect* valid_pix_ROI2 CV_DEFAULT(0));
00284
00285
00286
00287 CVAPI(int) cvStereoRectifyUncalibrated( const CvMat* points1, const CvMat* points2,
00288 const CvMat* F, CvSize img_size,
00289 CvMat* H1, CvMat* H2,
00290 double threshold CV_DEFAULT(5));
00291
00292
00293
00294
00295
00296 #define CV_STEREO_BM_NORMALIZED_RESPONSE 0
00297 #define CV_STEREO_BM_XSOBEL 1
00298
00299
00300 typedef struct CvStereoBMState
00301 {
00302
00303 int preFilterType;
00304 int preFilterSize;
00305 int preFilterCap;
00306
00307
00308 int SADWindowSize;
00309 int minDisparity;
00310 int numberOfDisparities;
00311
00312
00313 int textureThreshold;
00314
00315 int uniquenessRatio;
00316
00317
00318 int speckleWindowSize;
00319 int speckleRange;
00320
00321 int trySmallerWindows;
00322
00323 CvRect roi1, roi2;
00324 int disp12MaxDiff;
00325
00326
00327 CvMat* preFilteredImg0;
00328 CvMat* preFilteredImg1;
00329 CvMat* slidingSumBuf;
00330 CvMat* cost;
00331 CvMat* disp;
00332 } CvStereoBMState;
00333
00334 #define CV_STEREO_BM_BASIC 0
00335 #define CV_STEREO_BM_FISH_EYE 1
00336 #define CV_STEREO_BM_NARROW 2
00337
00338 CVAPI(CvStereoBMState*) cvCreateStereoBMState(int preset CV_DEFAULT(CV_STEREO_BM_BASIC),
00339 int numberOfDisparities CV_DEFAULT(0));
00340
00341 CVAPI(void) cvReleaseStereoBMState( CvStereoBMState** state );
00342
00343 CVAPI(void) cvFindStereoCorrespondenceBM( const CvArr* left, const CvArr* right,
00344 CvArr* disparity, CvStereoBMState* state );
00345
00346 CVAPI(CvRect) cvGetValidDisparityROI( CvRect roi1, CvRect roi2, int minDisparity,
00347 int numberOfDisparities, int SADWindowSize );
00348
00349 CVAPI(void) cvValidateDisparity( CvArr* disparity, const CvArr* cost,
00350 int minDisparity, int numberOfDisparities,
00351 int disp12MaxDiff CV_DEFAULT(1) );
00352
00353
00354 #define CV_STEREO_GC_OCCLUDED SHRT_MAX
00355
00356 typedef struct CvStereoGCState
00357 {
00358 int Ithreshold;
00359 int interactionRadius;
00360 float K, lambda, lambda1, lambda2;
00361 int occlusionCost;
00362 int minDisparity;
00363 int numberOfDisparities;
00364 int maxIters;
00365
00366 CvMat* left;
00367 CvMat* right;
00368 CvMat* dispLeft;
00369 CvMat* dispRight;
00370 CvMat* ptrLeft;
00371 CvMat* ptrRight;
00372 CvMat* vtxBuf;
00373 CvMat* edgeBuf;
00374 } CvStereoGCState;
00375
00376 CVAPI(CvStereoGCState*) cvCreateStereoGCState( int numberOfDisparities, int maxIters );
00377 CVAPI(void) cvReleaseStereoGCState( CvStereoGCState** state );
00378
00379 CVAPI(void) cvFindStereoCorrespondenceGC( const CvArr* left, const CvArr* right,
00380 CvArr* disparityLeft, CvArr* disparityRight,
00381 CvStereoGCState* state,
00382 int useDisparityGuess CV_DEFAULT(0) );
00383
00384
00385 CVAPI(void) cvReprojectImageTo3D( const CvArr* disparityImage,
00386 CvArr* _3dImage, const CvMat* Q,
00387 int handleMissingValues CV_DEFAULT(0) );
00388
00389
00390 #ifdef __cplusplus
00391 }
00392
00394
00395 class CV_EXPORTS CvLevMarq
00396 {
00397 public:
00398 CvLevMarq();
00399 CvLevMarq( int nparams, int nerrs, CvTermCriteria criteria=
00400 cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
00401 bool completeSymmFlag=false );
00402 ~CvLevMarq();
00403 void init( int nparams, int nerrs, CvTermCriteria criteria=
00404 cvTermCriteria(CV_TERMCRIT_EPS+CV_TERMCRIT_ITER,30,DBL_EPSILON),
00405 bool completeSymmFlag=false );
00406 bool update( const CvMat*& param, CvMat*& J, CvMat*& err );
00407 bool updateAlt( const CvMat*& param, CvMat*& JtJ, CvMat*& JtErr, double*& errNorm );
00408
00409 void clear();
00410 void step();
00411 enum { DONE=0, STARTED=1, CALC_J=2, CHECK_ERR=3 };
00412
00413 cv::Ptr<CvMat> mask;
00414 cv::Ptr<CvMat> prevParam;
00415 cv::Ptr<CvMat> param;
00416 cv::Ptr<CvMat> J;
00417 cv::Ptr<CvMat> err;
00418 cv::Ptr<CvMat> JtJ;
00419 cv::Ptr<CvMat> JtJN;
00420 cv::Ptr<CvMat> JtErr;
00421 cv::Ptr<CvMat> JtJV;
00422 cv::Ptr<CvMat> JtJW;
00423 double prevErrNorm, errNorm;
00424 int lambdaLg10;
00425 CvTermCriteria criteria;
00426 int state;
00427 int iters;
00428 bool completeSymmFlag;
00429 };
00430
00431 namespace cv
00432 {
00433
00435 CV_EXPORTS_W void Rodrigues(const Mat& src, CV_OUT Mat& dst);
00436
00438 CV_EXPORTS_AS(RodriguesJ) void Rodrigues(const Mat& src, CV_OUT Mat& dst, CV_OUT Mat& jacobian);
00439
00441 enum
00442 {
00443 LMEDS=CV_LMEDS,
00444 RANSAC=CV_RANSAC
00445 };
00446
00448 CV_EXPORTS_AS(findHomographyAndOutliers) Mat findHomography( const Mat& srcPoints,
00449 const Mat& dstPoints,
00450 vector<uchar>& mask, int method=0,
00451 double ransacReprojThreshold=3 );
00452
00454 CV_EXPORTS_W Mat findHomography( const Mat& srcPoints,
00455 const Mat& dstPoints,
00456 int method=0, double ransacReprojThreshold=3 );
00457
00459 CV_EXPORTS int estimateAffine3D(const Mat& from, const Mat& to, CV_OUT Mat& dst,
00460 CV_OUT vector<uchar>& outliers,
00461 double param1 = 3.0, double param2 = 0.99);
00462
00464 CV_EXPORTS void RQDecomp3x3( const Mat& M, Mat& R, Mat& Q );
00465
00467 CV_EXPORTS_W Vec3d RQDecomp3x3( const Mat& M, Mat& R, Mat& Q,
00468 CV_OUT Mat& Qx, CV_OUT Mat& Qy, CV_OUT Mat& Qz );
00469
00471 CV_EXPORTS void decomposeProjectionMatrix( const Mat& projMatrix, Mat& cameraMatrix,
00472 Mat& rotMatrix, Mat& transVect );
00473
00475 CV_EXPORTS_W void decomposeProjectionMatrix( const Mat& projMatrix, CV_OUT Mat& cameraMatrix,
00476 CV_OUT Mat& rotMatrix, CV_OUT Mat& transVect,
00477 CV_OUT Mat& rotMatrixX, CV_OUT Mat& rotMatrixY,
00478 CV_OUT Mat& rotMatrixZ, CV_OUT Vec3d& eulerAngles );
00479
00481 CV_EXPORTS_W void matMulDeriv( const Mat& A, const Mat& B, CV_OUT Mat& dABdA, CV_OUT Mat& dABdB );
00482
00484 CV_EXPORTS_W void composeRT( const Mat& rvec1, const Mat& tvec1,
00485 const Mat& rvec2, const Mat& tvec2,
00486 CV_OUT Mat& rvec3, CV_OUT Mat& tvec3 );
00487
00489 CV_EXPORTS_AS(composeRT_J) void composeRT( const Mat& rvec1, const Mat& tvec1,
00490 const Mat& rvec2, const Mat& tvec2,
00491 CV_OUT Mat& rvec3, CV_OUT Mat& tvec3,
00492 CV_OUT Mat& dr3dr1, CV_OUT Mat& dr3dt1,
00493 CV_OUT Mat& dr3dr2, CV_OUT Mat& dr3dt2,
00494 CV_OUT Mat& dt3dr1, CV_OUT Mat& dt3dt1,
00495 CV_OUT Mat& dt3dr2, CV_OUT Mat& dt3dt2 );
00496
00498 CV_EXPORTS_W void projectPoints( const Mat& objectPoints,
00499 const Mat& rvec, const Mat& tvec,
00500 const Mat& cameraMatrix,
00501 const Mat& distCoeffs,
00502 CV_OUT vector<Point2f>& imagePoints );
00503
00505 CV_EXPORTS_AS(projectPointsJ) void projectPoints( const Mat& objectPoints,
00506 const Mat& rvec, const Mat& tvec,
00507 const Mat& cameraMatrix,
00508 const Mat& distCoeffs,
00509 CV_OUT vector<Point2f>& imagePoints,
00510 CV_OUT Mat& dpdrot, CV_OUT Mat& dpdt, CV_OUT Mat& dpdf,
00511 CV_OUT Mat& dpdc, CV_OUT Mat& dpddist,
00512 double aspectRatio=0 );
00513
00515 CV_EXPORTS_W void solvePnP( const Mat& objectPoints,
00516 const Mat& imagePoints,
00517 const Mat& cameraMatrix,
00518 const Mat& distCoeffs,
00519 CV_OUT Mat& rvec, CV_OUT Mat& tvec,
00520 bool useExtrinsicGuess=false );
00521
00523 CV_EXPORTS_W Mat initCameraMatrix2D( const vector<vector<Point3f> >& objectPoints,
00524 const vector<vector<Point2f> >& imagePoints,
00525 Size imageSize, double aspectRatio=1. );
00526
00527
00528 enum { CALIB_CB_ADAPTIVE_THRESH = 1, CALIB_CB_NORMALIZE_IMAGE = 2,
00529 CALIB_CB_FILTER_QUADS = 4, CALIB_CB_FAST_CHECK = 8 };
00530
00532 CV_EXPORTS_W bool findChessboardCorners( const Mat& image, Size patternSize,
00533 CV_OUT vector<Point2f>& corners,
00534 int flags=CALIB_CB_ADAPTIVE_THRESH+
00535 CALIB_CB_NORMALIZE_IMAGE );
00536
00538 CV_EXPORTS_W void drawChessboardCorners( Mat& image, Size patternSize,
00539 const Mat& corners,
00540 bool patternWasFound );
00541
00542 CV_EXPORTS void drawChessboardCorners( Mat& image, Size patternSize,
00543 const vector<Point2f>& corners,
00544 bool patternWasFound );
00545
00547 CV_EXPORTS_W bool findCirclesGrid( const Mat& image, Size patternSize,
00548 CV_OUT vector<Point2f>& centers,
00549 int flags=0 );
00550
00551 enum
00552 {
00553 CALIB_USE_INTRINSIC_GUESS = CV_CALIB_USE_INTRINSIC_GUESS,
00554 CALIB_FIX_ASPECT_RATIO = CV_CALIB_FIX_ASPECT_RATIO,
00555 CALIB_FIX_PRINCIPAL_POINT = CV_CALIB_FIX_PRINCIPAL_POINT,
00556 CALIB_ZERO_TANGENT_DIST = CV_CALIB_ZERO_TANGENT_DIST,
00557 CALIB_FIX_FOCAL_LENGTH = CV_CALIB_FIX_FOCAL_LENGTH,
00558 CALIB_FIX_K1 = CV_CALIB_FIX_K1,
00559 CALIB_FIX_K2 = CV_CALIB_FIX_K2,
00560 CALIB_FIX_K3 = CV_CALIB_FIX_K3,
00561 CALIB_FIX_K4 = CV_CALIB_FIX_K4,
00562 CALIB_FIX_K5 = CV_CALIB_FIX_K5,
00563 CALIB_FIX_K6 = CV_CALIB_FIX_K6,
00564 CALIB_RATIONAL_MODEL = CV_CALIB_RATIONAL_MODEL,
00565
00566 CALIB_FIX_INTRINSIC = CV_CALIB_FIX_INTRINSIC,
00567 CALIB_SAME_FOCAL_LENGTH = CV_CALIB_SAME_FOCAL_LENGTH,
00568
00569 CALIB_ZERO_DISPARITY = CV_CALIB_ZERO_DISPARITY
00570 };
00571
00573 CV_EXPORTS_W double calibrateCamera( const vector<vector<Point3f> >& objectPoints,
00574 const vector<vector<Point2f> >& imagePoints,
00575 Size imageSize,
00576 CV_IN_OUT Mat& cameraMatrix,
00577 CV_IN_OUT Mat& distCoeffs,
00578 CV_OUT vector<Mat>& rvecs, CV_OUT vector<Mat>& tvecs,
00579 int flags=0 );
00580
00582 CV_EXPORTS_W void calibrationMatrixValues( const Mat& cameraMatrix,
00583 Size imageSize,
00584 double apertureWidth,
00585 double apertureHeight,
00586 CV_OUT double& fovx,
00587 CV_OUT double& fovy,
00588 CV_OUT double& focalLength,
00589 CV_OUT Point2d& principalPoint,
00590 CV_OUT double& aspectRatio );
00591
00593 CV_EXPORTS_W double stereoCalibrate( const vector<vector<Point3f> >& objectPoints,
00594 const vector<vector<Point2f> >& imagePoints1,
00595 const vector<vector<Point2f> >& imagePoints2,
00596 CV_IN_OUT Mat& cameraMatrix1, CV_IN_OUT Mat& distCoeffs1,
00597 CV_IN_OUT Mat& cameraMatrix2, CV_IN_OUT Mat& distCoeffs2,
00598 Size imageSize, CV_OUT Mat& R, CV_OUT Mat& T,
00599 CV_OUT Mat& E, CV_OUT Mat& F,
00600 TermCriteria criteria = TermCriteria(TermCriteria::COUNT+
00601 TermCriteria::EPS, 30, 1e-6),
00602 int flags=CALIB_FIX_INTRINSIC );
00603
00604
00606 CV_EXPORTS void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1,
00607 const Mat& cameraMatrix2, const Mat& distCoeffs2,
00608 Size imageSize, const Mat& R, const Mat& T,
00609 CV_OUT Mat& R1, CV_OUT Mat& R2,
00610 CV_OUT Mat& P1, CV_OUT Mat& P2, CV_OUT Mat& Q,
00611 int flags=CALIB_ZERO_DISPARITY );
00612
00614 CV_EXPORTS_W void stereoRectify( const Mat& cameraMatrix1, const Mat& distCoeffs1,
00615 const Mat& cameraMatrix2, const Mat& distCoeffs2,
00616 Size imageSize, const Mat& R, const Mat& T,
00617 CV_OUT Mat& R1, CV_OUT Mat& R2,
00618 CV_OUT Mat& P1, CV_OUT Mat& P2, CV_OUT Mat& Q,
00619 double alpha, Size newImageSize=Size(),
00620 CV_OUT Rect* validPixROI1=0, CV_OUT Rect* validPixROI2=0,
00621 int flags=CALIB_ZERO_DISPARITY );
00622
00624 CV_EXPORTS_W bool stereoRectifyUncalibrated( const Mat& points1, const Mat& points2,
00625 const Mat& F, Size imgSize,
00626 CV_OUT Mat& H1, CV_OUT Mat& H2,
00627 double threshold=5 );
00628
00630 CV_EXPORTS_W float rectify3Collinear( const Mat& cameraMatrix1, const Mat& distCoeffs1,
00631 const Mat& cameraMatrix2, const Mat& distCoeffs2,
00632 const Mat& cameraMatrix3, const Mat& distCoeffs3,
00633 const vector<vector<Point2f> >& imgpt1,
00634 const vector<vector<Point2f> >& imgpt3,
00635 Size imageSize, const Mat& R12, const Mat& T12,
00636 const Mat& R13, const Mat& T13,
00637 CV_OUT Mat& R1, CV_OUT Mat& R2, CV_OUT Mat& R3,
00638 CV_OUT Mat& P1, CV_OUT Mat& P2, CV_OUT Mat& P3, CV_OUT Mat& Q,
00639 double alpha, Size newImgSize,
00640 CV_OUT Rect* roi1, CV_OUT Rect* roi2, int flags );
00641
00643 CV_EXPORTS_W Mat getOptimalNewCameraMatrix( const Mat& cameraMatrix, const Mat& distCoeffs,
00644 Size imageSize, double alpha, Size newImgSize=Size(),
00645 CV_OUT Rect* validPixROI=0);
00646
00648 CV_EXPORTS void convertPointsHomogeneous( const Mat& src, CV_OUT vector<Point3f>& dst );
00650 CV_EXPORTS void convertPointsHomogeneous( const Mat& src, CV_OUT vector<Point2f>& dst );
00651
00653 enum
00654 {
00655 FM_7POINT = CV_FM_7POINT,
00656 FM_8POINT = CV_FM_8POINT,
00657 FM_LMEDS = CV_FM_LMEDS,
00658 FM_RANSAC = CV_FM_RANSAC
00659 };
00660
00662 CV_EXPORTS Mat findFundamentalMat( const Mat& points1, const Mat& points2,
00663 CV_OUT vector<uchar>& mask, int method=FM_RANSAC,
00664 double param1=3., double param2=0.99 );
00665
00667 CV_EXPORTS_W Mat findFundamentalMat( const Mat& points1, const Mat& points2,
00668 int method=FM_RANSAC,
00669 double param1=3., double param2=0.99 );
00670
00672 CV_EXPORTS void computeCorrespondEpilines( const Mat& points1,
00673 int whichImage, const Mat& F,
00674 CV_OUT vector<Vec3f>& lines );
00675
00676 template<> CV_EXPORTS void Ptr<CvStereoBMState>::delete_obj();
00677
00683 class CV_EXPORTS_W StereoBM
00684 {
00685 public:
00686 enum { PREFILTER_NORMALIZED_RESPONSE = 0, PREFILTER_XSOBEL = 1,
00687 BASIC_PRESET=0, FISH_EYE_PRESET=1, NARROW_PRESET=2 };
00688
00690 CV_WRAP StereoBM();
00692 CV_WRAP StereoBM(int preset, int ndisparities=0, int SADWindowSize=21);
00694 void init(int preset, int ndisparities=0, int SADWindowSize=21);
00696 CV_WRAP_AS(compute) void operator()( const Mat& left, const Mat& right, Mat& disparity, int disptype=CV_16S );
00697
00699 Ptr<CvStereoBMState> state;
00700 };
00701
00702
00708 class CV_EXPORTS_W StereoSGBM
00709 {
00710 public:
00711 enum { DISP_SHIFT=4, DISP_SCALE = (1<<DISP_SHIFT) };
00712
00714 CV_WRAP StereoSGBM();
00715
00717 CV_WRAP StereoSGBM(int minDisparity, int numDisparities, int SADWindowSize,
00718 int P1=0, int P2=0, int disp12MaxDiff=0,
00719 int preFilterCap=0, int uniquenessRatio=0,
00720 int speckleWindowSize=0, int speckleRange=0,
00721 bool fullDP=false);
00723 virtual ~StereoSGBM();
00724
00726 CV_WRAP_AS(compute) virtual void operator()(const Mat& left, const Mat& right, Mat& disp);
00727
00728 CV_PROP_RW int minDisparity;
00729 CV_PROP_RW int numberOfDisparities;
00730 CV_PROP_RW int SADWindowSize;
00731 CV_PROP_RW int preFilterCap;
00732 CV_PROP_RW int uniquenessRatio;
00733 CV_PROP_RW int P1;
00734 CV_PROP_RW int P2;
00735 CV_PROP_RW int speckleWindowSize;
00736 CV_PROP_RW int speckleRange;
00737 CV_PROP_RW int disp12MaxDiff;
00738 CV_PROP_RW bool fullDP;
00739
00740 protected:
00741 Mat buffer;
00742 };
00743
00745 CV_EXPORTS_W void filterSpeckles( Mat& img, double newVal, int maxSpeckleSize, double maxDiff, Mat& buf );
00746
00748 CV_EXPORTS_W Rect getValidDisparityROI( Rect roi1, Rect roi2,
00749 int minDisparity, int numberOfDisparities,
00750 int SADWindowSize );
00751
00753 CV_EXPORTS_W void validateDisparity( Mat& disparity, const Mat& cost,
00754 int minDisparity, int numberOfDisparities,
00755 int disp12MaxDisp=1 );
00756
00758 CV_EXPORTS_W void reprojectImageTo3D( const Mat& disparity,
00759 CV_OUT Mat& _3dImage, const Mat& Q,
00760 bool handleMissingValues=false );
00761
00762 }
00763
00764 #endif
00765
00766 #endif