Expand description
§Camera Calibration and 3D Reconstruction
The functions in this section use a so-called pinhole camera model. The view of a scene
is obtained by projecting a scene’s 3D point into the image plane using a perspective
transformation which forms the corresponding pixel
. Both
and
are
represented in homogeneous coordinates, i.e. as 3D and 2D homogeneous vector respectively. You will
find a brief introduction to projective geometry, homogeneous vectors and homogeneous
transformations at the end of this section’s introduction. For more succinct notation, we often drop
the ‘homogeneous’ and say vector instead of homogeneous vector.
The distortion-free projective transformation given by a pinhole camera model is shown below.
where is a 3D point expressed with respect to the world coordinate system,
is a 2D pixel in the image plane,
is the camera intrinsic matrix,
and
are the rotation and translation that describe the change of coordinates from
world to camera coordinate systems (or camera frame) and
is the projective transformation’s
arbitrary scaling and not part of the camera model.
The camera intrinsic matrix (notation used as in Zhang2000 and also generally notated
as
) projects 3D points given in the camera coordinate system to 2D pixel coordinates, i.e.
The camera intrinsic matrix is composed of the focal lengths
and
, which are
expressed in pixel units, and the principal point
, that is usually close to the
image center:
and thus
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 a zoom lens). Thus, if an image from the camera is scaled by a factor, all of these parameters need to be scaled (multiplied/divided, respectively) by the same factor.
The joint rotation-translation matrix is the matrix product of a projective
transformation and a homogeneous transformation. The 3-by-4 projective transformation maps 3D points
represented in camera coordinates to 2D points in the image plane and represented in normalized
camera coordinates
and
:
The homogeneous transformation is encoded by the extrinsic parameters and
and
represents the change of basis from world coordinate system
to the camera coordinate sytem
. Thus, given the representation of the point
in world coordinates,
, we
obtain
’s representation in the camera coordinate system,
, by
This homogeneous transformation is composed out of , a 3-by-3 rotation matrix, and
, a
3-by-1 translation vector:
and therefore
Combining the projective transformation and the homogeneous transformation, we obtain the projective transformation that maps 3D points in world coordinates into 2D points in the image plane and in normalized camera coordinates:
with and
. Putting the equations for instrincs and extrinsics together, we can write out
as
If , the transformation above is equivalent to the following,
with
The following figure illustrates the pinhole camera model.
Real lenses usually have some distortion, mostly radial distortion, and slight tangential distortion. So, the above model is extended as:
where
with
and
if .
The distortion parameters are the radial coefficients ,
,
,
,
, and
,
and
are the tangential distortion coefficients, and
,
,
, and
,
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
( monotonically decreasing)
and pincushion distortion (
monotonically increasing).
Radial distortion is always monotonic for real lenses,
and if the estimator produces a non-monotonic result,
this should be considered a calibration failure.
More generally, radial distortion must be monotonic and the distortion function must be bijective.
A failed estimation result may look deceptively good near the image center
but will work poorly in e.g. AR/SFM applications.
The optimization method used in OpenCV camera calibration does not include these constraints as
the framework does not support the required integer programming and polynomial inequalities.
See issue #15992 for additional information.
In some cases, the image sensor may be tilted in order to focus an oblique plane in front of the
camera (Scheimpflug principle). This can be useful for particle image velocimetry (PIV) or
triangulation with a laser fan. The tilt causes a perspective distortion of and
. This distortion can be modeled in the following way, see e.g. Louhichi07.
where
and the matrix is defined by two rotations with angular parameter
and
, respectively,
In the functions below the coefficients are passed or returned as
vector. That is, if the vector contains four elements, it means that . 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
,
,
, and
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.
Homogeneous Coordinates
Homogeneous Coordinates are a system of coordinates that are used in projective geometry. Their use
allows to represent points at infinity by finite coordinates and simplifies formulas when compared
to the cartesian counterparts, e.g. they have the advantage that affine transformations can be
expressed as linear homogeneous transformation.
One obtains the homogeneous vector by appending a 1 along an n-dimensional cartesian
vector
e.g. for a 3D cartesian vector the mapping
is:
For the inverse mapping , one divides all elements of the homogeneous vector
by its last element, e.g. for a 3D homogeneous vector one gets its 2D cartesian counterpart by:
if .
Due to this mapping, all multiples , for
, of a homogeneous point represent
the same point
. An intuitive understanding of this property is that under a projective
transformation, all multiples of
are mapped to the same point. This is the physical
observation one does for pinhole cameras, as all points along a ray through the camera’s pinhole are
projected to the same image point, e.g. all points along the red ray in the image of the pinhole
camera model above would be mapped to the same image coordinate. This property is also the source
for the scale ambiguity s in the equation of the pinhole camera model.
As mentioned, by using homogeneous coordinates we can express any change of basis parameterized by
and
as a linear transformation, e.g. for the change of basis from coordinate system
0 to coordinate system 1 becomes:
Note:
- Many functions in this module take a camera intrinsic matrix as an input parameter. Although all functions assume the same structure of this parameter, they may name it differently. The parameter’s description, however, will be clear in that a camera intrinsic matrix with the structure shown above is required.
- A calibration sample for 3 cameras in a 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:
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:
The pinhole projection coordinates of P is [a; b] where
Fisheye distortion:
The distorted point coordinates are [x’; y’] where
Finally, conversion into pixel coordinates: The final pixel coordinates vector [u; v] where:
Summary: Generic camera model Kannala2006 with perspective projection and without distortion correction
Modules§
Structs§
- Circles
Grid Finder Parameters - LMSolver
- Levenberg-Marquardt solver. Starting with the specified vector of parameters it optimizes the target vector criteria “err” (finds local minima of each target vector component absolute value).
- LMSolver_
Callback - StereoBM
- Class for computing stereo correspondence using the block matching algorithm, introduced and contributed to OpenCV by K. Konolige.
- Stereo
Matcher - 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:
- Usac
Params
Enums§
- Circles
Grid Finder Parameters_ Grid Type - Hand
EyeCalibration Method - Local
Optim Method - Neighbor
Search Method - Polishing
Method - Robot
World Hand EyeCalibration Method - Sampling
Method - Score
Method - Solve
PnPMethod - Undistort
Types - cv::undistort mode
Constants§
- CALIB_
CB_ ACCURACY - CALIB_
CB_ ADAPTIVE_ THRESH - CALIB_
CB_ ASYMMETRIC_ GRID - CALIB_
CB_ CLUSTERING - CALIB_
CB_ EXHAUSTIVE - CALIB_
CB_ FAST_ CHECK - CALIB_
CB_ FILTER_ QUADS - CALIB_
CB_ LARGER - CALIB_
CB_ MARKER - CALIB_
CB_ NORMALIZE_ IMAGE - CALIB_
CB_ PLAIN - CALIB_
CB_ SYMMETRIC_ GRID - 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_ 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_
NINTRINSIC - CALIB_
RATIONAL_ MODEL - CALIB_
ROBOT_ WORLD_ HAND_ EYE_ LI - Simultaneous robot-world and hand-eye calibration using dual-quaternions and kronecker product Li2010SimultaneousRA
- CALIB_
ROBOT_ WORLD_ HAND_ EYE_ SHAH - Solving the robot-world/hand-eye calibration problem using the kronecker product Shah2013SolvingTR
- 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 - COV_
POLISHER - Circles
Grid Finder Parameters_ ASYMMETRIC_ GRID - Circles
Grid Finder Parameters_ 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.
- Fisheye_
CALIB_ CHECK_ COND - Fisheye_
CALIB_ FIX_ FOCAL_ LENGTH - Fisheye_
CALIB_ FIX_ INTRINSIC - Fisheye_
CALIB_ FIX_ K1 - Fisheye_
CALIB_ FIX_ K2 - Fisheye_
CALIB_ FIX_ K3 - Fisheye_
CALIB_ FIX_ K4 - Fisheye_
CALIB_ FIX_ PRINCIPAL_ POINT - Fisheye_
CALIB_ FIX_ SKEW - Fisheye_
CALIB_ RECOMPUTE_ EXTRINSIC - Fisheye_
CALIB_ USE_ INTRINSIC_ GUESS - Fisheye_
CALIB_ ZERO_ DISPARITY - LMEDS
- least-median of squares algorithm
- LOCAL_
OPTIM_ GC - LOCAL_
OPTIM_ INNER_ AND_ ITER_ LO - LOCAL_
OPTIM_ INNER_ LO - LOCAL_
OPTIM_ NULL - LOCAL_
OPTIM_ SIGMA - LSQ_
POLISHER - MAGSAC
- NEIGH_
FLANN_ KNN - NEIGH_
FLANN_ RADIUS - NEIGH_
GRID - NONE_
POLISHER - PROJ_
SPHERICAL_ EQRECT - PROJ_
SPHERICAL_ ORTHO - RANSAC
- RANSAC algorithm
- RHO
- RHO algorithm
- SAMPLING_
NAPSAC - SAMPLING_
PROGRESSIVE_ NAPSAC - SAMPLING_
PROSAC - SAMPLING_
UNIFORM - SCORE_
METHOD_ LMEDS - SCORE_
METHOD_ MAGSAC - SCORE_
METHOD_ MSAC - SCORE_
METHOD_ RANSAC - SOLVEPNP_
AP3P - An Efficient Algebraic Solution to the Perspective-Three-Point Problem Ke17
- SOLVEPNP_
DLS - Broken implementation. Using this flag will fallback to EPnP.
- 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 - Pose refinement using non-linear Levenberg-Marquardt minimization scheme Madsen04 Eade13
- SOLVEPNP_
MAX_ COUNT - Used for count
- SOLVEPNP_
P3P - Complete Solution Classification for the Perspective-Three-Point Problem gao2003complete
- SOLVEPNP_
SQPNP - SQPnP: A Consistently Fast and Globally OptimalSolution to the Perspective-n-Point Problem Terzakis2020SQPnP
- SOLVEPNP_
UPNP - Broken implementation. Using this flag will fallback to EPnP.
- StereoBM_
PREFILTER_ NORMALIZED_ RESPONSE - StereoBM_
PREFILTER_ XSOBEL - Stereo
Matcher_ DISP_ SCALE - Stereo
Matcher_ DISP_ SHIFT - StereoSGBM_
MODE_ HH - StereoSGBM_
MODE_ HH4 - StereoSGBM_
MODE_ SGBM - StereoSGBM_
MODE_ SGBM_ 3WAY - USAC_
ACCURATE - USAC, accurate settings
- USAC_
DEFAULT - USAC algorithm, default settings
- USAC_
FAST - USAC, fast settings
- USAC_
FM_ 8PTS - USAC, fundamental matrix 8 points
- USAC_
MAGSAC - USAC, runs MAGSAC++
- USAC_
PARALLEL - USAC, parallel version
- USAC_
PROSAC - USAC, sorted points, runs PROSAC
Traits§
- LMSolver
Trait - Mutable methods for crate::calib3d::LMSolver
- LMSolver
Trait Const - Constant methods for crate::calib3d::LMSolver
- LMSolver_
Callback Trait - Mutable methods for crate::calib3d::LMSolver_Callback
- LMSolver_
Callback Trait Const - Constant methods for crate::calib3d::LMSolver_Callback
- StereoBM
Trait - Mutable methods for crate::calib3d::StereoBM
- StereoBM
Trait Const - Constant methods for crate::calib3d::StereoBM
- Stereo
Matcher Trait - Mutable methods for crate::calib3d::StereoMatcher
- Stereo
Matcher Trait Const - Constant methods for crate::calib3d::StereoMatcher
- StereoSGBM
Trait - Mutable methods for crate::calib3d::StereoSGBM
- StereoSGBM
Trait Const - Constant methods for crate::calib3d::StereoSGBM
Functions§
- calibrate
- Performs camera calibration
- calibrate_
camera - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
camera_ def - @overload
- calibrate_
camera_ extended - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
camera_ extended_ def - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
camera_ ro - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
camera_ ro_ def - @overload
- calibrate_
camera_ ro_ extended - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
camera_ ro_ extended_ def - Finds the camera intrinsic and extrinsic parameters from several views of a calibration pattern.
- calibrate_
def - Performs camera calibration
- calibrate_
hand_ eye - Computes Hand-Eye calibration: inline formula
- calibrate_
hand_ eye_ def - Computes Hand-Eye calibration: inline formula
- calibrate_
robot_ world_ hand_ eye - Computes Robot-World/Hand-Eye calibration: inline formula and inline formula
- calibrate_
robot_ world_ hand_ eye_ def - Computes Robot-World/Hand-Eye calibration: inline formula and inline formula
- calibration_
matrix_ values - Computes useful camera characteristics from the camera intrinsic matrix.
- check_
chessboard - compose_
rt - Combines two rotation-and-shift transformations.
- compose_
rt_ def - 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 intrinsic matrix.
- decompose_
projection_ matrix_ def - Decomposes a projection matrix into a rotation matrix and a camera intrinsic matrix.
- distort_
points - Distorts 2D points using fisheye model.
- distort_
points_ def - @overload Overload of distortPoints function to handle cases when undistorted points are obtained with non-identity camera matrix, e.g. output of #estimateNewCameraMatrixForUndistortRectify.
- 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
- draw_
frame_ axes_ def - 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_ 2d_ 1 - estimate_
affine_ 2d_ def - 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_ 3d_ 1 - Computes an optimal affine transformation between two 3D point sets.
- estimate_
affine_ 3d_ 1_ def - Computes an optimal affine transformation between two 3D point sets.
- estimate_
affine_ 3d_ def - 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_
affine_ partial_ 2d_ def - Computes an optimal limited affine transformation with 4 degrees of freedom between two 2D point sets.
- estimate_
chessboard_ sharpness - Estimates the sharpness of a detected chessboard.
- estimate_
chessboard_ sharpness_ def - Estimates the sharpness of a detected chessboard.
- estimate_
new_ camera_ matrix_ for_ undistort_ rectify - Estimates new camera intrinsic matrix for undistortion or rectification.
- estimate_
new_ camera_ matrix_ for_ undistort_ rectify_ def - Estimates new camera intrinsic matrix for undistortion or rectification.
- estimate_
translation_ 3d - Computes an optimal translation between two 3D point sets.
- estimate_
translation_ 3d_ def - Computes an optimal translation between two 3D point sets.
- filter_
homography_ decomp_ by_ visible_ refpoints - Filters homography decompositions based on additional information.
- filter_
homography_ decomp_ by_ visible_ refpoints_ def - Filters homography decompositions based on additional information.
- filter_
speckles - Filters off small noise blobs (speckles) in the disparity map
- filter_
speckles_ def - 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_
chessboard_ corners_ def - Finds the positions of internal corners of the chessboard.
- find_
chessboard_ corners_ sb - Finds the positions of internal corners of the chessboard using a sector based approach.
- find_
chessboard_ corners_ sb_ def - @overload
- find_
chessboard_ corners_ sb_ with_ meta - Finds the positions of internal corners of the chessboard using a sector based approach.
- find_
circles_ grid - Finds centers in the grid of circles.
- find_
circles_ grid_ 1 - Finds centers in the grid of circles.
- find_
circles_ grid_ 1_ def - @overload
- find_
essential_ mat - Calculates an essential matrix from the corresponding points in two images.
- find_
essential_ mat_ 1 - Calculates an essential matrix from the corresponding points in two images.
- find_
essential_ mat_ 2 - Calculates an essential matrix from the corresponding points in two images.
- find_
essential_ mat_ 3 - Calculates an essential matrix from the corresponding points in two images from potentially two different cameras.
- find_
essential_ mat_ 4 - find_
essential_ mat_ 1_ def - @overload
- find_
essential_ mat_ 3_ def - Calculates an essential matrix from the corresponding points in two images from potentially two different cameras.
- find_
essential_ mat_ def - 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_
fundamental_ mat_ 1 - Calculates a fundamental matrix from the corresponding points in two images.
- find_
fundamental_ mat_ 2 - find_
fundamental_ mat_ 1_ def - @overload
- find_
fundamental_ mat_ def - Calculates a fundamental matrix from the corresponding points in two images.
- find_
fundamental_ mat_ mask - Calculates a fundamental matrix from the corresponding points in two images.
- find_
fundamental_ mat_ mask_ def - @overload
- find_
homography - Finds a perspective transformation between two planes.
- find_
homography_ 1 - find_
homography_ def - @overload
- find_
homography_ ext - Finds a perspective transformation between two planes.
- find_
homography_ ext_ def - Finds a perspective transformation between two planes.
- fisheye_
distort_ points - Distorts 2D points using fisheye model.
- fisheye_
distort_ points_ def - Distorts 2D points using fisheye model.
- fisheye_
init_ undistort_ rectify_ map - Computes undistortion and rectification maps for image transform by #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_
project_ points_ def - Projects points using fisheye model
- fisheye_
project_ points_ vec - Projects points using fisheye model
- fisheye_
project_ points_ vec_ def - @overload
- fisheye_
stereo_ calibrate - Performs stereo calibration
- fisheye_
stereo_ calibrate_ def - @overload
- fisheye_
stereo_ rectify - Stereo rectification for fisheye camera model
- fisheye_
stereo_ rectify_ def - Stereo rectification for fisheye camera model
- fisheye_
undistort_ image - Transforms an image to compensate for fisheye lens distortion.
- fisheye_
undistort_ image_ def - Transforms an image to compensate for fisheye lens distortion.
- fisheye_
undistort_ points - Undistorts 2D points using fisheye model
- fisheye_
undistort_ points_ def - Undistorts 2D points using fisheye model
- get_
default_ new_ camera_ matrix - Returns the default new camera matrix.
- get_
default_ new_ camera_ matrix_ def - Returns the default new camera matrix.
- get_
optimal_ new_ camera_ matrix - Returns the new camera intrinsic matrix based on the free scaling parameter.
- get_
optimal_ new_ camera_ matrix_ def - Returns the new camera intrinsic 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 #stereoRectify)
- init_
camera_ matrix_ 2d - Finds an initial camera intrinsic matrix from 3D-2D point correspondences.
- init_
camera_ matrix_ 2d_ def - Finds an initial camera intrinsic matrix from 3D-2D point correspondences.
- init_
inverse_ rectification_ map - Computes the projection and inverse-rectification transformation map. In essense, this is the inverse of init_undistort_rectify_map to accomodate stereo-rectification of projectors (‘inverse-cameras’) in projector-camera pairs.
- init_
undistort_ rectify_ map - Computes the undistortion and rectification transformation map.
- init_
wide_ angle_ proj_ map - initializes maps for [remap] for wide-angle
- init_
wide_ angle_ proj_ map_ def - initializes maps for [remap] for wide-angle
- mat_
mul_ deriv - Computes partial derivatives of the matrix product for each multiplied matrix.
- project_
points - Projects 3D points to an image plane.
- project_
points_ def - Projects 3D points to an image plane.
- recover_
pose - 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.
- recover_
pose_ 2_ cameras - Recovers the relative camera rotation and the translation from corresponding points in two images from two different cameras, using cheirality check. Returns the number of inliers that pass the check.
- recover_
pose_ 2_ cameras_ def - Recovers the relative camera rotation and the translation from corresponding points in two images from two different cameras, using cheirality check. Returns the number of inliers that pass the check.
- recover_
pose_ def - @overload
- recover_
pose_ estimated - 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.
- recover_
pose_ estimated_ def - 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.
- recover_
pose_ triangulated - 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.
- recover_
pose_ triangulated_ def - @overload
- 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.
- reproject_
image_ to_ 3d_ def - Reprojects a disparity image to 3D space.
- rodrigues
- Converts a rotation matrix to a rotation vector or vice versa.
- rodrigues_
def - Converts a rotation matrix to a rotation vector or vice versa.
- rq_
decomp3x3 - Computes an RQ decomposition of 3x3 matrices.
- rq_
decomp3x3_ def - 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.
- solve_
pnp_ 1 - Finds an object pose from 3D-2D point correspondences for fisheye camera moodel.
- solve_
pnp_ 1_ def - Finds an object pose from 3D-2D point correspondences for fisheye camera moodel.
- solve_
pnp_ def - Finds an object pose from 3D-2D point correspondences.
- solve_
pnp_ generic - Finds an object pose from 3D-2D point correspondences.
- solve_
pnp_ generic_ def - Finds an object pose from 3D-2D point correspondences.
- solve_
pnp_ ransac - Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
- solve_
pnp_ ransac_ 1 - C++ default parameters
- solve_
pnp_ ransac_ 1_ def - Note
- solve_
pnp_ ransac_ def - 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_ lm_ def - 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.
- solve_
pnp_ refine_ vvs_ def - 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 - Calibrates a stereo camera set up. This function finds the intrinsic parameters for each of the two cameras and the extrinsic parameters between the two cameras.
- stereo_
calibrate_ 1 - Calibrates a stereo camera set up. This function finds the intrinsic parameters for each of the two cameras and the extrinsic parameters between the two cameras.
- stereo_
calibrate_ 2 - Performs stereo calibration
- stereo_
calibrate_ 1_ def - @overload
- stereo_
calibrate_ 2_ def - Performs stereo calibration
- stereo_
calibrate_ def - @overload
- stereo_
calibrate_ extended - Calibrates a stereo camera set up. This function finds the intrinsic parameters for each of the two cameras and the extrinsic parameters between the two cameras.
- stereo_
calibrate_ extended_ def - Calibrates a stereo camera set up. This function finds the intrinsic parameters for each of the two cameras and the extrinsic parameters between the two cameras.
- stereo_
rectify - Computes rectification transforms for each head of a calibrated stereo camera.
- stereo_
rectify_ def - Computes rectification transforms for each head of a calibrated stereo camera.
- stereo_
rectify_ uncalibrated - Computes a rectification transform for an uncalibrated stereo camera.
- stereo_
rectify_ uncalibrated_ def - Computes a rectification transform for an uncalibrated stereo camera.
- triangulate_
points - This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observations with a stereo camera.
- undistort
- Transforms an image to compensate for lens distortion.
- undistort_
def - Transforms an image to compensate for lens distortion.
- undistort_
image_ points - Compute undistorted image points position
- undistort_
image_ points_ def - Compute undistorted image points position
- undistort_
points - Computes the ideal point coordinates from the observed point coordinates.
- undistort_
points_ def - Computes the ideal point coordinates from the observed point coordinates.
- undistort_
points_ iter - Computes the ideal point coordinates from the observed point coordinates.
- validate_
disparity - validates disparity using the left-right check. The matrix “cost” should be computed by the stereo correspondence algorithm
- validate_
disparity_ def - validates disparity using the left-right check. The matrix “cost” should be computed by the stereo correspondence algorithm