|  | 
| double | cv::fisheye::calibrate (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, const Size &image_size, InputOutputArray K, InputOutputArray D, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 100, DBL_EPSILON)) | 
|  | Performs camera calibaration.  More... 
 | 
|  | 
| double | cv::calibrateCamera (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, OutputArray stdDeviationsIntrinsics, OutputArray stdDeviationsExtrinsics, OutputArray perViewErrors, int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, DBL_EPSILON)) | 
|  | Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.  More... 
 | 
|  | 
| double | cv::calibrateCamera (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, Size imageSize, InputOutputArray cameraMatrix, InputOutputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags=0, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, DBL_EPSILON)) | 
|  | 
| void | cv::calibrateHandEye (InputArrayOfArrays R_gripper2base, InputArrayOfArrays t_gripper2base, InputArrayOfArrays R_target2cam, InputArrayOfArrays t_target2cam, OutputArray R_cam2gripper, OutputArray t_cam2gripper, HandEyeCalibrationMethod method=CALIB_HAND_EYE_TSAI) | 
|  | Computes Hand-Eye calibration: \(_{}^{g}\textrm{T}_c\).  More... 
 | 
|  | 
| void | cv::calibrationMatrixValues (InputArray cameraMatrix, Size imageSize, double apertureWidth, double apertureHeight, double &fovx, double &fovy, double &focalLength, Point2d &principalPoint, double &aspectRatio) | 
|  | Computes useful camera characteristics from the camera matrix.  More... 
 | 
|  | 
| void | cv::composeRT (InputArray rvec1, InputArray tvec1, InputArray rvec2, InputArray tvec2, OutputArray rvec3, OutputArray tvec3, OutputArray dr3dr1=noArray(), OutputArray dr3dt1=noArray(), OutputArray dr3dr2=noArray(), OutputArray dr3dt2=noArray(), OutputArray dt3dr1=noArray(), OutputArray dt3dt1=noArray(), OutputArray dt3dr2=noArray(), OutputArray dt3dt2=noArray()) | 
|  | Combines two rotation-and-shift transformations.  More... 
 | 
|  | 
| void | cv::computeCorrespondEpilines (InputArray points, int whichImage, InputArray F, OutputArray lines) | 
|  | For points in an image of a stereo pair, computes the corresponding epilines in the other image.  More... 
 | 
|  | 
| void | cv::convertPointsFromHomogeneous (InputArray src, OutputArray dst) | 
|  | Converts points from homogeneous to Euclidean space.  More... 
 | 
|  | 
| void | cv::convertPointsHomogeneous (InputArray src, OutputArray dst) | 
|  | Converts points to/from homogeneous coordinates.  More... 
 | 
|  | 
| void | cv::convertPointsToHomogeneous (InputArray src, OutputArray dst) | 
|  | Converts points from Euclidean to homogeneous space.  More... 
 | 
|  | 
| void | cv::correctMatches (InputArray F, InputArray points1, InputArray points2, OutputArray newPoints1, OutputArray newPoints2) | 
|  | Refines coordinates of corresponding points.  More... 
 | 
|  | 
| void | cv::decomposeEssentialMat (InputArray E, OutputArray R1, OutputArray R2, OutputArray t) | 
|  | Decompose an essential matrix to possible rotations and translation.  More... 
 | 
|  | 
| int | cv::decomposeHomographyMat (InputArray H, InputArray K, OutputArrayOfArrays rotations, OutputArrayOfArrays translations, OutputArrayOfArrays normals) | 
|  | Decompose a homography matrix to rotation(s), translation(s) and plane normal(s).  More... 
 | 
|  | 
| void | cv::decomposeProjectionMatrix (InputArray projMatrix, OutputArray cameraMatrix, OutputArray rotMatrix, OutputArray transVect, OutputArray rotMatrixX=noArray(), OutputArray rotMatrixY=noArray(), OutputArray rotMatrixZ=noArray(), OutputArray eulerAngles=noArray()) | 
|  | Decomposes a projection matrix into a rotation matrix and a camera matrix.  More... 
 | 
|  | 
| void | cv::fisheye::distortPoints (InputArray undistorted, OutputArray distorted, InputArray K, InputArray D, double alpha=0) | 
|  | Distorts 2D points using fisheye model.  More... 
 | 
|  | 
| void | cv::drawChessboardCorners (InputOutputArray image, Size patternSize, InputArray corners, bool patternWasFound) | 
|  | Renders the detected chessboard corners.  More... 
 | 
