calib3d 
        library 
 
       
    
    
    
      Classes 
      
          
  Fisheye  
  
 
          
  StereoBM  
  Class for computing stereo correspondence using the block matching algorithm,
introduced and contributed to OpenCV by K. Konolige.
 
          
  StereoSGBM  
  The class implements the modified H. Hirschmuller algorithm 128 that differs from the original one as follows:
 
          
  UsacParams  
  
 
       
     
    
    
      Functions 
      
          
  calibrateCamera (Contours3f objectPoints , Contours2f imagePoints , (int int   imageSize , InputOutputArray cameraMatrix , InputOutputArray distCoeffs , {Mat ?rvecs , Mat ?tvecs , int flags  = 0 , (int int double   criteria  = (TERM_COUNT + TERM_EPS, 30, 1e-4) → (double Mat Mat Mat Mat  
   
  
 
  CalibrateCamera finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
  
 
          
  calibrateCameraAsync (Contours3f objectPoints , Contours2f imagePoints , (int int   imageSize , InputOutputArray cameraMatrix , InputOutputArray distCoeffs , {Mat ?rvecs , Mat ?tvecs , int flags  = 0 , (int int double   criteria  = (TERM_COUNT + TERM_EPS, 30, 1e-4) → Future <(double Mat Mat Mat Mat  >  
   
  
 
  
  
 
          
  checkChessboard (Mat img , Size size → bool  
   
  
 
  https://docs.opencv.org/4.11.0/d9/d0c/group__calib3d.html#gacd8162cfd39138d0bc29e4b53d080673 
  
 
          
  computeCorrespondEpilines (InputArray points , int whichImage , InputArray F , {OutputArray ?lines → Mat  
   
  
 
  For points in an image of a stereo pair, computes the corresponding epilines in the other image.
  
 
          
  computeCorrespondEpilinesAsync (InputArray points , int whichImage , InputArray F , {OutputArray ?lines → Future <Mat   
   
  
 
  For points in an image of a stereo pair, computes the corresponding epilines in the other image.
  
 
          
  convertPointsFromHomogeneous (InputArray src , {OutputArray ?dst → Mat  
   
  
 
  Converts points from homogeneous to Euclidean space.
  
 
          
  convertPointsFromHomogeneousAsync (InputArray src , {OutputArray ?dst → Future <Mat   
   
  
 
  Converts points from homogeneous to Euclidean space.
  
 
          
  convertPointsToHomogeneous (InputArray src , {OutputArray ?dst → Mat  
   
  
 
  Converts points from Euclidean to homogeneous space.
  
 
          
  convertPointsToHomogeneousAsync (InputArray src , {OutputArray ?dst → Future <Mat   
   
  
 
  Converts points from Euclidean to homogeneous space.
  
 
          
  correctMatches (Mat F , InputArray points1 , InputArray points2 , {OutputArray ?newPoints1 , OutputArray ?newPoints2 → (Mat Mat  
   
  
 
  Refines coordinates of corresponding points.
  
 
          
  correctMatchesAsync (Mat F , InputArray points1 , InputArray points2 , {OutputArray ?newPoints1 , OutputArray ?newPoints2 → Future <(Mat Mat  >  
   
  
 
  Refines coordinates of corresponding points.
  
 
          
  decomposeEssentialMat (Mat E , {OutputArray ?R1 , OutputArray ?R2 , OutputArray ?t → (Mat Mat Mat  
   
  
 
  Decompose an essential matrix to possible rotations and translation.
  
 
          
  decomposeEssentialMatAsync (Mat E , {OutputArray ?R1 , OutputArray ?R2 , OutputArray ?t → Future <(Mat Mat Mat  >  
   
  
 
  Decompose an essential matrix to possible rotations and translation.
  
 
          
  decomposeHomographyMat (Mat H , Mat K , {VecMat ?rotations , VecMat ?translations , VecMat ?normals → (int VecMat VecMat VecMat  
   
  
 
  Decompose a homography matrix to rotation(s), translation(s) and plane normal(s).
  
 
          
  decomposeHomographyMatAsync (Mat H , Mat K , {VecMat ?rotations , VecMat ?translations , VecMat ?normals → Future <(int VecMat VecMat VecMat  >  
   
  
 
  Decompose a homography matrix to rotation(s), translation(s) and plane normal(s).
  
 
          
  decomposeProjectionMatrix (Mat projMatrix , {OutputArray ?cameraMatrix , OutputArray ?rotMatrix , OutputArray ?transVect , OutputArray ?rotMatrixX , OutputArray ?rotMatrixY , OutputArray ?rotMatrixZ , OutputArray ?eulerAngles → (Mat Mat Mat  
   
  
 
  Decomposes a projection matrix into a rotation matrix and a camera intrinsic matrix.
  
 
          
  decomposeProjectionMatrixAsync (Mat projMatrix , {OutputArray ?cameraMatrix , OutputArray ?rotMatrix , OutputArray ?transVect , OutputArray ?rotMatrixX , OutputArray ?rotMatrixY , OutputArray ?rotMatrixZ , OutputArray ?eulerAngles → Future <(Mat Mat Mat  >  
   
  
 
  Decomposes a projection matrix into a rotation matrix and a camera intrinsic matrix.
  
 
          
  drawChessboardCorners (InputOutputArray image , (int int   patternSize , VecPoint2f corners , bool patternWasFound → Mat  
   
  
 
  DrawChessboardCorners renders the detected chessboard corners.
  
 
          
  drawChessboardCornersAsync (InputOutputArray image , (int int   patternSize , VecPoint2f corners , bool patternWasFound → Future <Mat   
   
  
 
  
  
 
          
  drawFrameAxes (Mat image , Mat cameraMatrix , Mat distCoeffs , Mat rvec , Mat tvec , double length , {int thickness  = 3 → void 
   
  
 
  Draw axes of the world/object coordinate system from pose estimation.
  
 
          
  drawFrameAxesAsync (Mat image , Mat cameraMatrix , Mat distCoeffs , Mat rvec , Mat tvec , double length , {int thickness  = 3 → Future <void >  
   
  
 
  Draw axes of the world/object coordinate system from pose estimation.
  
 
          
  estimateAffine2D (VecPoint2f from , VecPoint2f to , {int method  = RANSAC , double ransacReprojThreshold  = 3 , int maxIters  = 2000 , double confidence  = 0.99 , int refineIters  = 10 , OutputArray ?inliers → (Mat Mat  
   
  
 
  EstimateAffine2D Computes an optimal affine transformation between two 2D point sets.
  
 
          
  estimateAffine2DAsync (VecPoint2f from , VecPoint2f to , {int method  = RANSAC , double ransacReprojThreshold  = 3 , int maxIters  = 2000 , double confidence  = 0.99 , int refineIters  = 10 , OutputArray ?inliers → Future <(Mat Mat  >  
   
  
 
  
  
 
          
  estimateAffine3D (Mat src , Mat dst , {Mat ?out , Mat ?inliers , double ransacThreshold  = 3 , double confidence  = 0.99 → (int Mat Mat  
   
  
 
  Computes an optimal affine transformation between two 3D point sets.
  
 
          
  estimateAffine3DAsync (Mat src , Mat dst , {Mat ?out , Mat ?inliers , double ransacThreshold  = 3 , double confidence  = 0.99 → Future <(int Mat Mat  >  
   
  
 
  Computes an optimal affine transformation between two 3D point sets.
  
 
          
  estimateAffinePartial2D (VecPoint2f from , VecPoint2f to , {int method  = RANSAC , double ransacReprojThreshold  = 3 , int maxIters  = 2000 , double confidence  = 0.99 , int refineIters  = 10 , OutputArray ?inliers → (Mat Mat  
   
  
 
  EstimateAffinePartial2D computes an optimal limited affine transformation
with 4 degrees of freedom between two 2D point sets.
  
 
          
  estimateAffinePartial2DAsync (VecPoint2f from , VecPoint2f to , {int method  = RANSAC , double ransacReprojThreshold  = 3 , int maxIters  = 2000 , double confidence  = 0.99 , int refineIters  = 10 , OutputArray ?inliers → Future <(Mat Mat  >  
   
  
 
  
  
 
          
  estimateChessboardSharpness (InputArray image , (int int   patternSize , InputArray corners , {double riseDistance  = 0.8 , bool vertical  = false , OutputArray ?sharpness → Scalar  
   
  
 
  Estimates the sharpness of a detected chessboard.
  
 
          
  estimateChessboardSharpnessAsync (InputArray image , (int int   patternSize , InputArray corners , {double riseDistance  = 0.8 , bool vertical  = false , OutputArray ?sharpness → Future <Scalar   
   
  
 
  Estimates the sharpness of a detected chessboard.
  
 
          
  estimateTranslation3D (InputArray src , InputArray dst , {OutputArray ?out , OutputArray ?inliers , double ransacThreshold  = 3 , double confidence  = 0.99 → (int Mat Mat  
   
  
 
  Computes an optimal translation between two 3D point sets.
  
 
          
  estimateTranslation3DAsync (InputArray src , InputArray dst , {OutputArray ?out , OutputArray ?inliers , double ransacThreshold  = 3 , double confidence  = 0.99 → Future <(int Mat Mat  >  
   
  
 
  Computes an optimal translation between two 3D point sets.
  
 
          
  filterHomographyDecompByVisibleRefpoints (VecMat rotations , VecMat normals , InputArray beforePoints , InputArray afterPoints , {OutputArray ?possibleSolutions , InputArray ?pointsMask → Mat  
   
  
 
  Filters homography decompositions based on additional information.
  
 
          
  filterHomographyDecompByVisibleRefpointsAsync (VecMat rotations , VecMat normals , InputArray beforePoints , InputArray afterPoints , {OutputArray ?possibleSolutions , InputArray ?pointsMask → Future <Mat   
   
  
 
  Filters homography decompositions based on additional information.
  
 
          
  filterSpeckles (InputOutputArray img , double newVal , int maxSpeckleSize , double maxDiff , {OutputArray ?buf → void 
   
  
 
  Filters off small noise blobs (speckles) in the disparity map.
  
 
          
  filterSpecklesAsync (InputOutputArray img , double newVal , int maxSpeckleSize , double maxDiff , {OutputArray ?buf → Future <void >  
   
  
 
  Filters off small noise blobs (speckles) in the disparity map.
  
 
          
  find4QuadCornerSubpix (InputArray img , InputOutputArray corners , (int int   regionSize → bool  
   
  
 
  finds subpixel-accurate positions of the chessboard corners
  
 
          
  find4QuadCornerSubpixAsync (InputArray img , InputOutputArray corners , (int int   regionSize → Future <bool   
   
  
 
  finds subpixel-accurate positions of the chessboard corners
  
 
          
  findChessboardCorners (InputArray image , (int int   patternSize , {VecPoint2f ?corners , int flags  = CALIB_CB_ADAPTIVE_THRESH + CALIB_CB_NORMALIZE_IMAGE → (bool VecPoint2f  
   
  
 
  FindChessboardCorners finds the positions of internal corners of the chessboard.
  
 
          
  findChessboardCornersAsync (InputArray image , (int int   patternSize , {VecPoint2f ?corners , int flags  = CALIB_CB_ADAPTIVE_THRESH + CALIB_CB_NORMALIZE_IMAGE → Future <(bool VecPoint2f  >  
   
  
 
  
  
 
          
  Finds the positions of internal corners of the chessboard using a sector based approach.
  
 
          
  
  
 
          
  Finds the positions of internal corners of the chessboard using a sector based approach.
  
 
          
  
  
 
          
  findCirclesGrid (InputArray image , Size patternSize , {int flags  = CALIB_CB_SYMMETRIC_GRID , OutputArray ?centers → (bool Mat  
   
  
 
  Finds centers in the grid of circles.
  
 
          
  findCirclesGridAsync (InputArray image , Size patternSize , {int flags  = CALIB_CB_SYMMETRIC_GRID , OutputArray ?centers → Future <(bool Mat  >  
   
  
 
  Finds centers in the grid of circles.
  
 
          
  findEssentialMat (InputArray points1 , InputArray points2 , {double focal  = 1.0 , Point2d ?pp , int method  = RANSAC , double prob  = 0.999 , double threshold  = 1.0 , int maxIters  = 1000 , OutputArray ?mask → Mat  
   
  
 
  Calculates an essential matrix from the corresponding points in two images.
  
 
          
  findEssentialMatAsync (InputArray points1 , InputArray points2 , {double focal  = 1.0 , Point2d ?pp , int method  = RANSAC , double prob  = 0.999 , double threshold  = 1.0 , int maxIters  = 1000 , OutputArray ?mask → Future <Mat   
   
  
 
  Calculates an essential matrix from the corresponding points in two images.
  
 
          
  findEssentialMatCameraMatrix (InputArray points1 , InputArray points2 , InputArray cameraMatrix , {int method  = RANSAC , double prob  = 0.999 , double threshold  = 1.0 , int maxIters  = 1000 , OutputArray ?mask → Mat  
   
  
 
  Calculates an essential matrix from the corresponding points in two images.
  
 
          
  findEssentialMatCameraMatrixAsync (InputArray points1 , InputArray points2 , InputArray cameraMatrix , {int method  = RANSAC , double prob  = 0.999 , double threshold  = 1.0 , int maxIters  = 1000 , OutputArray ?mask → Future <Mat   
   
  
 
  Calculates an essential matrix from the corresponding points in two images.
  
 
          
  findFundamentalMat (InputArray points1 , InputArray points2 , {int method  = FM_RANSAC , double ransacReprojThreshold  = 3 , double confidence  = 0.99 , int maxIters  = 1000 , OutputArray ?mask → Mat  
   
  
 
  Calculates a fundamental matrix from the corresponding points in two images.
  
 
          
  findFundamentalMatAsync (InputArray points1 , InputArray points2 , {int method  = FM_RANSAC , double ransacReprojThreshold  = 3 , double confidence  = 0.99 , int maxIters  = 1000 , OutputArray ?mask → Future <Mat   
   
  
 
  Calculates a fundamental matrix from the corresponding points in two images.
  
 
          
  findFundamentalMatUsac (InputArray points1 , InputArray points2 , UsacParams params , {OutputArray ?mask → Mat  
   
  
 
  Calculates a fundamental matrix from the corresponding points in two images.
  
 
          
  findFundamentalMatUsacAsync (InputArray points1 , InputArray points2 , UsacParams params , {OutputArray ?mask → Future <Mat   
   
  
 
  Calculates a fundamental matrix from the corresponding points in two images.
  
 
          
  findHomography (InputArray srcPoints , InputArray dstPoints , {int method  = 0 , double ransacReprojThreshold  = 3 , OutputArray ?mask , int maxIters  = 2000 , double confidence  = 0.995 → Mat  
   
  
 
  FindHomography finds an optimal homography matrix using 4 or more point pairs (as opposed to GetPerspectiveTransform, which uses exactly 4)
  
 
          
  findHomographyAsync (InputArray srcPoints , InputArray dstPoints , {int method  = 0 , double ransacReprojThreshold  = 3 , OutputArray ?mask , int maxIters  = 2000 , double confidence  = 0.995 → Future <(Mat Mat  >  
   
  
 
  FindHomography finds an optimal homography matrix using 4 or more point pairs (as opposed to GetPerspectiveTransform, which uses exactly 4)
  
 
          
  findHomographyUsac (InputArray srcPoints , InputArray dstPoints , UsacParams params , {OutputArray ?mask → Mat  
   
  
 
  FindHomography finds an optimal homography matrix using 4 or more point pairs (as opposed to GetPerspectiveTransform, which uses exactly 4)
  
 
          
  findHomographyUsacAsync (InputArray srcPoints , InputArray dstPoints , UsacParams params , {OutputArray ?mask → Future <Mat   
   
  
 
  FindHomography finds an optimal homography matrix using 4 or more point pairs (as opposed to GetPerspectiveTransform, which uses exactly 4)
  
 
          
  getDefaultNewCameraMatrix (InputArray cameraMatrix , {Size ?imgsize , bool centerPrincipalPoint  = false → Mat  
   
  
 
  Returns the default new camera matrix.
  
 
          
  getDefaultNewCameraMatrixAsync (InputArray cameraMatrix , {Size ?imgsize , bool centerPrincipalPoint  = false → Future <Mat   
   
  
 
  Returns the default new camera matrix.
  
 
          
  getOptimalNewCameraMatrix (InputArray cameraMatrix , InputArray distCoeffs , (int int   imageSize , double alpha , {(int int   newImgSize  = (0, 0) , bool centerPrincipalPoint  = false → (Mat Rect  
   
  
 
  GetOptimalNewCameraMatrixWithParams computes and returns the optimal new camera matrix based on the free scaling parameter.
  
 
          
  getOptimalNewCameraMatrixAsync (InputArray cameraMatrix , InputArray distCoeffs , (int int   imageSize , double alpha , {(int int   newImgSize  = (0, 0) , bool centerPrincipalPoint  = false → Future <(Mat Rect  >  
   
  
 
  GetOptimalNewCameraMatrixWithParams computes and returns the optimal new camera matrix based on the free scaling parameter.
  
 
          
  initUndistortRectifyMap (InputArray cameraMatrix , InputArray distCoeffs , InputArray R , InputArray newCameraMatrix , (int int   size , int m1type , {OutputArray ?map1 , OutputArray ?map2 → (Mat Mat  
   
  
 
  InitUndistortRectifyMap computes the joint undistortion and rectification transformation and represents the result in the form of maps for remap
  
 
          
  initUndistortRectifyMapAsync (InputArray cameraMatrix , InputArray distCoeffs , InputArray R , InputArray newCameraMatrix , (int int   size , int m1type , {OutputArray ?map1 , OutputArray ?map2 → Future <(Mat Mat  >  
   
  
 
  InitUndistortRectifyMap computes the joint undistortion and rectification transformation and represents the result in the form of maps for remap
  
 
          
  initWideAngleProjMap (InputArray cameraMatrix , InputArray distCoeffs , Size imageSize , int destImageWidth , int m1type , {OutputArray ?map1 , OutputArray ?map2 , int projType  = PROJ_SPHERICAL_EQRECT , double alpha  = 0 → (double Mat Mat  
   
  
 
  initializes maps for remap for wide-angle
  
 
          
  initWideAngleProjMapAsync (InputArray cameraMatrix , InputArray distCoeffs , Size imageSize , int destImageWidth , int m1type , {OutputArray ?map1 , OutputArray ?map2 , int projType  = PROJ_SPHERICAL_EQRECT , double alpha  = 0 → Future <(double Mat Mat  >  
   
  
 
  initializes maps for remap for wide-angle
  
 
          
  matMulDeriv (InputArray A , InputArray B , {OutputArray ?dABdA , OutputArray ?dABdB → (Mat Mat  
   
  
 
  Computes partial derivatives of the matrix product for each multiplied matrix.
  
 
          
  matMulDerivAsync (InputArray A , InputArray B , {OutputArray ?dABdA , OutputArray ?dABdB → Future <(Mat Mat  >  
   
  
 
  Computes partial derivatives of the matrix product for each multiplied matrix.
  
 
          
  projectPoints (InputArray objectPoints , InputArray rvec , InputArray tvec , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?imagePoints , OutputArray ?jacobian , double aspectRatio  = 0 → (Mat Mat  
   
  
 
  Projects 3D points to an image plane.
  
 
          
  projectPointsAsync (InputArray objectPoints , InputArray rvec , InputArray tvec , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?imagePoints , OutputArray ?jacobian , double aspectRatio  = 0 → Future <(Mat Mat  >  
   
  
 
  Projects 3D points to an image plane.
  
 
          
  recoverPose (InputArray E , InputArray points1 , InputArray points2 , {OutputArray ?R , OutputArray ?t , double focal  = 1 , Point2d ?pp , InputOutputArray ?mask → (int Mat Mat  
   
  
 
  Recovers the relative camera rotation and the translation from an estimated essential matrix and the corresponding points in two images, using chirality check. Returns the number of inliers that pass the check.
  
 
          
  recoverPoseAsync (InputArray E , InputArray points1 , InputArray points2 , {OutputArray ?R , OutputArray ?t , double focal  = 1 , Point2d ?pp , InputOutputArray ?mask → Future <(int Mat Mat  >  
   
  
 
  Recovers the relative camera rotation and the translation from an estimated essential matrix and the corresponding points in two images, using chirality check. Returns the number of inliers that pass the check.
  
 
          
  recoverPoseCameraMatrix (InputArray E , InputArray points1 , InputArray points2 , InputArray cameraMatrix , {OutputArray ?R , OutputArray ?t , double distanceThresh  = 1 , InputOutputArray ?mask , OutputArray ?triangulatedPoints → (int Mat Mat Mat  
   
  
 
  int cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, double distanceThresh, InputOutputArray mask=noArray(), OutputArray triangulatedPoints=noArray())
  
 
          
  recoverPoseCameraMatrixAsync (InputArray E , InputArray points1 , InputArray points2 , InputArray cameraMatrix , {OutputArray ?R , OutputArray ?t , double distanceThresh  = 1 , InputOutputArray ?mask , OutputArray ?triangulatedPoints → Future <(int Mat Mat Mat  >  
   
  
 
  int cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, double distanceThresh, InputOutputArray mask=noArray(), OutputArray triangulatedPoints=noArray())
  
 
          
  Rodrigues (InputArray src , {OutputArray ?dst , OutputArray ?jacobian → Mat  
   
  
 
  Converts a rotation matrix to a rotation vector or vice versa.
  
 
          
  RodriguesAsync (InputArray src , {OutputArray ?dst , OutputArray ?jacobian → Future <Mat   
   
  
 
  Converts a rotation matrix to a rotation vector or vice versa.
  
 
          
  RQDecomp3x3 (InputArray src , {OutputArray ?mtxR , OutputArray ?mtxQ , OutputArray ?Qx , OutputArray ?Qy , OutputArray ?Qz → (Vec3d Mat Mat  
   
  
 
  Computes an RQ decomposition of 3x3 matrices.
  
 
          
  RQDecomp3x3Async (InputArray src , {OutputArray ?mtxR , OutputArray ?mtxQ , OutputArray ?Qx , OutputArray ?Qy , OutputArray ?Qz → Future <(Vec3d Mat Mat  >  
   
  
 
  Computes an RQ decomposition of 3x3 matrices.
  
 
          
  sampsonDistance (InputArray pt1 , InputArray pt2 , InputArray F → double  
   
  
 
  Calculates the Sampson Distance between two points.
  
 
          
  solveP3P (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , int flags , {VecMat ?rvecs , VecMat ?tvecs → (int VecMat VecMat  
   
  
 
  Finds an object pose from 3 3D-2D point correspondences.
  
 
          
  solveP3PAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , int flags , {VecMat ?rvecs , VecMat ?tvecs → Future <(int VecMat VecMat  >  
   
  
 
  Finds an object pose from 3 3D-2D point correspondences.
  
 
          
  solvePnP (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , bool useExtrinsicGuess  = false , int flags  = SOLVEPNP_ITERATIVE → (bool Mat Mat  
   
  
 
  Finds an object pose from 3D-2D point correspondences.
  
 
          
  solvePnPAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , bool useExtrinsicGuess  = false , int flags  = SOLVEPNP_ITERATIVE → Future <(bool Mat Mat  >  
   
  
 
  Finds an object pose from 3D-2D point correspondences.
  
 
          
  solvePnPGeneric (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {VecMat ?rvecs , VecMat ?tvecs , bool useExtrinsicGuess  = false , int flags  = SOLVEPNP_ITERATIVE , InputArray ?rvec , InputArray ?tvec , OutputArray ?reprojectionError → (int VecMat VecMat Mat  
   
  
 
  Finds an object pose from 3D-2D point correspondences.
  
 
          
  solvePnPGenericAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {VecMat ?rvecs , VecMat ?tvecs , bool useExtrinsicGuess  = false , int flags  = SOLVEPNP_ITERATIVE , InputArray ?rvec , InputArray ?tvec , OutputArray ?reprojectionError → Future <(int VecMat VecMat Mat  >  
   
  
 
  Finds an object pose from 3D-2D point correspondences.
  
 
          
  solvePnPRansac (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , bool useExtrinsicGuess  = false , int iterationsCount  = 100 , double reprojectionError  = 8.0 , double confidence  = 0.99 , OutputArray ?inliers , int flags  = SOLVEPNP_ITERATIVE → (bool Mat Mat Mat  
   
  
 
  Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
  
 
          
  solvePnPRansacAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , bool useExtrinsicGuess  = false , int iterationsCount  = 100 , double reprojectionError  = 8.0 , double confidence  = 0.99 , OutputArray ?inliers , int flags  = SOLVEPNP_ITERATIVE → Future <(bool Mat Mat Mat  >  
   
  
 
  Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
  
 
          
  solvePnPRansacUsac (InputArray objectPoints , InputArray imagePoints , InputOutputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , OutputArray ?inliers , UsacParams ?params → (bool Mat Mat Mat  
   
  
 
  Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
  
 
          
  solvePnPRansacUsacAsync (InputArray objectPoints , InputArray imagePoints , InputOutputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?rvec , OutputArray ?tvec , OutputArray ?inliers , UsacParams ?params → Future <(bool Mat Mat Mat  >  
   
  
 
  Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
  
 
          
  solvePnPRefineLM (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , InputOutputArray rvec , InputOutputArray tvec , {TermCriteria ?criteria → void 
   
  
 
  Refine a pose (the translation and the rotation that transform a 3D point expressed in the
object coordinate frame to the camera coordinate frame) from a 3D-2D point correspondences and
starting from an initial solution.
  
 
          
  solvePnPRefineLMAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , InputOutputArray rvec , InputOutputArray tvec , {TermCriteria ?criteria → Future <void >  
   
  
 
  Refine a pose (the translation and the rotation that transform a 3D point expressed in the
object coordinate frame to the camera coordinate frame) from a 3D-2D point correspondences and
starting from an initial solution.
  
 
          
  solvePnPRefineVVS (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , InputOutputArray rvec , InputOutputArray tvec , {TermCriteria ?criteria , double VVSlambda  = 1.0 → void 
   
  
 
  Refine a pose (the translation and the rotation that transform a 3D point expressed in the
object coordinate frame to the camera coordinate frame) from a 3D-2D point correspondences and
starting from an initial solution.
  
 
          
  solvePnPRefineVVSAsync (InputArray objectPoints , InputArray imagePoints , InputArray cameraMatrix , InputArray distCoeffs , InputOutputArray rvec , InputOutputArray tvec , {TermCriteria ?criteria , double VVSlambda  = 1.0 → Future <void >  
   
  
 
  Refine a pose (the translation and the rotation that transform a 3D point expressed in the
object coordinate frame to the camera coordinate frame) from a 3D-2D point correspondences and
starting from an initial solution.
  
 
          
  triangulatePoints (InputArray projMatr1 , InputArray projMatr2 , InputArray projPoints1 , InputArray projPoints2 , {OutputArray ?points4D → Mat  
   
  
 
  This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observations with a stereo camera.
  
 
          
  triangulatePointsAsync (InputArray projMatr1 , InputArray projMatr2 , InputArray projPoints1 , InputArray projPoints2 , {OutputArray ?points4D → Future <Mat   
   
  
 
  This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observations with a stereo camera.
  
 
          
  undistort (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , InputArray ?newCameraMatrix → Mat  
   
  
 
  Transforms an image to compensate for lens distortion.
The function transforms an image to compensate radial and tangential lens distortion.
The function is simply a combination of initUndistortRectifyMap (with unity R ) and remap (with bilinear interpolation). See the former function for details of the transformation being performed.
Those pixels in the destination image, for which there is no correspondent pixels in the source image, are filled with zeros (black color).
A particular subset of the source image that will be visible in the corrected image can be regulated by newCameraMatrix. You can use getOptimalNewCameraMatrix to compute the appropriate newCameraMatrix depending on your requirements.
The camera matrix and the distortion parameters can be determined using calibrateCamera. If the resolution of images is different from the resolution used at the calibration stage, fx,fy,cx and cy need to be scaled accordingly, while the distortion coefficients remain the same.
  
 
          
  undistortAsync (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , InputArray ?newCameraMatrix → Future <Mat   
   
  
 
  Transforms an image to compensate for lens distortion.
The function transforms an image to compensate radial and tangential lens distortion.
The function is simply a combination of initUndistortRectifyMap (with unity R ) and remap (with bilinear interpolation). See the former function for details of the transformation being performed.
Those pixels in the destination image, for which there is no correspondent pixels in the source image, are filled with zeros (black color).
A particular subset of the source image that will be visible in the corrected image can be regulated by newCameraMatrix. You can use getOptimalNewCameraMatrix to compute the appropriate newCameraMatrix depending on your requirements.
The camera matrix and the distortion parameters can be determined using calibrateCamera. If the resolution of images is different from the resolution used at the calibration stage, fx,fy,cx and cy need to be scaled accordingly, while the distortion coefficients remain the same.
  
 
          
  undistortImagePoints (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , TermCriteria ?criteria → Mat  
   
  
 
  Compute undistorted image points position.
  
 
          
  undistortImagePointsAsync (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , TermCriteria ?criteria → Future <Mat   
   
  
 
  Compute undistorted image points position.
  
 
          
  undistortPoints (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , InputArray ?R , InputArray ?P , (int int double   criteria  = (TERM_COUNT + TERM_EPS, 30, 1e-4) → Mat  
   
  
 
  UndistortPoints transforms points to compensate for lens distortion
  
 
          
  undistortPointsAsync (InputArray src , InputArray cameraMatrix , InputArray distCoeffs , {OutputArray ?dst , InputArray ?R , InputArray ?P , (int int double   criteria  = (TERM_COUNT + TERM_EPS, 30, 1e-4) → Future <Mat   
   
  
 
  UndistortPoints transforms points to compensate for lens distortion