[][src]Module opencv::calib3d

Camera Calibration and 3D Reconstruction

The functions in this section use a so-called pinhole camera model. In this model, a scene view is formed by projecting 3D points into the image plane using a perspective transformation.

block formula

or

block formula

where:

  • inline formula are the coordinates of a 3D point in the world coordinate space
  • inline formula are the coordinates of the projection point in pixels
  • inline formula is a camera matrix, or a matrix of intrinsic parameters
  • inline formula is a principal point that is usually at the image center
  • inline formula are the focal lengths expressed in pixel units.

Thus, if an image from the camera is scaled by a factor, all of these parameters should be scaled (multiplied/divided, respectively) by the same factor. The matrix of intrinsic parameters does not depend on the scene viewed. So, once estimated, it can be re-used as long as the focal length is fixed (in case of zoom lens). The joint rotation-translation matrix inline formula is called a matrix of extrinsic parameters. It is used to describe the camera motion around a static scene, or vice versa, rigid motion of an object in front of a still camera. That is, inline formula translates coordinates of a point inline formula to a coordinate system, fixed with respect to the camera. The transformation above is equivalent to the following (when inline formula ):

block formula

The following figure illustrates the pinhole camera model.

Pinhole camera model

Real lenses usually have some distortion, mostly radial distortion and slight tangential distortion. So, the above model is extended as:

block formula

inline formula, inline formula, inline formula, inline formula, inline formula, and inline formula are radial distortion coefficients. inline formula and inline formula are tangential distortion coefficients. inline formula, inline formula, inline formula, and inline formula, are the thin prism distortion coefficients. Higher-order coefficients are not considered in OpenCV.

The next figures show two common types of radial distortion: barrel distortion (typically inline formula) and pincushion distortion (typically inline formula).

In some cases the image sensor may be tilted in order to focus an oblique plane in front of the camera (Scheimpfug condition). This can be useful for particle image velocimetry (PIV) or triangulation with a laser fan. The tilt causes a perspective distortion of inline formula and inline formula. This distortion can be modelled in the following way, see e.g. Louhichi07.

block formula

where the matrix inline formula is defined by two rotations with angular parameter inline formula and inline formula, respectively,

block formula

In the functions below the coefficients are passed or returned as

block formula

vector. That is, if the vector contains four elements, it means that inline formula . The distortion coefficients do not depend on the scene viewed. Thus, they also belong to the intrinsic camera parameters. And they remain the same regardless of the captured image resolution. If, for example, a camera has been calibrated on images of 320 x 240 resolution, absolutely the same distortion coefficients can be used for 640 x 480 images from the same camera while inline formula, inline formula, inline formula, and inline formula need to be scaled appropriately.

The functions below use the above model to do the following:

  • Project 3D points to the image plane given intrinsic and extrinsic parameters.
  • Compute extrinsic parameters given intrinsic parameters, a few 3D points, and their projections.
  • Estimate intrinsic and extrinsic camera parameters from several views of a known calibration pattern (every view is described by several 3D-2D point correspondences).
  • Estimate the relative position and orientation of the stereo camera "heads" and compute the rectification transformation that makes the camera optical axes parallel.

Note:

  • A calibration sample for 3 cameras in horizontal position can be found at opencv_source_code/samples/cpp/3calibration.cpp
  • A calibration sample based on a sequence of images can be found at opencv_source_code/samples/cpp/calibration.cpp
  • A calibration sample in order to do 3D reconstruction can be found at opencv_source_code/samples/cpp/build3dmodel.cpp
  • A calibration example on stereo calibration can be found at opencv_source_code/samples/cpp/stereo_calib.cpp
  • A calibration example on stereo matching can be found at opencv_source_code/samples/cpp/stereo_match.cpp
  • (Python) A camera calibration sample can be found at opencv_source_code/samples/python/calibrate.py

Fisheye camera model

Definitions: Let P be a point in 3D of coordinates X in the world reference frame (stored in the matrix X) The coordinate vector of P in the camera reference frame is:

block formula

where R is the rotation matrix corresponding to the rotation vector om: R = rodrigues(om); call x, y and z the 3 coordinates of Xc:

block formula

The pinhole projection coordinates of P is [a; b] where

block formula

Fisheye distortion:

block formula

The distorted point coordinates are [x'; y'] where

block formula

Finally, conversion into pixel coordinates: The final pixel coordinates vector [u; v] where:

block formula

C API

Structs

CirclesGridFinderParameters

Enums

HandEyeCalibrationMethod
SolvePnPMethod

Constants