|  | 
| void | cv::drawFrameAxes (InputOutputArray image, InputArray cameraMatrix, InputArray distCoeffs, InputArray rvec, InputArray tvec, float length, int thickness=3) | 
|  | Draw axes of the world/object coordinate system from pose estimation.  More... 
 | 
|  | 
| cv::Mat | cv::estimateAffine2D (InputArray from, InputArray to, OutputArray inliers=noArray(), int method=RANSAC, double ransacReprojThreshold=3, size_t maxIters=2000, double confidence=0.99, size_t refineIters=10) | 
|  | Computes an optimal affine transformation between two 2D point sets.  More... 
 | 
|  | 
| int | cv::estimateAffine3D (InputArray src, InputArray dst, OutputArray out, OutputArray inliers, double ransacThreshold=3, double confidence=0.99) | 
|  | Computes an optimal affine transformation between two 3D point sets.  More... 
 | 
|  | 
| cv::Mat | cv::estimateAffinePartial2D (InputArray from, InputArray to, OutputArray inliers=noArray(), int method=RANSAC, double ransacReprojThreshold=3, size_t maxIters=2000, double confidence=0.99, size_t refineIters=10) | 
|  | Computes an optimal limited affine transformation with 4 degrees of freedom between two 2D point sets.  More... 
 | 
|  | 
| void | cv::fisheye::estimateNewCameraMatrixForUndistortRectify (InputArray K, InputArray D, const Size &image_size, InputArray R, OutputArray P, double balance=0.0, const Size &new_size=Size(), double fov_scale=1.0) | 
|  | Estimates new camera matrix for undistortion or rectification.  More... 
 | 
|  | 
| void | cv::filterHomographyDecompByVisibleRefpoints (InputArrayOfArrays rotations, InputArrayOfArrays normals, InputArray beforePoints, InputArray afterPoints, OutputArray possibleSolutions, InputArray pointsMask=noArray()) | 
|  | Filters homography decompositions based on additional information.  More... 
 | 
|  | 
| void | cv::filterSpeckles (InputOutputArray img, double newVal, int maxSpeckleSize, double maxDiff, InputOutputArray buf=noArray()) | 
|  | Filters off small noise blobs (speckles) in the disparity map.  More... 
 | 
|  | 
| bool | cv::find4QuadCornerSubpix (InputArray img, InputOutputArray corners, Size region_size) | 
|  | finds subpixel-accurate positions of the chessboard corners  More... 
 | 
|  | 
| bool | cv::findChessboardCorners (InputArray image, Size patternSize, OutputArray corners, int flags=CALIB_CB_ADAPTIVE_THRESH+CALIB_CB_NORMALIZE_IMAGE) | 
|  | Finds the positions of internal corners of the chessboard.  More... 
 | 
|  | 
| bool | cv::findCirclesGrid (InputArray image, Size patternSize, OutputArray centers, int flags, const Ptr< FeatureDetector > &blobDetector, CirclesGridFinderParameters parameters) | 
|  | Finds centers in the grid of circles.  More... 
 | 
|  | 
| bool | cv::findCirclesGrid (InputArray image, Size patternSize, OutputArray centers, int flags=CALIB_CB_SYMMETRIC_GRID, const Ptr< FeatureDetector > &blobDetector=SimpleBlobDetector::create()) | 
|  | 
| bool | cv::findCirclesGrid2 (InputArray image, Size patternSize, OutputArray centers, int flags, const Ptr< FeatureDetector > &blobDetector, CirclesGridFinderParameters2 parameters) | 
|  | 
| Mat | cv::findEssentialMat (InputArray points1, InputArray points2, InputArray cameraMatrix, int method=RANSAC, double prob=0.999, double threshold=1.0, OutputArray mask=noArray()) | 
|  | Calculates an essential matrix from the corresponding points in two images.  More... 
 | 
|  | 
| Mat | cv::findEssentialMat (InputArray points1, InputArray points2, double focal=1.0, Point2d pp=Point2d(0, 0), int method=RANSAC, double prob=0.999, double threshold=1.0, OutputArray mask=noArray()) | 
|  | 
| Mat | cv::findFundamentalMat (InputArray points1, InputArray points2, int method=FM_RANSAC, double ransacReprojThreshold=3., double confidence=0.99, OutputArray mask=noArray()) | 
|  | Calculates a fundamental matrix from the corresponding points in two images.  More... 
 | 
|  | 
| Mat | cv::findFundamentalMat (InputArray points1, InputArray points2, OutputArray mask, int method=FM_RANSAC, double ransacReprojThreshold=3., double confidence=0.99) | 
|  | 
| Mat | cv::findHomography (InputArray srcPoints, InputArray dstPoints, int method=0, double ransacReprojThreshold=3, OutputArray mask=noArray(), const int maxIters=2000, const double confidence=0.995) | 
|  | Finds a perspective transformation between two planes.  More... 
 | 