CALIB_CB_ADAPTIVE_THRESH
CALIB_CB_ASYMMETRIC_GRID
CALIB_CB_CLUSTERING
CALIB_CB_FAST_CHECK
CALIB_CB_FILTER_QUADS
CALIB_CB_NORMALIZE_IMAGE
CALIB_CB_SYMMETRIC_GRID
CALIB_CHECK_COND
CALIB_FIX_ASPECT_RATIO
CALIB_FIX_FOCAL_LENGTH
CALIB_FIX_INTRINSIC
CALIB_FIX_K1
CALIB_FIX_K2
CALIB_FIX_K3
CALIB_FIX_K4
CALIB_FIX_K5
CALIB_FIX_K6
CALIB_FIX_PRINCIPAL_POINT
CALIB_FIX_S1_S2_S3_S4
CALIB_FIX_SKEW
CALIB_FIX_TANGENT_DIST
CALIB_FIX_TAUX_TAUY
CALIB_HAND_EYE_ANDREFF

On-line Hand-Eye Calibration Andreff99

CALIB_HAND_EYE_DANIILIDIS

Hand-Eye Calibration Using Dual Quaternions Daniilidis98

CALIB_HAND_EYE_HORAUD

Hand-eye Calibration Horaud95

CALIB_HAND_EYE_PARK

Robot Sensor Calibration: Solving AX = XB on the Euclidean Group Park94

CALIB_HAND_EYE_TSAI

A New Technique for Fully Autonomous and Efficient 3D Robotics Hand/Eye Calibration Tsai89

CALIB_RATIONAL_MODEL
CALIB_RECOMPUTE_EXTRINSIC
CALIB_SAME_FOCAL_LENGTH
CALIB_THIN_PRISM_MODEL
CALIB_TILTED_MODEL
CALIB_USE_EXTRINSIC_GUESS

for stereoCalibrate

CALIB_USE_INTRINSIC_GUESS
CALIB_USE_LU

use LU instead of SVD decomposition for solving. much faster but potentially less precise

CALIB_USE_QR

use QR instead of SVD decomposition for solving. Faster but potentially less precise

CALIB_ZERO_DISPARITY
CALIB_ZERO_TANGENT_DIST
CirclesGridFinderParameters_ASYMMETRIC_GRID
CirclesGridFinderParameters_SYMMETRIC_GRID
FM_7POINT

7-point algorithm

FM_8POINT

8-point algorithm

FM_LMEDS

least-median algorithm. 7-point algorithm is used.

FM_RANSAC

RANSAC algorithm. It needs at least 15 points. 7-point algorithm is used.

LMEDS

least-median of squares algorithm

RANSAC

RANSAC algorithm

RHO

RHO algorithm

SOLVEPNP_AP3P

An Efficient Algebraic Solution to the Perspective-Three-Point Problem Ke17

SOLVEPNP_DLS

A Direct Least-Squares (DLS) Method for PnP hesch2011direct

SOLVEPNP_EPNP

EPnP: Efficient Perspective-n-Point Camera Pose Estimation lepetit2009epnp

SOLVEPNP_IPPE

Infinitesimal Plane-Based Pose Estimation Collins14

SOLVEPNP_IPPE_SQUARE

Infinitesimal Plane-Based Pose Estimation Collins14

SOLVEPNP_ITERATIVE
SOLVEPNP_MAX_COUNT

Used for count

SOLVEPNP_P3P

Complete Solution Classification for the Perspective-Three-Point Problem gao2003complete

SOLVEPNP_UPNP

Exhaustive Linearization for Robust Camera Pose and Focal Length Estimation penate2013exhaustive

StereoBM_PREFILTER_NORMALIZED_RESPONSE
StereoBM_PREFILTER_XSOBEL
StereoMatcher_DISP_SCALE
StereoMatcher_DISP_SHIFT
StereoSGBM_MODE_HH
StereoSGBM_MODE_HH4
StereoSGBM_MODE_SGBM
StereoSGBM_MODE_SGBM_3WAY

Traits

StereoBM

Class for computing stereo correspondence using the block matching algorithm, introduced and contributed to OpenCV by K. Konolige.

StereoMatcher

The base class for stereo correspondence algorithms.

StereoSGBM

The class implements the modified H. Hirschmuller algorithm HH08 that differs from the original one as follows:

Functions

calibrate

Performs camera calibaration

calibrate_camera

Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.

calibrate_camera_with_stddev

Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.

calibrate_hand_eye

Computes Hand-Eye calibration:

inline formula

calibration_matrix_values

Computes useful camera characteristics from the camera matrix.

compose_rt

Combines two rotation-and-shift transformations.

compute_correspond_epilines

For points in an image of a stereo pair, computes the corresponding epilines in the other image.

convert_points_from_homogeneous

Converts points from homogeneous to Euclidean space.

convert_points_homogeneous

Converts points to/from homogeneous coordinates.

convert_points_to_homogeneous

Converts points from Euclidean to homogeneous space.

correct_matches

Refines coordinates of corresponding points.

decompose_essential_mat

Decompose an essential matrix to possible rotations and translation.

decompose_homography_mat

Decompose a homography matrix to rotation(s), translation(s) and plane normal(s).

decompose_projection_matrix

Decomposes a projection matrix into a rotation matrix and a camera matrix.

distort_points

Distorts 2D points using fisheye model.

draw_chessboard_corners

Renders the detected chessboard corners.

draw_frame_axes

Draw axes of the world/object coordinate system from pose estimation. ## See also solvePnP

estimate_affine_2d

Computes an optimal affine transformation between two 2D point sets.

estimate_affine_3d

Computes an optimal affine transformation between two 3D point sets.

estimate_affine_partial_2d

Computes an optimal limited affine transformation with 4 degrees of freedom between two 2D point sets.

estimate_new_camera_matrix_for_undistort_rectify

Estimates new camera matrix for undistortion or rectification.

filter_homography_decomp_by_visible_refpoints

Filters homography decompositions based on additional information.

filter_speckles

Filters off small noise blobs (speckles) in the disparity map

find4_quad_corner_subpix

finds subpixel-accurate positions of the chessboard corners

find_chessboard_corners

Finds the positions of internal corners of the chessboard.

find_circles_grid

Finds centers in the grid of circles.

find_circles_grid_params

Finds centers in the grid of circles.

find_essential_mat

Calculates an essential matrix from the corresponding points in two images.

find_essential_mat_matrix

Calculates an essential matrix from the corresponding points in two images.

find_fundamental_mat

Calculates a fundamental matrix from the corresponding points in two images.

find_homography

Finds a perspective transformation between two planes.

find_homography_ext

Finds a perspective transformation between two planes.

fisheye_init_undistort_rectify_map

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.

fisheye_project_points

Projects points using fisheye model

fisheye_stereo_calibrate

Performs stereo calibration

fisheye_stereo_rectify

Stereo rectification for fisheye camera model

fisheye_undistort_image

Transforms an image to compensate for fisheye lens distortion.

fisheye_undistort_points

Undistorts 2D points using fisheye model

get_optimal_new_camera_matrix

Returns the new camera matrix based on the free scaling parameter.

get_valid_disparity_roi

computes valid disparity ROI from the valid ROIs of the rectified images (that are returned by cv::stereoRectify())

init_camera_matrix_2d

Finds an initial camera matrix from 3D-2D point correspondences.

mat_mul_deriv

Computes partial derivatives of the matrix product for each multiplied matrix.

project_points

Projects 3D points to an image plane.

recover_pose

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.

recover_pose_camera

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.

recover_pose_camera_with_points

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.

rectify3_collinear

computes the rectification transformations for 3-head camera, where all the heads are on the same line.

reproject_image_to_3d

Reprojects a disparity image to 3D space.

rodrigues

Converts a rotation matrix to a rotation vector or vice versa.

rq_decomp3x3

Computes an RQ decomposition of 3x3 matrices.

sampson_distance

Calculates the Sampson Distance between two points.

solve_p3p

Finds an object pose from 3 3D-2D point correspondences.

solve_pnp

Finds an object pose from 3D-2D point correspondences. This function returns the rotation and the translation vectors that transform a 3D point expressed in the object coordinate frame to the camera coordinate frame, using different methods:

solve_pnp_generic

Finds an object pose from 3D-2D point correspondences. This function returns a list of all the possible solutions (a solution is a <rotation vector, translation vector> couple), depending on the number of input points and the chosen method:

solve_pnp_ransac

Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.

solve_pnp_refine_lm

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.

solve_pnp_refine_vvs

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.

stereo_calibrate_camera

C++ default parameters

stereo_calibrate_camera_with_errors

Calibrates the stereo camera.

stereo_rectify_camera

Computes rectification transforms for each head of a calibrated stereo camera.

stereo_rectify_uncalibrated

Computes a rectification transform for an uncalibrated stereo camera.

triangulate_points

Reconstructs points by triangulation.

validate_disparity

validates disparity using the left-right check. The matrix "cost" should be computed by the stereo correspondence algorithm