|  | 
| Mat | cv::findHomography (InputArray srcPoints, InputArray dstPoints, OutputArray mask, int method=0, double ransacReprojThreshold=3) | 
|  | 
| Mat | cv::getOptimalNewCameraMatrix (InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, double alpha, Size newImgSize=Size(), Rect *validPixROI=0, bool centerPrincipalPoint=false) | 
|  | Returns the new camera matrix based on the free scaling parameter.  More... 
 | 
|  | 
| Rect | cv::getValidDisparityROI (Rect roi1, Rect roi2, int minDisparity, int numberOfDisparities, int SADWindowSize) | 
|  | computes valid disparity ROI from the valid ROIs of the rectified images (that are returned by cv::stereoRectify())  More... 
 | 
|  | 
| Mat | cv::initCameraMatrix2D (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints, Size imageSize, double aspectRatio=1.0) | 
|  | Finds an initial camera matrix from 3D-2D point correspondences.  More... 
 | 
|  | 
| void | cv::fisheye::initUndistortRectifyMap (InputArray K, InputArray D, InputArray R, InputArray P, const cv::Size &size, int m1type, OutputArray map1, OutputArray map2) | 
|  | Computes undistortion and rectification maps for image transform by cv::remap(). If D is empty zero distortion is used, if R or P is empty identity matrixes are used.  More... 
 | 
|  | 
| void | cv::matMulDeriv (InputArray A, InputArray B, OutputArray dABdA, OutputArray dABdB) | 
|  | Computes partial derivatives of the matrix product for each multiplied matrix.  More... 
 | 
|  | 
| void | cv::projectPoints (InputArray objectPoints, InputArray rvec, InputArray tvec, InputArray cameraMatrix, InputArray distCoeffs, OutputArray imagePoints, OutputArray jacobian=noArray(), double aspectRatio=0) | 
|  | Projects 3D points to an image plane.  More... 
 | 
|  | 
| void | cv::fisheye::projectPoints (InputArray objectPoints, OutputArray imagePoints, const Affine3d &affine, InputArray K, InputArray D, double alpha=0, OutputArray jacobian=noArray()) | 
|  | Projects points using fisheye model.  More... 
 | 
|  | 
| void | cv::fisheye::projectPoints (InputArray objectPoints, OutputArray imagePoints, InputArray rvec, InputArray tvec, InputArray K, InputArray D, double alpha=0, OutputArray jacobian=noArray()) | 
|  | 
| int | cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, InputOutputArray mask=noArray()) | 
|  | Recover relative camera rotation and translation from an estimated essential matrix and the corresponding points in two images, using cheirality check. Returns the number of inliers which pass the check.  More... 
 | 
|  | 
| int | cv::recoverPose (InputArray E, InputArray points1, InputArray points2, OutputArray R, OutputArray t, double focal=1.0, Point2d pp=Point2d(0, 0), InputOutputArray mask=noArray()) | 
|  | 
| int | cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, double distanceThresh, InputOutputArray mask=noArray(), OutputArray triangulatedPoints=noArray()) | 
|  | 
| float | cv::rectify3Collinear (InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, InputArray cameraMatrix3, InputArray distCoeffs3, InputArrayOfArrays imgpt1, InputArrayOfArrays imgpt3, Size imageSize, InputArray R12, InputArray T12, InputArray R13, InputArray T13, OutputArray R1, OutputArray R2, OutputArray R3, OutputArray P1, OutputArray P2, OutputArray P3, OutputArray Q, double alpha, Size newImgSize, Rect *roi1, Rect *roi2, int flags) | 
|  | computes the rectification transformations for 3-head camera, where all the heads are on the same line.  More... 
 | 
|  | 
| void | cv::reprojectImageTo3D (InputArray disparity, OutputArray _3dImage, InputArray Q, bool handleMissingValues=false, int ddepth=-1) | 
|  | Reprojects a disparity image to 3D space.  More... 
 | 
|  | 
| void | cv::Rodrigues (InputArray src, OutputArray dst, OutputArray jacobian=noArray()) | 
|  | Converts a rotation matrix to a rotation vector or vice versa.  More... 
 | 
|  | 
| Vec3d | cv::RQDecomp3x3 (InputArray src, OutputArray mtxR, OutputArray mtxQ, OutputArray Qx=noArray(), OutputArray Qy=noArray(), OutputArray Qz=noArray()) | 
|  | Computes an RQ decomposition of 3x3 matrices.  More... 
 | 
|  | 
| double | cv::sampsonDistance (InputArray pt1, InputArray pt2, InputArray F) | 
|  | Calculates the Sampson Distance between two points.  More... 
 | 
|  | 
| int | cv::solveP3P (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, int flags) | 
|  | Finds an object pose from 3 3D-2D point correspondences.  More... 
 | 
|  | 
| bool | cv::solvePnP (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int flags=SOLVEPNP_ITERATIVE) | 
|  | Finds an object pose from 3D-2D point correspondences.  More... 
 | 
|  | 
| bool | cv::solvePnPRansac (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, bool useExtrinsicGuess=false, int iterationsCount=100, float reprojectionError=8.0, double confidence=0.99, OutputArray inliers=noArray(), int flags=SOLVEPNP_ITERATIVE) | 
|  | Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.  More... 
 | 
|  | 
| double | cv::stereoCalibrate (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2, InputOutputArray cameraMatrix1, InputOutputArray distCoeffs1, InputOutputArray cameraMatrix2, InputOutputArray distCoeffs2, Size imageSize, InputOutputArray R, InputOutputArray T, OutputArray E, OutputArray F, OutputArray perViewErrors, int flags=CALIB_FIX_INTRINSIC, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, 1e-6)) | 
|  | Calibrates the stereo camera.  More... 
 | 
|  | 
| double | cv::stereoCalibrate (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2, InputOutputArray cameraMatrix1, InputOutputArray distCoeffs1, InputOutputArray cameraMatrix2, InputOutputArray distCoeffs2, Size imageSize, OutputArray R, OutputArray T, OutputArray E, OutputArray F, int flags=CALIB_FIX_INTRINSIC, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 30, 1e-6)) | 
|  | 
| double | cv::fisheye::stereoCalibrate (InputArrayOfArrays objectPoints, InputArrayOfArrays imagePoints1, InputArrayOfArrays imagePoints2, InputOutputArray K1, InputOutputArray D1, InputOutputArray K2, InputOutputArray D2, Size imageSize, OutputArray R, OutputArray T, int flags=fisheye::CALIB_FIX_INTRINSIC, TermCriteria criteria=TermCriteria(TermCriteria::COUNT+TermCriteria::EPS, 100, DBL_EPSILON)) | 
|  | Performs stereo calibration.  More... 
 | 
|  | 
| void | cv::stereoRectify (InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, Size imageSize, InputArray R, InputArray T, OutputArray R1, OutputArray R2, OutputArray P1, OutputArray P2, OutputArray Q, int flags=CALIB_ZERO_DISPARITY, double alpha=-1, Size newImageSize=Size(), Rect *validPixROI1=0, Rect *validPixROI2=0) | 
|  | Computes rectification transforms for each head of a calibrated stereo camera.  More... 
 | 
|  | 
| void | cv::fisheye::stereoRectify (InputArray K1, InputArray D1, InputArray K2, InputArray D2, const Size &imageSize, InputArray R, InputArray tvec, OutputArray R1, OutputArray R2, OutputArray P1, OutputArray P2, OutputArray Q, int flags, const Size &newImageSize=Size(), double balance=0.0, double fov_scale=1.0) | 
|  | Stereo rectification for fisheye camera model.  More... 
 | 
|  | 
| bool | cv::stereoRectifyUncalibrated (InputArray points1, InputArray points2, InputArray F, Size imgSize, OutputArray H1, OutputArray H2, double threshold=5) | 
|  | Computes a rectification transform for an uncalibrated stereo camera.  More... 
 | 
|  | 
| void | cv::triangulatePoints (InputArray projMatr1, InputArray projMatr2, InputArray projPoints1, InputArray projPoints2, OutputArray points4D) | 
|  | Reconstructs points by triangulation.  More... 
 | 
|  | 
| void | cv::fisheye::undistortImage (InputArray distorted, OutputArray undistorted, InputArray K, InputArray D, InputArray Knew=cv::noArray(), const Size &new_size=Size()) | 
|  | Transforms an image to compensate for fisheye lens distortion.  More... 
 | 
|  | 
| void | cv::fisheye::undistortPoints (InputArray distorted, OutputArray undistorted, InputArray K, InputArray D, InputArray R=noArray(), InputArray P=noArray()) | 
|  | Undistorts 2D points using fisheye model.  More... 
 | 
|  | 
| void | cv::validateDisparity (InputOutputArray disparity, InputArray cost, int minDisparity, int numberOfDisparities, int disp12MaxDisp=1) | 
|  | validates disparity using the left-right check. The matrix "cost" should be computed by the stereo correspondence algorithm  More... 
 | 
|  |