OpenCV  5.0.0-pre
Open Source Computer Vision
Loading...
Searching...
No Matches
Namespaces | Classes | Enumerations | Functions
3D vision functionality

Detailed Description

Most of 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 \(P_w\) into the image plane using a perspective transformation which forms the corresponding pixel \(p\). Both \(P_w\) and \(p\) 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.

\[s \; p = A \begin{bmatrix} R|t \end{bmatrix} P_w,\]

where \(P_w\) is a 3D point expressed with respect to the world coordinate system, \(p\) is a 2D pixel in the image plane, \(A\) is the camera intrinsic matrix, \(R\) and \(t\) are the rotation and translation that describe the change of coordinates from world to camera coordinate systems (or camera frame) and \(s\) is the projective transformation's arbitrary scaling and not part of the camera model.

The camera intrinsic matrix \(A\) (notation used as in [315] and also generally notated as \(K\)) projects 3D points given in the camera coordinate system to 2D pixel coordinates, i.e.

\[p = A P_c.\]

The camera intrinsic matrix \(A\) is composed of the focal lengths \(f_x\) and \(f_y\), which are expressed in pixel units, and the principal point \((c_x, c_y)\), that is usually close to the image center:

\[A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1},\]

and thus

\[s \vecthree{u}{v}{1} = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1} \vecthree{X_c}{Y_c}{Z_c}.\]

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 \([R|t]\) 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 \(x' = X_c / Z_c\) and \(y' = Y_c / Z_c\):

\[Z_c \begin{bmatrix} x' \\ y' \\ 1 \end{bmatrix} = \begin{bmatrix} 1 & 0 & 0 & 0 \\ 0 & 1 & 0 & 0 \\ 0 & 0 & 1 & 0 \end{bmatrix} \begin{bmatrix} X_c \\ Y_c \\ Z_c \\ 1 \end{bmatrix}.\]

The homogeneous transformation is encoded by the extrinsic parameters \(R\) and \(t\) and represents the change of basis from world coordinate system \(w\) to the camera coordinate sytem \(c\). Thus, given the representation of the point \(P\) in world coordinates, \(P_w\), we obtain \(P\)'s representation in the camera coordinate system, \(P_c\), by

\[P_c = \begin{bmatrix} R & t \\ 0 & 1 \end{bmatrix} P_w,\]

This homogeneous transformation is composed out of \(R\), a 3-by-3 rotation matrix, and \(t\), a 3-by-1 translation vector:

\[\begin{bmatrix} R & t \\ 0 & 1 \end{bmatrix} = \begin{bmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \\ 0 & 0 & 0 & 1 \end{bmatrix}, \]

and therefore

\[\begin{bmatrix} X_c \\ Y_c \\ Z_c \\ 1 \end{bmatrix} = \begin{bmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \\ 0 & 0 & 0 & 1 \end{bmatrix} \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix}.\]

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:

\[Z_c \begin{bmatrix} x' \\ y' \\ 1 \end{bmatrix} = \begin{bmatrix} R|t \end{bmatrix} \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix} = \begin{bmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \end{bmatrix} \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix},\]

with \(x' = X_c / Z_c\) and \(y' = Y_c / Z_c\). Putting the equations for instrincs and extrinsics together, we can write out \(s \; p = A \begin{bmatrix} R|t \end{bmatrix} P_w\) as

\[s \vecthree{u}{v}{1} = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1} \begin{bmatrix} r_{11} & r_{12} & r_{13} & t_x \\ r_{21} & r_{22} & r_{23} & t_y \\ r_{31} & r_{32} & r_{33} & t_z \end{bmatrix} \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix}.\]

If \(Z_c \ne 0\), the transformation above is equivalent to the following,

\[\begin{bmatrix} u \\ v \end{bmatrix} = \begin{bmatrix} f_x X_c/Z_c + c_x \\ f_y Y_c/Z_c + c_y \end{bmatrix}\]

with

\[\vecthree{X_c}{Y_c}{Z_c} = \begin{bmatrix} R|t \end{bmatrix} \begin{bmatrix} X_w \\ Y_w \\ Z_w \\ 1 \end{bmatrix}.\]

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:

\[\begin{bmatrix} u \\ v \end{bmatrix} = \begin{bmatrix} f_x x'' + c_x \\ f_y y'' + c_y \end{bmatrix}\]

where

\[\begin{bmatrix} x'' \\ y'' \end{bmatrix} = \begin{bmatrix} x' \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6} + 2 p_1 x' y' + p_2(r^2 + 2 x'^2) + s_1 r^2 + s_2 r^4 \\ y' \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6} + p_1 (r^2 + 2 y'^2) + 2 p_2 x' y' + s_3 r^2 + s_4 r^4 \\ \end{bmatrix}\]

with

\[r^2 = x'^2 + y'^2\]

and

\[\begin{bmatrix} x'\\ y' \end{bmatrix} = \begin{bmatrix} X_c/Z_c \\ Y_c/Z_c \end{bmatrix},\]

if \(Z_c \ne 0\).

The distortion parameters are the radial coefficients \(k_1\), \(k_2\), \(k_3\), \(k_4\), \(k_5\), and \(k_6\) , \(p_1\) and \(p_2\) are the tangential distortion coefficients, and \(s_1\), \(s_2\), \(s_3\), and \(s_4\), 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 ( \( 1 + k_1 r^2 + k_2 r^4 + k_3 r^6 \) monotonically decreasing) and pincushion distortion ( \( 1 + k_1 r^2 + k_2 r^4 + k_3 r^6 \) 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 \(x''\) and \(y''\). This distortion can be modeled in the following way, see e.g. [167].

\[\begin{bmatrix} u \\ v \end{bmatrix} = \begin{bmatrix} f_x x''' + c_x \\ f_y y''' + c_y \end{bmatrix},\]

where

\[s\vecthree{x'''}{y'''}{1} = \vecthreethree{R_{33}(\tau_x, \tau_y)}{0}{-R_{13}(\tau_x, \tau_y)} {0}{R_{33}(\tau_x, \tau_y)}{-R_{23}(\tau_x, \tau_y)} {0}{0}{1} R(\tau_x, \tau_y) \vecthree{x''}{y''}{1}\]

and the matrix \(R(\tau_x, \tau_y)\) is defined by two rotations with angular parameter \(\tau_x\) and \(\tau_y\), respectively,

\[ R(\tau_x, \tau_y) = \vecthreethree{\cos(\tau_y)}{0}{-\sin(\tau_y)}{0}{1}{0}{\sin(\tau_y)}{0}{\cos(\tau_y)} \vecthreethree{1}{0}{0}{0}{\cos(\tau_x)}{\sin(\tau_x)}{0}{-\sin(\tau_x)}{\cos(\tau_x)} = \vecthreethree{\cos(\tau_y)}{\sin(\tau_y)\sin(\tau_x)}{-\sin(\tau_y)\cos(\tau_x)} {0}{\cos(\tau_x)}{\sin(\tau_x)} {\sin(\tau_y)}{-\cos(\tau_y)\sin(\tau_x)}{\cos(\tau_y)\cos(\tau_x)}. \]

In the functions below the coefficients are passed or returned as

\[(k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6 [, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\]

vector. That is, if the vector contains four elements, it means that \(k_3=0\) . 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 \(f_x\), \(f_y\), \(c_x\), and \(c_y\) need to be scaled appropriately.

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

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 \(P_h\) by appending a 1 along an n-dimensional cartesian vector \(P\) e.g. for a 3D cartesian vector the mapping \(P \rightarrow P_h\) is:

\[\begin{bmatrix} X \\ Y \\ Z \end{bmatrix} \rightarrow \begin{bmatrix} X \\ Y \\ Z \\ 1 \end{bmatrix}.\]

For the inverse mapping \(P_h \rightarrow P\), 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:

\[\begin{bmatrix} X \\ Y \\ W \end{bmatrix} \rightarrow \begin{bmatrix} X / W \\ Y / W \end{bmatrix},\]

if \(W \ne 0\).

Due to this mapping, all multiples \(k P_h\), for \(k \ne 0\), of a homogeneous point represent the same point \(P_h\). An intuitive understanding of this property is that under a projective transformation, all multiples of \(P_h\) 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 \(R\) and \(t\) as a linear transformation, e.g. for the change of basis from coordinate system 0 to coordinate system 1 becomes:

\[P_1 = R P_0 + t \rightarrow P_{h_1} = \begin{bmatrix} R & t \\ 0 & 1 \end{bmatrix} P_{h_0}.\]

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

Namespaces

namespace  cv::fisheye
 The methods in this namespace use a so-called fisheye camera model.
 

Classes

class  cv::LevMarq
 Levenberg-Marquadt solver. More...
 
class  cv::Octree
 Octree for 3D vision. More...
 
class  cv::RegionGrowing3D
 Region Growing algorithm in 3D point cloud. More...
 
class  cv::SACSegmentation
 Sample Consensus algorithm segmentation of 3D point cloud model. More...
 
struct  cv::TriangleRasterizeSettings
 Structure to keep settings for rasterization. More...
 
struct  cv::UsacParams
 

Enumerations

enum  {
  cv::LMEDS = 4 ,
  cv::RANSAC = 8 ,
  cv::RHO = 16 ,
  cv::USAC_DEFAULT = 32 ,
  cv::USAC_PARALLEL = 33 ,
  cv::USAC_FM_8PTS = 34 ,
  cv::USAC_FAST = 35 ,
  cv::USAC_ACCURATE = 36 ,
  cv::USAC_PROSAC = 37 ,
  cv::USAC_MAGSAC = 38
}
 type of the robust estimation algorithm More...
 
enum  {
  cv::FM_7POINT = 1 ,
  cv::FM_8POINT = 2 ,
  cv::FM_LMEDS = 4 ,
  cv::FM_RANSAC = 8
}
 the algorithm for finding fundamental matrix More...
 
enum  cv::LocalOptimMethod {
  cv::LOCAL_OPTIM_NULL =0 ,
  cv::LOCAL_OPTIM_INNER_LO =1 ,
  cv::LOCAL_OPTIM_INNER_AND_ITER_LO =2 ,
  cv::LOCAL_OPTIM_GC =3 ,
  cv::LOCAL_OPTIM_SIGMA =4
}
 
enum class  cv::MatrixType {
  cv::MatrixType::AUTO = 0 ,
  cv::MatrixType::DENSE = 1 ,
  cv::MatrixType::SPARSE = 2
}
 Type of matrix used in LevMarq solver. More...
 
enum  cv::NeighborSearchMethod {
  cv::NEIGH_FLANN_KNN =0 ,
  cv::NEIGH_GRID =1 ,
  cv::NEIGH_FLANN_RADIUS =2
}
 
enum  cv::PolishingMethod {
  cv::NONE_POLISHER =0 ,
  cv::LSQ_POLISHER =1 ,
  cv::MAGSAC =2 ,
  cv::COV_POLISHER =3
}
 
enum  cv::SacMethod { cv::SAC_METHOD_RANSAC }
 type of the robust estimation algorithm More...
 
enum  cv::SacModelType {
  cv::SAC_MODEL_PLANE ,
  cv::SAC_MODEL_SPHERE
}
 
enum  cv::SamplingMethod {
  cv::SAMPLING_UNIFORM =0 ,
  cv::SAMPLING_PROGRESSIVE_NAPSAC =1 ,
  cv::SAMPLING_NAPSAC =2 ,
  cv::SAMPLING_PROSAC =3
}
 
enum  cv::ScoreMethod {
  cv::SCORE_METHOD_RANSAC =0 ,
  cv::SCORE_METHOD_MSAC =1 ,
  cv::SCORE_METHOD_MAGSAC =2 ,
  cv::SCORE_METHOD_LMEDS =3
}
 
enum  cv::SolvePnPMethod {
  cv::SOLVEPNP_ITERATIVE = 0 ,
  cv::SOLVEPNP_EPNP = 1 ,
  cv::SOLVEPNP_P3P = 2 ,
  cv::SOLVEPNP_DLS = 3 ,
  cv::SOLVEPNP_UPNP = 4 ,
  cv::SOLVEPNP_AP3P = 5 ,
  cv::SOLVEPNP_IPPE = 6 ,
  cv::SOLVEPNP_IPPE_SQUARE = 7 ,
  cv::SOLVEPNP_SQPNP = 8
}
 
enum  cv::TriangleCullingMode {
  cv::RASTERIZE_CULLING_NONE = 0 ,
  cv::RASTERIZE_CULLING_CW = 1 ,
  cv::RASTERIZE_CULLING_CCW = 2
}
 Face culling settings: what faces are drawn after face culling. More...
 
enum  cv::TriangleGlCompatibleMode {
  cv::RASTERIZE_COMPAT_DISABLED = 0 ,
  cv::RASTERIZE_COMPAT_INVDEPTH = 1
}
 GL compatibility settings. More...
 
enum  cv::TriangleShadingType {
  cv::RASTERIZE_SHADING_WHITE = 0 ,
  cv::RASTERIZE_SHADING_FLAT = 1 ,
  cv::RASTERIZE_SHADING_SHADED = 2
}
 Triangle fill settings. More...
 
enum  cv::UndistortTypes {
  cv::PROJ_SPHERICAL_ORTHO = 0 ,
  cv::PROJ_SPHERICAL_EQRECT = 1
}
 cv::undistort mode More...
 
enum class  cv::VariableType {
  cv::VariableType::LINEAR = 0 ,
  cv::VariableType::SO3 = 1 ,
  cv::VariableType::SE3 = 2
}
 Type of variables used in LevMarq solver. More...
 

Functions

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.
 
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.
 
void cv::convertPointsFromHomogeneous (InputArray src, OutputArray dst, int dtype=-1)
 Converts points from homogeneous to Euclidean space.
 
void cv::convertPointsHomogeneous (InputArray src, OutputArray dst)
 Converts points to/from homogeneous coordinates.
 
void cv::convertPointsToHomogeneous (InputArray src, OutputArray dst, int dtype=-1)
 Converts points from Euclidean to homogeneous space.
 
void cv::correctMatches (InputArray F, InputArray points1, InputArray points2, OutputArray newPoints1, OutputArray newPoints2)
 Refines coordinates of corresponding points.
 
void cv::decomposeEssentialMat (InputArray E, OutputArray R1, OutputArray R2, OutputArray t)
 Decompose an essential matrix to possible rotations and translation.
 
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).
 
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 intrinsic matrix.
 
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.
 
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.
 
Mat cv::estimateAffine2D (InputArray pts1, InputArray pts2, OutputArray inliers, const UsacParams &params)
 
cv::Mat cv::estimateAffine3D (InputArray src, InputArray dst, double *scale=nullptr, bool force_rotation=true)
 Computes an optimal affine transformation between two 3D point sets.
 
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.
 
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.
 
int cv::estimateTranslation3D (InputArray src, InputArray dst, OutputArray out, OutputArray inliers, double ransacThreshold=3, double confidence=0.99)
 Computes an optimal translation between two 3D point sets.
 
int cv::farthestPointSampling (OutputArray sampled_point_flags, InputArray input_pts, float sampled_scale, float dist_lower_limit=0, RNG *rng=nullptr)
 
int cv::farthestPointSampling (OutputArray sampled_point_flags, InputArray input_pts, int sampled_pts_size, float dist_lower_limit=0, RNG *rng=nullptr)
 Point cloud sampling by Farthest Point Sampling(FPS).
 
void cv::filterHomographyDecompByVisibleRefpoints (InputArrayOfArrays rotations, InputArrayOfArrays normals, InputArray beforePoints, InputArray afterPoints, OutputArray possibleSolutions, InputArray pointsMask=noArray())
 Filters homography decompositions based on additional information.
 
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, int maxIters=1000, OutputArray mask=noArray())
 
Mat cv::findEssentialMat (InputArray points1, InputArray points2, InputArray cameraMatrix, int method=RANSAC, double prob=0.999, double threshold=1.0, int maxIters=1000, OutputArray mask=noArray())
 Calculates an essential matrix from the corresponding points in two images.
 
Mat cv::findEssentialMat (InputArray points1, InputArray points2, InputArray cameraMatrix1, InputArray cameraMatrix2, InputArray dist_coeff1, InputArray dist_coeff2, OutputArray mask, const UsacParams &params)
 
Mat cv::findEssentialMat (InputArray points1, InputArray points2, InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, 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 from potentially two different cameras.
 
Mat cv::findFundamentalMat (InputArray points1, InputArray points2, int method, double ransacReprojThreshold, double confidence, int maxIters, OutputArray mask=noArray())
 Calculates a fundamental matrix from the corresponding points in two images.
 
Mat cv::findFundamentalMat (InputArray points1, InputArray points2, int method=FM_RANSAC, double ransacReprojThreshold=3., double confidence=0.99, OutputArray mask=noArray())
 
Mat cv::findFundamentalMat (InputArray points1, InputArray points2, OutputArray mask, const UsacParams &params)
 
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.
 
Mat cv::findHomography (InputArray srcPoints, InputArray dstPoints, OutputArray mask, const UsacParams &params)
 
Mat cv::findHomography (InputArray srcPoints, InputArray dstPoints, OutputArray mask, int method=0, double ransacReprojThreshold=3)
 
Mat cv::getDefaultNewCameraMatrix (InputArray cameraMatrix, Size imgsize=Size(), bool centerPrincipalPoint=false)
 Returns the default new camera matrix.
 
Mat cv::getOptimalNewCameraMatrix (InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, double alpha, Size newImgSize=Size(), Rect *validPixROI=0, bool centerPrincipalPoint=false)
 Returns the new camera intrinsic matrix based on the free scaling parameter.
 
void cv::getUndistortRectangles (InputArray cameraMatrix, InputArray distCoeffs, InputArray R, InputArray newCameraMatrix, Size imgSize, Rect_< double > &inner, Rect_< double > &outer)
 Returns the inscribed and bounding rectangles for the "undisorted" image plane.
 
void cv::initInverseRectificationMap (InputArray cameraMatrix, InputArray distCoeffs, InputArray R, InputArray newCameraMatrix, const Size &size, int m1type, OutputArray map1, OutputArray map2)
 Computes the projection and inverse-rectification transformation map. In essense, this is the inverse of initUndistortRectifyMap to accomodate stereo-rectification of projectors ('inverse-cameras') in projector-camera pairs.
 
void cv::initUndistortRectifyMap (InputArray cameraMatrix, InputArray distCoeffs, InputArray R, InputArray newCameraMatrix, Size size, int m1type, OutputArray map1, OutputArray map2)
 Computes the undistortion and rectification transformation map.
 
float cv::initWideAngleProjMap (InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, int destImageWidth, int m1type, OutputArray map1, OutputArray map2, enum UndistortTypes projType=PROJ_SPHERICAL_EQRECT, double alpha=0)
 initializes maps for remap for wide-angle
 
static float cv::initWideAngleProjMap (InputArray cameraMatrix, InputArray distCoeffs, Size imageSize, int destImageWidth, int m1type, OutputArray map1, OutputArray map2, int projType, double alpha=0)
 
void cv::loadMesh (const String &filename, OutputArray vertices, OutputArrayOfArrays indices, OutputArray normals=noArray(), OutputArray colors=noArray(), OutputArray texCoords=noArray())
 Loads a mesh from a file.
 
void cv::loadPointCloud (const String &filename, OutputArray vertices, OutputArray normals=noArray(), OutputArray rgb=noArray())
 Loads a point cloud from a file.
 
void cv::matMulDeriv (InputArray A, InputArray B, OutputArray dABdA, OutputArray dABdB)
 Computes partial derivatives of the matrix product for each multiplied matrix.
 
void cv::normalEstimate (OutputArray normals, OutputArray curvatures, InputArray input_pts, InputArrayOfArrays nn_idx, int max_neighbor_num=0)
 Estimate the normal and curvature of each point in point cloud from NN results.
 
void cv::projectPoints (InputArray objectPoints, InputArray rvec, InputArray tvec, InputArray cameraMatrix, InputArray distCoeffs, OutputArray imagePoints, OutputArray dpdr, OutputArray dpdt, OutputArray dpdf=noArray(), OutputArray dpdc=noArray(), OutputArray dpdk=noArray(), OutputArray dpdo=noArray(), double aspectRatio=0.)
 
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.
 
void cv::randomSampling (OutputArray sampled_pts, InputArray input_pts, float sampled_scale, RNG *rng=nullptr)
 
void cv::randomSampling (OutputArray sampled_pts, InputArray input_pts, int sampled_pts_size, RNG *rng=nullptr)
 Point cloud sampling by randomly select points.
 
int cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, double distanceThresh, InputOutputArray mask=noArray(), OutputArray triangulatedPoints=noArray())
 
int cv::recoverPose (InputArray E, InputArray points1, InputArray points2, InputArray cameraMatrix, OutputArray R, OutputArray t, InputOutputArray mask=noArray())
 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.
 
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 points1, InputArray points2, InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, OutputArray E, OutputArray R, OutputArray t, int method=cv::RANSAC, double prob=0.999, double threshold=1.0, InputOutputArray mask=noArray())
 Recovers the relative camera rotation and the translation from corresponding points in two images from two different cameras, using chirality check. Returns the number of inliers that pass the check.
 
void cv::Rodrigues (InputArray src, OutputArray dst, OutputArray jacobian=noArray())
 Converts a rotation matrix to a rotation vector or vice versa.
 
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.
 
double cv::sampsonDistance (InputArray pt1, InputArray pt2, InputArray F)
 Calculates the Sampson Distance between two points.
 
void cv::saveMesh (const String &filename, InputArray vertices, InputArrayOfArrays indices, InputArray normals=noArray(), InputArray colors=noArray(), InputArray texCoords=noArray())
 Saves a mesh to a specified file.
 
void cv::savePointCloud (const String &filename, InputArray vertices, InputArray normals=noArray(), InputArray rgb=noArray())
 Saves a point cloud to a specified file.
 
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.
 
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.
 
int cv::solvePnPGeneric (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, OutputArrayOfArrays rvecs, OutputArrayOfArrays tvecs, bool useExtrinsicGuess=false, int flags=SOLVEPNP_ITERATIVE, InputArray rvec=noArray(), InputArray tvec=noArray(), OutputArray reprojectionError=noArray())
 Finds an object pose from 3D-2D point correspondences.
 
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.
 
bool cv::solvePnPRansac (InputArray objectPoints, InputArray imagePoints, InputOutputArray cameraMatrix, InputArray distCoeffs, OutputArray rvec, OutputArray tvec, OutputArray inliers, const UsacParams &params=UsacParams())
 
void cv::solvePnPRefineLM (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec, InputOutputArray tvec, TermCriteria criteria=TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON))
 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.
 
void cv::solvePnPRefineVVS (InputArray objectPoints, InputArray imagePoints, InputArray cameraMatrix, InputArray distCoeffs, InputOutputArray rvec, InputOutputArray tvec, TermCriteria criteria=TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON), double VVSlambda=1)
 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.
 
void cv::triangleRasterize (InputArray vertices, InputArray indices, InputArray colors, InputOutputArray colorBuf, InputOutputArray depthBuf, InputArray world2cam, double fovY, double zNear, double zFar, const TriangleRasterizeSettings &settings=TriangleRasterizeSettings())
 Renders a set of triangles on a depth and color image.
 
void cv::triangleRasterizeColor (InputArray vertices, InputArray indices, InputArray colors, InputOutputArray colorBuf, InputArray world2cam, double fovY, double zNear, double zFar, const TriangleRasterizeSettings &settings=TriangleRasterizeSettings())
 Overloaded version of triangleRasterize() with color-only rendering.
 
void cv::triangleRasterizeDepth (InputArray vertices, InputArray indices, InputOutputArray depthBuf, InputArray world2cam, double fovY, double zNear, double zFar, const TriangleRasterizeSettings &settings=TriangleRasterizeSettings())
 Overloaded version of triangleRasterize() with depth-only rendering.
 
void cv::triangulatePoints (InputArray projMatr1, InputArray projMatr2, InputArray projPoints1, InputArray projPoints2, OutputArray points4D)
 This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observations with a stereo camera.
 
void cv::undistort (InputArray src, OutputArray dst, InputArray cameraMatrix, InputArray distCoeffs, InputArray newCameraMatrix=noArray())
 Transforms an image to compensate for lens distortion.
 
void cv::undistortImagePoints (InputArray src, OutputArray dst, InputArray cameraMatrix, InputArray distCoeffs, TermCriteria=TermCriteria(TermCriteria::MAX_ITER+TermCriteria::EPS, 5, 0.01))
 Compute undistorted image points position.
 
void cv::undistortPoints (InputArray src, OutputArray dst, InputArray cameraMatrix, InputArray distCoeffs, InputArray R=noArray(), InputArray P=noArray(), TermCriteria criteria=TermCriteria(TermCriteria::MAX_ITER, 5, 0.01))
 Computes the ideal point coordinates from the observed point coordinates.
 
int cv::voxelGridSampling (OutputArray sampled_point_flags, InputArray input_pts, float length, float width, float height)
 Point cloud sampling by Voxel Grid filter downsampling.
 

Enumeration Type Documentation

◆ anonymous enum

anonymous enum

#include <opencv2/3d.hpp>

type of the robust estimation algorithm

Enumerator
LMEDS 
Python: cv.LMEDS

least-median of squares algorithm

RANSAC 
Python: cv.RANSAC

RANSAC algorithm.

RHO 
Python: cv.RHO

RHO algorithm.

USAC_DEFAULT 
Python: cv.USAC_DEFAULT

USAC algorithm, default settings.

USAC_PARALLEL 
Python: cv.USAC_PARALLEL

USAC, parallel version.

USAC_FM_8PTS 
Python: cv.USAC_FM_8PTS

USAC, fundamental matrix 8 points.

USAC_FAST 
Python: cv.USAC_FAST

USAC, fast settings.

USAC_ACCURATE 
Python: cv.USAC_ACCURATE

USAC, accurate settings.

USAC_PROSAC 
Python: cv.USAC_PROSAC

USAC, sorted points, runs PROSAC.

USAC_MAGSAC 
Python: cv.USAC_MAGSAC

USAC, runs MAGSAC++.

◆ anonymous enum

anonymous enum

#include <opencv2/3d.hpp>

the algorithm for finding fundamental matrix

Enumerator
FM_7POINT 
Python: cv.FM_7POINT

7-point algorithm

FM_8POINT 
Python: cv.FM_8POINT

8-point algorithm

FM_LMEDS 
Python: cv.FM_LMEDS

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

FM_RANSAC 
Python: cv.FM_RANSAC

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

◆ LocalOptimMethod

#include <opencv2/3d.hpp>

Enumerator
LOCAL_OPTIM_NULL 
Python: cv.LOCAL_OPTIM_NULL
LOCAL_OPTIM_INNER_LO 
Python: cv.LOCAL_OPTIM_INNER_LO
LOCAL_OPTIM_INNER_AND_ITER_LO 
Python: cv.LOCAL_OPTIM_INNER_AND_ITER_LO
LOCAL_OPTIM_GC 
Python: cv.LOCAL_OPTIM_GC
LOCAL_OPTIM_SIGMA 
Python: cv.LOCAL_OPTIM_SIGMA

◆ MatrixType

enum class cv::MatrixType
strong

#include <opencv2/3d.hpp>

Type of matrix used in LevMarq solver.

Matrix type can be dense, sparse or chosen automatically based on a matrix size, performance considerations or backend availability.

Note: only dense matrix is now supported

Enumerator
AUTO 
DENSE 
SPARSE 

◆ NeighborSearchMethod

#include <opencv2/3d.hpp>

Enumerator
NEIGH_FLANN_KNN 
Python: cv.NEIGH_FLANN_KNN
NEIGH_GRID 
Python: cv.NEIGH_GRID
NEIGH_FLANN_RADIUS 
Python: cv.NEIGH_FLANN_RADIUS

◆ PolishingMethod

#include <opencv2/3d.hpp>

Enumerator
NONE_POLISHER 
Python: cv.NONE_POLISHER
LSQ_POLISHER 
Python: cv.LSQ_POLISHER
MAGSAC 
Python: cv.MAGSAC
COV_POLISHER 
Python: cv.COV_POLISHER

◆ SacMethod

#include <opencv2/3d/ptcloud.hpp>

type of the robust estimation algorithm

Enumerator
SAC_METHOD_RANSAC 
Python: cv.SAC_METHOD_RANSAC

The RANSAC algorithm described in [89].

◆ SacModelType

#include <opencv2/3d/ptcloud.hpp>

Enumerator
SAC_MODEL_PLANE 
Python: cv.SAC_MODEL_PLANE

The 3D PLANE model coefficients in list [a, b, c, d], corresponding to the coefficients of equation \( ax + by + cz + d = 0 \).

SAC_MODEL_SPHERE 
Python: cv.SAC_MODEL_SPHERE

The 3D SPHERE model coefficients in list [center_x, center_y, center_z, radius], corresponding to the coefficients of equation \( (x - center\_x)^2 + (y - center\_y)^2 + (z - center\_z)^2 = radius^2 \).

◆ SamplingMethod

#include <opencv2/3d.hpp>

Enumerator
SAMPLING_UNIFORM 
Python: cv.SAMPLING_UNIFORM
SAMPLING_PROGRESSIVE_NAPSAC 
Python: cv.SAMPLING_PROGRESSIVE_NAPSAC
SAMPLING_NAPSAC 
Python: cv.SAMPLING_NAPSAC
SAMPLING_PROSAC 
Python: cv.SAMPLING_PROSAC

◆ ScoreMethod

#include <opencv2/3d.hpp>

Enumerator
SCORE_METHOD_RANSAC 
Python: cv.SCORE_METHOD_RANSAC
SCORE_METHOD_MSAC 
Python: cv.SCORE_METHOD_MSAC
SCORE_METHOD_MAGSAC 
Python: cv.SCORE_METHOD_MAGSAC
SCORE_METHOD_LMEDS 
Python: cv.SCORE_METHOD_LMEDS

◆ SolvePnPMethod

#include <opencv2/3d.hpp>

Enumerator
SOLVEPNP_ITERATIVE 
Python: cv.SOLVEPNP_ITERATIVE

Pose refinement using non-linear Levenberg-Marquardt minimization scheme [174] [75]
Initial solution for non-planar "objectPoints" needs at least 6 points and uses the DLT algorithm.
Initial solution for planar "objectPoints" needs at least 4 points and uses pose from homography decomposition.

SOLVEPNP_EPNP 
Python: cv.SOLVEPNP_EPNP

EPnP: Efficient Perspective-n-Point Camera Pose Estimation [153].

SOLVEPNP_P3P 
Python: cv.SOLVEPNP_P3P

Complete Solution Classification for the Perspective-Three-Point Problem [97].

SOLVEPNP_DLS 
Python: cv.SOLVEPNP_DLS

Broken implementation. Using this flag will fallback to EPnP.
A Direct Least-Squares (DLS) Method for PnP [122]

SOLVEPNP_UPNP 
Python: cv.SOLVEPNP_UPNP

Broken implementation. Using this flag will fallback to EPnP.
Exhaustive Linearization for Robust Camera Pose and Focal Length Estimation [209]

SOLVEPNP_AP3P 
Python: cv.SOLVEPNP_AP3P

An Efficient Algebraic Solution to the Perspective-Three-Point Problem [141].

SOLVEPNP_IPPE 
Python: cv.SOLVEPNP_IPPE

Infinitesimal Plane-Based Pose Estimation [59]
Object points must be coplanar.

SOLVEPNP_IPPE_SQUARE 
Python: cv.SOLVEPNP_IPPE_SQUARE

Infinitesimal Plane-Based Pose Estimation [59]
This is a special case suitable for marker pose estimation.
4 coplanar object points must be defined in the following order:

  • point 0: [-squareLength / 2, squareLength / 2, 0]
  • point 1: [ squareLength / 2, squareLength / 2, 0]
  • point 2: [ squareLength / 2, -squareLength / 2, 0]
  • point 3: [-squareLength / 2, -squareLength / 2, 0]
SOLVEPNP_SQPNP 
Python: cv.SOLVEPNP_SQPNP

SQPnP: A Consistently Fast and Globally OptimalSolution to the Perspective-n-Point Problem [264].

◆ TriangleCullingMode

#include <opencv2/3d.hpp>

Face culling settings: what faces are drawn after face culling.

Enumerator
RASTERIZE_CULLING_NONE 
Python: cv.RASTERIZE_CULLING_NONE

all faces are drawn, no culling is actually performed

RASTERIZE_CULLING_CW 
Python: cv.RASTERIZE_CULLING_CW

triangles which vertices are given in clockwork order are drawn

RASTERIZE_CULLING_CCW 
Python: cv.RASTERIZE_CULLING_CCW

triangles which vertices are given in counterclockwork order are drawn

◆ TriangleGlCompatibleMode

#include <opencv2/3d.hpp>

GL compatibility settings.

Enumerator
RASTERIZE_COMPAT_DISABLED 
Python: cv.RASTERIZE_COMPAT_DISABLED

Color and depth have their natural values and converted to internal formats if needed.

RASTERIZE_COMPAT_INVDEPTH 
Python: cv.RASTERIZE_COMPAT_INVDEPTH

Color is natural, Depth is transformed from [-zNear; -zFar] to [0; 1] by the following formula: \( \frac{z_{far} \left(z + z_{near}\right)}{z \left(z_{far} - z_{near}\right)} \)
In this mode the input/output depthBuf is considered to be in this format, therefore it's faster since there're no conversions performed

◆ TriangleShadingType

#include <opencv2/3d.hpp>

Triangle fill settings.

Enumerator
RASTERIZE_SHADING_WHITE 
Python: cv.RASTERIZE_SHADING_WHITE

a white color is used for the whole triangle

RASTERIZE_SHADING_FLAT 
Python: cv.RASTERIZE_SHADING_FLAT

a color of 1st vertex of each triangle is used

RASTERIZE_SHADING_SHADED 
Python: cv.RASTERIZE_SHADING_SHADED

a color is interpolated between 3 vertices with perspective correction

◆ UndistortTypes

#include <opencv2/3d.hpp>

cv::undistort mode

Enumerator
PROJ_SPHERICAL_ORTHO 
Python: cv.PROJ_SPHERICAL_ORTHO
PROJ_SPHERICAL_EQRECT 
Python: cv.PROJ_SPHERICAL_EQRECT

◆ VariableType

enum class cv::VariableType
strong

#include <opencv2/3d.hpp>

Type of variables used in LevMarq solver.

Variables can be linear, rotation (SO(3) group) or rigid transformation (SE(3) group) with corresponding jacobians and exponential updates.

Note: only linear variables are now supported

Enumerator
LINEAR 
SO3 
SE3 

Function Documentation

◆ composeRT()

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() 
)
Python:
cv.composeRT(rvec1, tvec1, rvec2, tvec2[, rvec3[, tvec3[, dr3dr1[, dr3dt1[, dr3dr2[, dr3dt2[, dt3dr1[, dt3dt1[, dt3dr2[, dt3dt2]]]]]]]]]]) -> rvec3, tvec3, dr3dr1, dr3dt1, dr3dr2, dr3dt2, dt3dr1, dt3dt1, dt3dr2, dt3dt2

#include <opencv2/3d.hpp>

Combines two rotation-and-shift transformations.

Parameters
rvec1First rotation vector.
tvec1First translation vector.
rvec2Second rotation vector.
tvec2Second translation vector.
rvec3Output rotation vector of the superposition.
tvec3Output translation vector of the superposition.
dr3dr1Optional output derivative of rvec3 with regard to rvec1
dr3dt1Optional output derivative of rvec3 with regard to tvec1
dr3dr2Optional output derivative of rvec3 with regard to rvec2
dr3dt2Optional output derivative of rvec3 with regard to tvec2
dt3dr1Optional output derivative of tvec3 with regard to rvec1
dt3dt1Optional output derivative of tvec3 with regard to tvec1
dt3dr2Optional output derivative of tvec3 with regard to rvec2
dt3dt2Optional output derivative of tvec3 with regard to tvec2

The functions compute:

\[\begin{array}{l} \texttt{rvec3} = \mathrm{rodrigues} ^{-1} \left ( \mathrm{rodrigues} ( \texttt{rvec2} ) \cdot \mathrm{rodrigues} ( \texttt{rvec1} ) \right ) \\ \texttt{tvec3} = \mathrm{rodrigues} ( \texttt{rvec2} ) \cdot \texttt{tvec1} + \texttt{tvec2} \end{array} ,\]

where \(\mathrm{rodrigues}\) denotes a rotation vector to a rotation matrix transformation, and \(\mathrm{rodrigues}^{-1}\) denotes the inverse transformation. See Rodrigues for details.

Also, the functions can compute the derivatives of the output vectors with regards to the input vectors (see matMulDeriv ). The functions are used inside stereoCalibrate but can also be used in your own code where Levenberg-Marquardt or another gradient-based solver is used to optimize a function that contains a matrix multiplication.

◆ computeCorrespondEpilines()

void cv::computeCorrespondEpilines ( InputArray  points,
int  whichImage,
InputArray  F,
OutputArray  lines 
)
Python:
cv.computeCorrespondEpilines(points, whichImage, F[, lines]) -> lines

#include <opencv2/3d.hpp>

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

Parameters
pointsInput points. \(N \times 1\) or \(1 \times N\) matrix of type CV_32FC2 or vector<Point2f> .
whichImageIndex of the image (1 or 2) that contains the points .
FFundamental matrix that can be estimated using findFundamentalMat or stereoRectify .
linesOutput vector of the epipolar lines corresponding to the points in the other image. Each line \(ax + by + c=0\) is encoded by 3 numbers \((a, b, c)\) .

For every point in one of the two images of a stereo pair, the function finds the equation of the corresponding epipolar line in the other image.

From the fundamental matrix definition (see findFundamentalMat ), line \(l^{(2)}_i\) in the second image for the point \(p^{(1)}_i\) in the first image (when whichImage=1 ) is computed as:

\[l^{(2)}_i = F p^{(1)}_i\]

And vice versa, when whichImage=2, \(l^{(1)}_i\) is computed from \(p^{(2)}_i\) as:

\[l^{(1)}_i = F^T p^{(2)}_i\]

Line coefficients are defined up to a scale. They are normalized so that \(a_i^2+b_i^2=1\) .

◆ convertPointsFromHomogeneous()

void cv::convertPointsFromHomogeneous ( InputArray  src,
OutputArray  dst,
int  dtype = -1 
)
Python:
cv.convertPointsFromHomogeneous(src[, dst[, dtype]]) -> dst

#include <opencv2/3d.hpp>

Converts points from homogeneous to Euclidean space.

Parameters
srcInput vector of N-dimensional points.
dstOutput vector of N-1-dimensional points.
dtypeThe desired output array depth (either CV_32F or CV_64F are currently supported). If it's -1, then it's set automatically to CV_32F or CV_64F, depending on the input depth.

The function converts points homogeneous to Euclidean space using perspective projection. That is, each point (x1, x2, ... x(n-1), xn) is converted to (x1/xn, x2/xn, ..., x(n-1)/xn). When xn=0, the output point coordinates will be (0,0,0,...).

◆ convertPointsHomogeneous()

void cv::convertPointsHomogeneous ( InputArray  src,
OutputArray  dst 
)

#include <opencv2/3d.hpp>

Converts points to/from homogeneous coordinates.

Parameters
srcInput array or vector of 2D, 3D, or 4D points.
dstOutput vector of 2D, 3D, or 4D points.

The function converts 2D or 3D points from/to homogeneous coordinates by calling either convertPointsToHomogeneous or convertPointsFromHomogeneous.

Note
The function is obsolete. Use one of the previous two functions instead.

◆ convertPointsToHomogeneous()

void cv::convertPointsToHomogeneous ( InputArray  src,
OutputArray  dst,
int  dtype = -1 
)
Python:
cv.convertPointsToHomogeneous(src[, dst[, dtype]]) -> dst

#include <opencv2/3d.hpp>

Converts points from Euclidean to homogeneous space.

Parameters
srcInput vector of N-dimensional points.
dstOutput vector of N+1-dimensional points.
dtypeThe desired output array depth (either CV_32F or CV_64F are currently supported). If it's -1, then it's set automatically to CV_32F or CV_64F, depending on the input depth.

The function converts points from Euclidean to homogeneous space by appending 1's to the tuple of point coordinates. That is, each point (x1, x2, ..., xn) is converted to (x1, x2, ..., xn, 1).

◆ correctMatches()

void cv::correctMatches ( InputArray  F,
InputArray  points1,
InputArray  points2,
OutputArray  newPoints1,
OutputArray  newPoints2 
)
Python:
cv.correctMatches(F, points1, points2[, newPoints1[, newPoints2]]) -> newPoints1, newPoints2

#include <opencv2/3d.hpp>

Refines coordinates of corresponding points.

Parameters
F3x3 fundamental matrix.
points11xN array containing the first set of points.
points21xN array containing the second set of points.
newPoints1The optimized points1.
newPoints2The optimized points2.

The function implements the Optimal Triangulation Method (see Multiple View Geometry [116] for details). For each given point correspondence points1[i] <-> points2[i], and a fundamental matrix F, it computes the corrected correspondences newPoints1[i] <-> newPoints2[i] that minimize the geometric error \(d(points1[i], newPoints1[i])^2 + d(points2[i],newPoints2[i])^2\) (where \(d(a,b)\) is the geometric distance between points \(a\) and \(b\) ) subject to the epipolar constraint \(newPoints2^T \cdot F \cdot newPoints1 = 0\) .

◆ decomposeEssentialMat()

void cv::decomposeEssentialMat ( InputArray  E,
OutputArray  R1,
OutputArray  R2,
OutputArray  t 
)
Python:
cv.decomposeEssentialMat(E[, R1[, R2[, t]]]) -> R1, R2, t

#include <opencv2/3d.hpp>

Decompose an essential matrix to possible rotations and translation.

Parameters
EThe input essential matrix.
R1One possible rotation matrix.
R2Another possible rotation matrix.
tOne possible translation.

This function decomposes the essential matrix E using svd decomposition [116]. In general, four possible poses exist for the decomposition of E. They are \([R_1, t]\), \([R_1, -t]\), \([R_2, t]\), \([R_2, -t]\).

If E gives the epipolar constraint \([p_2; 1]^T A^{-T} E A^{-1} [p_1; 1] = 0\) between the image points \(p_1\) in the first image and \(p_2\) in second image, then any of the tuples \([R_1, t]\), \([R_1, -t]\), \([R_2, t]\), \([R_2, -t]\) is a change of basis from the first camera's coordinate system to the second camera's coordinate system. However, by decomposing E, one can only get the direction of the translation. For this reason, the translation t is returned with unit length.

◆ decomposeHomographyMat()

int cv::decomposeHomographyMat ( InputArray  H,
InputArray  K,
OutputArrayOfArrays  rotations,
OutputArrayOfArrays  translations,
OutputArrayOfArrays  normals 
)
Python:
cv.decomposeHomographyMat(H, K[, rotations[, translations[, normals]]]) -> retval, rotations, translations, normals

#include <opencv2/3d.hpp>

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

Parameters
HThe input homography matrix between two images.
KThe input camera intrinsic matrix.
rotationsArray of rotation matrices.
translationsArray of translation matrices.
normalsArray of plane normal matrices.

This function extracts relative camera motion between two views of a planar object and returns up to four mathematical solution tuples of rotation, translation, and plane normal. The decomposition of the homography matrix H is described in detail in [176].

If the homography H, induced by the plane, gives the constraint

\[s_i \vecthree{x'_i}{y'_i}{1} \sim H \vecthree{x_i}{y_i}{1}\]

on the source image points \(p_i\) and the destination image points \(p'_i\), then the tuple of rotations[k] and translations[k] is a change of basis from the source camera's coordinate system to the destination camera's coordinate system. However, by decomposing H, one can only get the translation normalized by the (typically unknown) depth of the scene, i.e. its direction but with normalized length.

If point correspondences are available, at least two solutions may further be invalidated, by applying positive depth constraint, i.e. all points must be in front of the camera.

◆ decomposeProjectionMatrix()

void cv::decomposeProjectionMatrix ( InputArray  projMatrix,
OutputArray  cameraMatrix,
OutputArray  rotMatrix,
OutputArray  transVect,
OutputArray  rotMatrixX = noArray(),
OutputArray  rotMatrixY = noArray(),
OutputArray  rotMatrixZ = noArray(),
OutputArray  eulerAngles = noArray() 
)
Python:
cv.decomposeProjectionMatrix(projMatrix[, cameraMatrix[, rotMatrix[, transVect[, rotMatrixX[, rotMatrixY[, rotMatrixZ[, eulerAngles]]]]]]]) -> cameraMatrix, rotMatrix, transVect, rotMatrixX, rotMatrixY, rotMatrixZ, eulerAngles

#include <opencv2/3d.hpp>

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

Parameters
projMatrix3x4 input projection matrix P.
cameraMatrixOutput 3x3 camera intrinsic matrix \(\cameramatrix{A}\).
rotMatrixOutput 3x3 external rotation matrix R.
transVectOutput 4x1 translation vector T.
rotMatrixXOptional 3x3 rotation matrix around x-axis.
rotMatrixYOptional 3x3 rotation matrix around y-axis.
rotMatrixZOptional 3x3 rotation matrix around z-axis.
eulerAnglesOptional three-element vector containing three Euler angles of rotation in degrees.

The function computes a decomposition of a projection matrix into a calibration and a rotation matrix and the position of a camera.

It optionally returns three rotation matrices, one for each axis, and three Euler angles that could be used in OpenGL. Note, there is always more than one sequence of rotations about the three principal axes that results in the same orientation of an object, e.g. see [244] . Returned three rotation matrices and corresponding three Euler angles are only one of the possible solutions.

The function is based on RQDecomp3x3 .

◆ drawFrameAxes()

void cv::drawFrameAxes ( InputOutputArray  image,
InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  rvec,
InputArray  tvec,
float  length,
int  thickness = 3 
)
Python:
cv.drawFrameAxes(image, cameraMatrix, distCoeffs, rvec, tvec, length[, thickness]) -> image

#include <opencv2/3d.hpp>

Draw axes of the world/object coordinate system from pose estimation.

See also
solvePnP
Parameters
imageInput/output image. It must have 1 or 3 channels. The number of channels is not altered.
cameraMatrixInput 3x3 floating-point matrix of camera intrinsic parameters. \(\cameramatrix{A}\)
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is empty, the zero distortion coefficients are assumed.
rvecRotation vector (see Rodrigues ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system.
tvecTranslation vector.
lengthLength of the painted axes in the same unit than tvec (usually in meters).
thicknessLine thickness of the painted axes.

This function draws the axes of the world/object coordinate system w.r.t. to the camera frame. OX is drawn in red, OY in green and OZ in blue.

◆ estimateAffine2D() [1/2]

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 
)
Python:
cv.estimateAffine2D(from_, to[, inliers[, method[, ransacReprojThreshold[, maxIters[, confidence[, refineIters]]]]]]) -> retval, inliers
cv.estimateAffine2D(pts1, pts2, params[, inliers]) -> retval, inliers

#include <opencv2/3d.hpp>

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

It computes

\[ \begin{bmatrix} x\\ y\\ \end{bmatrix} = \begin{bmatrix} a_{11} & a_{12}\\ a_{21} & a_{22}\\ \end{bmatrix} \begin{bmatrix} X\\ Y\\ \end{bmatrix} + \begin{bmatrix} b_1\\ b_2\\ \end{bmatrix} \]

Parameters
fromFirst input 2D point set containing \((X,Y)\).
toSecond input 2D point set containing \((x,y)\).
inliersOutput vector indicating which points are inliers (1-inlier, 0-outlier).
methodRobust method used to compute transformation. The following methods are possible:
  • RANSAC - RANSAC-based robust method
  • LMEDS - Least-Median robust method RANSAC is the default method.
ransacReprojThresholdMaximum reprojection error in the RANSAC algorithm to consider a point as an inlier. Applies only to RANSAC.
maxItersThe maximum number of robust method iterations.
confidenceConfidence level, between 0 and 1, for the estimated transformation. Anything between 0.95 and 0.99 is usually good enough. Values too close to 1 can slow down the estimation significantly. Values lower than 0.8-0.9 can result in an incorrectly estimated transformation.
refineItersMaximum number of iterations of refining algorithm (Levenberg-Marquardt). Passing 0 will disable refining, so the output matrix will be output of robust method.
Returns
Output 2D affine transformation matrix \(2 \times 3\) or empty matrix if transformation could not be estimated. The returned matrix has the following form:

\[ \begin{bmatrix} a_{11} & a_{12} & b_1\\ a_{21} & a_{22} & b_2\\ \end{bmatrix} \]

The function estimates an optimal 2D affine transformation between two 2D point sets using the selected robust algorithm.

The computed transformation is then refined further (using only inliers) with the Levenberg-Marquardt method to reduce the re-projection error even more.

Note
The RANSAC method can handle practically any ratio of outliers but needs a threshold to distinguish inliers from outliers. The method LMeDS does not need any threshold but it works correctly only when there are more than 50% of inliers.
See also
estimateAffinePartial2D, getAffineTransform

◆ estimateAffine2D() [2/2]

Mat cv::estimateAffine2D ( InputArray  pts1,
InputArray  pts2,
OutputArray  inliers,
const UsacParams params 
)
Python:
cv.estimateAffine2D(from_, to[, inliers[, method[, ransacReprojThreshold[, maxIters[, confidence[, refineIters]]]]]]) -> retval, inliers
cv.estimateAffine2D(pts1, pts2, params[, inliers]) -> retval, inliers

#include <opencv2/3d.hpp>

◆ estimateAffine3D() [1/2]

cv::Mat cv::estimateAffine3D ( InputArray  src,
InputArray  dst,
double *  scale = nullptr,
bool  force_rotation = true 
)
Python:
cv.estimateAffine3D(src, dst[, out[, inliers[, ransacThreshold[, confidence]]]]) -> retval, out, inliers
cv.estimateAffine3D(src, dst[, force_rotation]) -> retval, scale

#include <opencv2/3d.hpp>

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

It computes \(R,s,t\) minimizing \(\sum{i} dst_i - c \cdot R \cdot src_i \) where \(R\) is a 3x3 rotation matrix, \(t\) is a 3x1 translation vector and \(s\) is a scalar size value. This is an implementation of the algorithm by Umeyama [274] . The estimated affine transform has a homogeneous scale which is a subclass of affine transformations with 7 degrees of freedom. The paired point sets need to comprise at least 3 points each.

Parameters
srcFirst input 3D point set.
dstSecond input 3D point set.
scaleIf null is passed, the scale parameter c will be assumed to be 1.0. Else the pointed-to variable will be set to the optimal scale.
force_rotationIf true, the returned rotation will never be a reflection. This might be unwanted, e.g. when optimizing a transform between a right- and a left-handed coordinate system.
Returns
3D affine transformation matrix \(3 \times 4\) of the form

\[T = \begin{bmatrix} R & t\\ \end{bmatrix} \]

◆ estimateAffine3D() [2/2]

int cv::estimateAffine3D ( InputArray  src,
InputArray  dst,
OutputArray  out,
OutputArray  inliers,
double  ransacThreshold = 3,
double  confidence = 0.99 
)
Python:
cv.estimateAffine3D(src, dst[, out[, inliers[, ransacThreshold[, confidence]]]]) -> retval, out, inliers
cv.estimateAffine3D(src, dst[, force_rotation]) -> retval, scale

#include <opencv2/3d.hpp>

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

It computes

\[ \begin{bmatrix} x\\ y\\ z\\ \end{bmatrix} = \begin{bmatrix} a_{11} & a_{12} & a_{13}\\ a_{21} & a_{22} & a_{23}\\ a_{31} & a_{32} & a_{33}\\ \end{bmatrix} \begin{bmatrix} X\\ Y\\ Z\\ \end{bmatrix} + \begin{bmatrix} b_1\\ b_2\\ b_3\\ \end{bmatrix} \]

Parameters
srcFirst input 3D point set containing \((X,Y,Z)\).
dstSecond input 3D point set containing \((x,y,z)\).
outOutput 3D affine transformation matrix \(3 \times 4\) of the form

\[ \begin{bmatrix} a_{11} & a_{12} & a_{13} & b_1\\ a_{21} & a_{22} & a_{23} & b_2\\ a_{31} & a_{32} & a_{33} & b_3\\ \end{bmatrix} \]

inliersOutput vector indicating which points are inliers (1-inlier, 0-outlier).
ransacThresholdMaximum reprojection error in the RANSAC algorithm to consider a point as an inlier.
confidenceConfidence level, between 0 and 1, for the estimated transformation. Anything between 0.95 and 0.99 is usually good enough. Values too close to 1 can slow down the estimation significantly. Values lower than 0.8-0.9 can result in an incorrectly estimated transformation.

The function estimates an optimal 3D affine transformation between two 3D point sets using the RANSAC algorithm.

◆ estimateAffinePartial2D()

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 
)
Python:
cv.estimateAffinePartial2D(from_, to[, inliers[, method[, ransacReprojThreshold[, maxIters[, confidence[, refineIters]]]]]]) -> retval, inliers

#include <opencv2/3d.hpp>

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

Parameters
fromFirst input 2D point set.
toSecond input 2D point set.
inliersOutput vector indicating which points are inliers.
methodRobust method used to compute transformation. The following methods are possible:
  • RANSAC - RANSAC-based robust method
  • LMEDS - Least-Median robust method RANSAC is the default method.
ransacReprojThresholdMaximum reprojection error in the RANSAC algorithm to consider a point as an inlier. Applies only to RANSAC.
maxItersThe maximum number of robust method iterations.
confidenceConfidence level, between 0 and 1, for the estimated transformation. Anything between 0.95 and 0.99 is usually good enough. Values too close to 1 can slow down the estimation significantly. Values lower than 0.8-0.9 can result in an incorrectly estimated transformation.
refineItersMaximum number of iterations of refining algorithm (Levenberg-Marquardt). Passing 0 will disable refining, so the output matrix will be output of robust method.
Returns
Output 2D affine transformation (4 degrees of freedom) matrix \(2 \times 3\) or empty matrix if transformation could not be estimated.

The function estimates an optimal 2D affine transformation with 4 degrees of freedom limited to combinations of translation, rotation, and uniform scaling. Uses the selected algorithm for robust estimation.

The computed transformation is then refined further (using only inliers) with the Levenberg-Marquardt method to reduce the re-projection error even more.

Estimated transformation matrix is:

\[ \begin{bmatrix} \cos(\theta) \cdot s & -\sin(\theta) \cdot s & t_x \\ \sin(\theta) \cdot s & \cos(\theta) \cdot s & t_y \end{bmatrix} \]

Where \( \theta \) is the rotation angle, \( s \) the scaling factor and \( t_x, t_y \) are translations in \( x, y \) axes respectively.

Note
The RANSAC method can handle practically any ratio of outliers but need a threshold to distinguish inliers from outliers. The method LMeDS does not need any threshold but it works correctly only when there are more than 50% of inliers.
See also
estimateAffine2D, getAffineTransform

◆ estimateTranslation3D()

int cv::estimateTranslation3D ( InputArray  src,
InputArray  dst,
OutputArray  out,
OutputArray  inliers,
double  ransacThreshold = 3,
double  confidence = 0.99 
)
Python:
cv.estimateTranslation3D(src, dst[, out[, inliers[, ransacThreshold[, confidence]]]]) -> retval, out, inliers

#include <opencv2/3d.hpp>

Computes an optimal translation between two 3D point sets.

It computes

\[ \begin{bmatrix} x\\ y\\ z\\ \end{bmatrix} = \begin{bmatrix} X\\ Y\\ Z\\ \end{bmatrix} + \begin{bmatrix} b_1\\ b_2\\ b_3\\ \end{bmatrix} \]

Parameters
srcFirst input 3D point set containing \((X,Y,Z)\).
dstSecond input 3D point set containing \((x,y,z)\).
outOutput 3D translation vector \(3 \times 1\) of the form

\[ \begin{bmatrix} b_1 \\ b_2 \\ b_3 \\ \end{bmatrix} \]

inliersOutput vector indicating which points are inliers (1-inlier, 0-outlier).
ransacThresholdMaximum reprojection error in the RANSAC algorithm to consider a point as an inlier.
confidenceConfidence level, between 0 and 1, for the estimated transformation. Anything between 0.95 and 0.99 is usually good enough. Values too close to 1 can slow down the estimation significantly. Values lower than 0.8-0.9 can result in an incorrectly estimated transformation.

The function estimates an optimal 3D translation between two 3D point sets using the RANSAC algorithm.

◆ farthestPointSampling() [1/2]

int cv::farthestPointSampling ( OutputArray  sampled_point_flags,
InputArray  input_pts,
float  sampled_scale,
float  dist_lower_limit = 0,
RNG rng = nullptr 
)

#include <opencv2/3d/ptcloud.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters
[out]sampled_point_flagsFlags of the sampled point, (pass in std::vector<int> or std::vector<char> etc.) sampled_point_flags[i] is 1 means i-th point selected, 0 means it is not selected.
input_ptsOriginal point cloud, vector of Point3 or Mat of size Nx3/3xN.
sampled_scaleRange (0, 1), the percentage of the sampled point cloud to the original size, that is, sampled size = original size * sampled_scale.
dist_lower_limitSampling is terminated early if the distance from the farthest point to S is less than dist_lower_limit, default 0.
rngOptional random number generator used for selecting seed point for FPS; if it is nullptr, theRNG () is used instead.
Returns
The number of points actually sampled.

◆ farthestPointSampling() [2/2]

int cv::farthestPointSampling ( OutputArray  sampled_point_flags,
InputArray  input_pts,
int  sampled_pts_size,
float  dist_lower_limit = 0,
RNG rng = nullptr 
)

#include <opencv2/3d/ptcloud.hpp>

Point cloud sampling by Farthest Point Sampling(FPS).

FPS Algorithm:

  • Input: Point cloud C, sampled_pts_size, dist_lower_limit
  • Initialize: Set sampled point cloud S to the empty set
  • Step:
    1. Randomly take a seed point from C and take it from C to S;
    2. Find a point in C that is the farthest away from S and take it from C to S; (The distance from point to set S is the smallest distance from point to all points in S)
    3. Repeat step 2 until the farthest distance of the point in C from S is less than dist_lower_limit, or the size of S is equal to sampled_pts_size.
  • Output: Sampled point cloud S
Parameters
[out]sampled_point_flagsFlags of the sampled point, (pass in std::vector<int> or std::vector<char> etc.) sampled_point_flags[i] is 1 means i-th point selected, 0 means it is not selected.
input_ptsOriginal point cloud, vector of Point3 or Mat of size Nx3/3xN.
sampled_pts_sizeThe desired point cloud size after sampling.
dist_lower_limitSampling is terminated early if the distance from the farthest point to S is less than dist_lower_limit, default 0.
rngOptional random number generator used for selecting seed point for FPS; if it is nullptr, theRNG () is used instead.
Returns
The number of points actually sampled.

◆ filterHomographyDecompByVisibleRefpoints()

void cv::filterHomographyDecompByVisibleRefpoints ( InputArrayOfArrays  rotations,
InputArrayOfArrays  normals,
InputArray  beforePoints,
InputArray  afterPoints,
OutputArray  possibleSolutions,
InputArray  pointsMask = noArray() 
)
Python:
cv.filterHomographyDecompByVisibleRefpoints(rotations, normals, beforePoints, afterPoints[, possibleSolutions[, pointsMask]]) -> possibleSolutions

#include <opencv2/3d.hpp>

Filters homography decompositions based on additional information.

Parameters
rotationsVector of rotation matrices.
normalsVector of plane normal matrices.
beforePointsVector of (rectified) visible reference points before the homography is applied
afterPointsVector of (rectified) visible reference points after the homography is applied
possibleSolutionsVector of int indices representing the viable solution set after filtering
pointsMaskoptional Mat/Vector of 8u type representing the mask for the inliers as given by the findHomography function

This function is intended to filter the output of the decomposeHomographyMat based on additional information as described in [176] . The summary of the method: the decomposeHomographyMat function returns 2 unique solutions and their "opposites" for a total of 4 solutions. If we have access to the sets of points visible in the camera frame before and after the homography transformation is applied, we can determine which are the true potential solutions and which are the opposites by verifying which homographies are consistent with all visible reference points being in front of the camera. The inputs are left unchanged; the filtered solution set is returned as indices into the existing one.

◆ findEssentialMat() [1/4]

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,
int  maxIters = 1000,
OutputArray  mask = noArray() 
)
Python:
cv.findEssentialMat(points1, points2, cameraMatrix[, method[, prob[, threshold[, maxIters[, mask]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2[, focal[, pp[, method[, prob[, threshold[, maxIters[, mask]]]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, method[, prob[, threshold[, mask]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, cameraMatrix2, dist_coeff1, dist_coeff2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters
points1Array of N (N >= 5) 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
focalfocal length of the camera. Note that this function assumes that points1 and points2 are feature points from cameras with same focal length and principal point.
ppprincipal point of the camera.
methodMethod for computing a fundamental matrix.
  • RANSAC for the RANSAC algorithm.
  • LMEDS for the LMedS algorithm.
thresholdParameter used for RANSAC. It is the maximum distance from a point to an epipolar line in pixels, beyond which the point is considered an outlier and is not used for computing the final fundamental matrix. It can be set to something like 1-3, depending on the accuracy of the point localization, image resolution, and the image noise.
probParameter used for the RANSAC or LMedS methods only. It specifies a desirable level of confidence (probability) that the estimated matrix is correct.
maskOutput array of N elements, every element of which is set to 0 for outliers and to 1 for the other points. The array is computed only in the RANSAC and LMedS methods.
maxItersThe maximum number of robust method iterations.

This function differs from the one above that it computes camera intrinsic matrix from focal length and principal point:

\[A = \begin{bmatrix} f & 0 & x_{pp} \\ 0 & f & y_{pp} \\ 0 & 0 & 1 \end{bmatrix}\]

◆ findEssentialMat() [2/4]

Mat cv::findEssentialMat ( InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix,
int  method = RANSAC,
double  prob = 0.999,
double  threshold = 1.0,
int  maxIters = 1000,
OutputArray  mask = noArray() 
)
Python:
cv.findEssentialMat(points1, points2, cameraMatrix[, method[, prob[, threshold[, maxIters[, mask]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2[, focal[, pp[, method[, prob[, threshold[, maxIters[, mask]]]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, method[, prob[, threshold[, mask]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, cameraMatrix2, dist_coeff1, dist_coeff2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

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

Parameters
points1Array of N (N >= 5) 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
cameraMatrixCamera intrinsic matrix \(\cameramatrix{A}\) . Note that this function assumes that points1 and points2 are feature points from cameras with the same camera intrinsic matrix. If this assumption does not hold for your use case, use undistortPoints with P = cv::NoArray() for both cameras to transform image points to normalized image coordinates, which are valid for the identity camera intrinsic matrix. When passing these coordinates, pass the identity matrix for this parameter.
methodMethod for computing an essential matrix.
  • RANSAC for the RANSAC algorithm.
  • LMEDS for the LMedS algorithm.
probParameter used for the RANSAC or LMedS methods only. It specifies a desirable level of confidence (probability) that the estimated matrix is correct.
thresholdParameter used for RANSAC. It is the maximum distance from a point to an epipolar line in pixels, beyond which the point is considered an outlier and is not used for computing the final fundamental matrix. It can be set to something like 1-3, depending on the accuracy of the point localization, image resolution, and the image noise.
maskOutput array of N elements, every element of which is set to 0 for outliers and to 1 for the other points. The array is computed only in the RANSAC and LMedS methods.
maxItersThe maximum number of robust method iterations.

This function estimates essential matrix based on the five-point algorithm solver in [204] . [248] is also a related. The epipolar geometry is described by the following equation:

\[[p_2; 1]^T K^{-T} E K^{-1} [p_1; 1] = 0\]

where \(E\) is an essential matrix, \(p_1\) and \(p_2\) are corresponding points in the first and the second images, respectively. The result of this function may be passed further to decomposeEssentialMat or recoverPose to recover the relative pose between cameras.

◆ findEssentialMat() [3/4]

Mat cv::findEssentialMat ( InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix1,
InputArray  cameraMatrix2,
InputArray  dist_coeff1,
InputArray  dist_coeff2,
OutputArray  mask,
const UsacParams params 
)
Python:
cv.findEssentialMat(points1, points2, cameraMatrix[, method[, prob[, threshold[, maxIters[, mask]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2[, focal[, pp[, method[, prob[, threshold[, maxIters[, mask]]]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, method[, prob[, threshold[, mask]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, cameraMatrix2, dist_coeff1, dist_coeff2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

◆ findEssentialMat() [4/4]

Mat cv::findEssentialMat ( InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix1,
InputArray  distCoeffs1,
InputArray  cameraMatrix2,
InputArray  distCoeffs2,
int  method = RANSAC,
double  prob = 0.999,
double  threshold = 1.0,
OutputArray  mask = noArray() 
)
Python:
cv.findEssentialMat(points1, points2, cameraMatrix[, method[, prob[, threshold[, maxIters[, mask]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2[, focal[, pp[, method[, prob[, threshold[, maxIters[, mask]]]]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, method[, prob[, threshold[, mask]]]]) -> retval, mask
cv.findEssentialMat(points1, points2, cameraMatrix1, cameraMatrix2, dist_coeff1, dist_coeff2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

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

Parameters
points1Array of N (N >= 5) 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
cameraMatrix1Camera matrix \(K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) . Note that this function assumes that points1 and points2 are feature points from cameras with the same camera matrix. If this assumption does not hold for your use case, use undistortPoints with P = cv::NoArray() for both cameras to transform image points to normalized image coordinates, which are valid for the identity camera matrix. When passing these coordinates, pass the identity matrix for this parameter.
cameraMatrix2Camera matrix \(K = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) . Note that this function assumes that points1 and points2 are feature points from cameras with the same camera matrix. If this assumption does not hold for your use case, use undistortPoints with P = cv::NoArray() for both cameras to transform image points to normalized image coordinates, which are valid for the identity camera matrix. When passing these coordinates, pass the identity matrix for this parameter.
distCoeffs1Input vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
distCoeffs2Input vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
methodMethod for computing an essential matrix.
  • RANSAC for the RANSAC algorithm.
  • LMEDS for the LMedS algorithm.
probParameter used for the RANSAC or LMedS methods only. It specifies a desirable level of confidence (probability) that the estimated matrix is correct.
thresholdParameter used for RANSAC. It is the maximum distance from a point to an epipolar line in pixels, beyond which the point is considered an outlier and is not used for computing the final fundamental matrix. It can be set to something like 1-3, depending on the accuracy of the point localization, image resolution, and the image noise.
maskOutput array of N elements, every element of which is set to 0 for outliers and to 1 for the other points. The array is computed only in the RANSAC and LMedS methods.

This function estimates essential matrix based on the five-point algorithm solver in [204] . [248] is also a related. The epipolar geometry is described by the following equation:

\[[p_2; 1]^T K^{-T} E K^{-1} [p_1; 1] = 0\]

where \(E\) is an essential matrix, \(p_1\) and \(p_2\) are corresponding points in the first and the second images, respectively. The result of this function may be passed further to decomposeEssentialMat or recoverPose to recover the relative pose between cameras.

◆ findFundamentalMat() [1/4]

Mat cv::findFundamentalMat ( InputArray  points1,
InputArray  points2,
int  method,
double  ransacReprojThreshold,
double  confidence,
int  maxIters,
OutputArray  mask = noArray() 
)
Python:
cv.findFundamentalMat(points1, points2, method, ransacReprojThreshold, confidence, maxIters[, mask]) -> retval, mask
cv.findFundamentalMat(points1, points2[, method[, ransacReprojThreshold[, confidence[, mask]]]]) -> retval, mask
cv.findFundamentalMat(points1, points2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

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

Parameters
points1Array of N points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
methodMethod for computing a fundamental matrix.
  • FM_7POINT for a 7-point algorithm. \(N = 7\)
  • FM_8POINT for an 8-point algorithm. \(N \ge 8\)
  • FM_RANSAC for the RANSAC algorithm. \(N \ge 8\)
  • FM_LMEDS for the LMedS algorithm. \(N \ge 8\)
ransacReprojThresholdParameter used only for RANSAC. It is the maximum distance from a point to an epipolar line in pixels, beyond which the point is considered an outlier and is not used for computing the final fundamental matrix. It can be set to something like 1-3, depending on the accuracy of the point localization, image resolution, and the image noise.
confidenceParameter used for the RANSAC and LMedS methods only. It specifies a desirable level of confidence (probability) that the estimated matrix is correct.
[out]maskoptional output mask
maxItersThe maximum number of robust method iterations.

The epipolar geometry is described by the following equation:

\[[p_2; 1]^T F [p_1; 1] = 0\]

where \(F\) is a fundamental matrix, \(p_1\) and \(p_2\) are corresponding points in the first and the second images, respectively.

The function calculates the fundamental matrix using one of four methods listed above and returns the found fundamental matrix. Normally just one matrix is found. But in case of the 7-point algorithm, the function may return up to 3 solutions ( \(9 \times 3\) matrix that stores all 3 matrices sequentially).

The calculated fundamental matrix may be passed further to computeCorrespondEpilines that finds the epipolar lines corresponding to the specified points. It can also be passed to stereoRectifyUncalibrated to compute the rectification transformation. :

// Example. Estimation of fundamental matrix using the RANSAC algorithm
int point_count = 100;
vector<Point2f> points1(point_count);
vector<Point2f> points2(point_count);
// initialize the points here ...
for( int i = 0; i < point_count; i++ )
{
points1[i] = ...;
points2[i] = ...;
}
Mat fundamental_matrix =
findFundamentalMat(points1, points2, FM_RANSAC, 3, 0.99);
Mat findFundamentalMat(InputArray points1, InputArray points2, int method, double ransacReprojThreshold, double confidence, int maxIters, OutputArray mask=noArray())
Calculates a fundamental matrix from the corresponding points in two images.
@ FM_RANSAC
RANSAC algorithm. It needs at least 15 points. 7-point algorithm is used.
Definition 3d.hpp:419

◆ findFundamentalMat() [2/4]

Mat cv::findFundamentalMat ( InputArray  points1,
InputArray  points2,
int  method = FM_RANSAC,
double  ransacReprojThreshold = 3.,
double  confidence = 0.99,
OutputArray  mask = noArray() 
)
Python:
cv.findFundamentalMat(points1, points2, method, ransacReprojThreshold, confidence, maxIters[, mask]) -> retval, mask
cv.findFundamentalMat(points1, points2[, method[, ransacReprojThreshold[, confidence[, mask]]]]) -> retval, mask
cv.findFundamentalMat(points1, points2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ findFundamentalMat() [3/4]

Mat cv::findFundamentalMat ( InputArray  points1,
InputArray  points2,
OutputArray  mask,
const UsacParams params 
)
Python:
cv.findFundamentalMat(points1, points2, method, ransacReprojThreshold, confidence, maxIters[, mask]) -> retval, mask
cv.findFundamentalMat(points1, points2[, method[, ransacReprojThreshold[, confidence[, mask]]]]) -> retval, mask
cv.findFundamentalMat(points1, points2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

◆ findFundamentalMat() [4/4]

Mat cv::findFundamentalMat ( InputArray  points1,
InputArray  points2,
OutputArray  mask,
int  method = FM_RANSAC,
double  ransacReprojThreshold = 3.,
double  confidence = 0.99 
)
Python:
cv.findFundamentalMat(points1, points2, method, ransacReprojThreshold, confidence, maxIters[, mask]) -> retval, mask
cv.findFundamentalMat(points1, points2[, method[, ransacReprojThreshold[, confidence[, mask]]]]) -> retval, mask
cv.findFundamentalMat(points1, points2, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ findHomography() [1/3]

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 
)
Python:
cv.findHomography(srcPoints, dstPoints[, method[, ransacReprojThreshold[, mask[, maxIters[, confidence]]]]]) -> retval, mask
cv.findHomography(srcPoints, dstPoints, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

Finds a perspective transformation between two planes.

Parameters
srcPointsCoordinates of the points in the original plane, a matrix of the type CV_32FC2 or vector<Point2f> .
dstPointsCoordinates of the points in the target plane, a matrix of the type CV_32FC2 or a vector<Point2f> .
methodMethod used to compute a homography matrix. The following methods are possible:
  • 0 - a regular method using all the points, i.e., the least squares method
  • RANSAC - RANSAC-based robust method
  • LMEDS - Least-Median robust method
  • RHO - PROSAC-based robust method
ransacReprojThresholdMaximum allowed reprojection error to treat a point pair as an inlier (used in the RANSAC and RHO methods only). That is, if

\[\| \texttt{dstPoints} _i - \texttt{convertPointsHomogeneous} ( \texttt{H} \cdot \texttt{srcPoints} _i) \|_2 > \texttt{ransacReprojThreshold}\]

then the point \(i\) is considered as an outlier. If srcPoints and dstPoints are measured in pixels, it usually makes sense to set this parameter somewhere in the range of 1 to 10.
maskOptional output mask set by a robust method ( RANSAC or LMeDS ). Note that the input mask values are ignored.
maxItersThe maximum number of RANSAC iterations.
confidenceConfidence level, between 0 and 1.

The function finds and returns the perspective transformation \(H\) between the source and the destination planes:

\[s_i \vecthree{x'_i}{y'_i}{1} \sim H \vecthree{x_i}{y_i}{1}\]

so that the back-projection error

\[\sum _i \left ( x'_i- \frac{h_{11} x_i + h_{12} y_i + h_{13}}{h_{31} x_i + h_{32} y_i + h_{33}} \right )^2+ \left ( y'_i- \frac{h_{21} x_i + h_{22} y_i + h_{23}}{h_{31} x_i + h_{32} y_i + h_{33}} \right )^2\]

is minimized. If the parameter method is set to the default value 0, the function uses all the point pairs to compute an initial homography estimate with a simple least-squares scheme.

However, if not all of the point pairs ( \(srcPoints_i\), \(dstPoints_i\) ) fit the rigid perspective transformation (that is, there are some outliers), this initial estimate will be poor. In this case, you can use one of the three robust methods. The methods RANSAC, LMeDS and RHO try many different random subsets of the corresponding point pairs (of four pairs each, collinear pairs are discarded), estimate the homography matrix using this subset and a simple least-squares algorithm, and then compute the quality/goodness of the computed homography (which is the number of inliers for RANSAC or the least median re-projection error for LMeDS). The best subset is then used to produce the initial estimate of the homography matrix and the mask of inliers/outliers.

Regardless of the method, robust or not, the computed homography matrix is refined further (using inliers only in case of a robust method) with the Levenberg-Marquardt method to reduce the re-projection error even more.

The methods RANSAC and RHO can handle practically any ratio of outliers but need a threshold to distinguish inliers from outliers. The method LMeDS does not need any threshold but it works correctly only when there are more than 50% of inliers. Finally, if there are no outliers and the noise is rather small, use the default method (method=0).

The function is used to find initial intrinsic and extrinsic matrices. Homography matrix is determined up to a scale. Thus, it is normalized so that \(h_{33}=1\). Note that whenever an \(H\) matrix cannot be estimated, an empty one will be returned.

See also
getAffineTransform, estimateAffine2D, estimateAffinePartial2D, getPerspectiveTransform, warpPerspective, perspectiveTransform

◆ findHomography() [2/3]

Mat cv::findHomography ( InputArray  srcPoints,
InputArray  dstPoints,
OutputArray  mask,
const UsacParams params 
)
Python:
cv.findHomography(srcPoints, dstPoints[, method[, ransacReprojThreshold[, mask[, maxIters[, confidence]]]]]) -> retval, mask
cv.findHomography(srcPoints, dstPoints, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

◆ findHomography() [3/3]

Mat cv::findHomography ( InputArray  srcPoints,
InputArray  dstPoints,
OutputArray  mask,
int  method = 0,
double  ransacReprojThreshold = 3 
)
Python:
cv.findHomography(srcPoints, dstPoints[, method[, ransacReprojThreshold[, mask[, maxIters[, confidence]]]]]) -> retval, mask
cv.findHomography(srcPoints, dstPoints, params[, mask]) -> retval, mask

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ getDefaultNewCameraMatrix()

Mat cv::getDefaultNewCameraMatrix ( InputArray  cameraMatrix,
Size  imgsize = Size(),
bool  centerPrincipalPoint = false 
)
Python:
cv.getDefaultNewCameraMatrix(cameraMatrix[, imgsize[, centerPrincipalPoint]]) -> retval

#include <opencv2/3d.hpp>

Returns the default new camera matrix.

The function returns the camera matrix that is either an exact copy of the input cameraMatrix (when centerPrinicipalPoint=false ), or the modified one (when centerPrincipalPoint=true).

In the latter case, the new camera matrix will be:

\[\begin{bmatrix} f_x && 0 && ( \texttt{imgSize.width} -1)*0.5 \\ 0 && f_y && ( \texttt{imgSize.height} -1)*0.5 \\ 0 && 0 && 1 \end{bmatrix} ,\]

where \(f_x\) and \(f_y\) are \((0,0)\) and \((1,1)\) elements of cameraMatrix, respectively.

By default, the undistortion functions in OpenCV (see initUndistortRectifyMap, undistort) do not move the principal point. However, when you work with stereo, it is important to move the principal points in both views to the same y-coordinate (which is required by most of stereo correspondence algorithms), and may be to the same x-coordinate too. So, you can form the new camera matrix for each view where the principal points are located at the center.

Parameters
cameraMatrixInput camera matrix.
imgsizeCamera view image size in pixels.
centerPrincipalPointLocation of the principal point in the new camera matrix. The parameter indicates whether this location should be at the image center or not.

◆ getOptimalNewCameraMatrix()

Mat cv::getOptimalNewCameraMatrix ( InputArray  cameraMatrix,
InputArray  distCoeffs,
Size  imageSize,
double  alpha,
Size  newImgSize = Size(),
Rect validPixROI = 0,
bool  centerPrincipalPoint = false 
)
Python:
cv.getOptimalNewCameraMatrix(cameraMatrix, distCoeffs, imageSize, alpha[, newImgSize[, centerPrincipalPoint]]) -> retval, validPixROI

#include <opencv2/3d.hpp>

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

Parameters
cameraMatrixInput camera intrinsic matrix.
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
imageSizeOriginal image size.
alphaFree scaling parameter between 0 (when all the pixels in the undistorted image are valid) and 1 (when all the source image pixels are retained in the undistorted image). See stereoRectify for details.
newImgSizeImage size after rectification. By default, it is set to imageSize .
validPixROIOptional output rectangle that outlines all-good-pixels region in the undistorted image. See roi1, roi2 description in stereoRectify .
centerPrincipalPointOptional flag that indicates whether in the new camera intrinsic matrix the principal point should be at the image center or not. By default, the principal point is chosen to best fit a subset of the source image (determined by alpha) to the corrected image.
Returns
new_camera_matrix Output new camera intrinsic matrix.

The function computes and returns the optimal new camera intrinsic matrix based on the free scaling parameter. By varying this parameter, you may retrieve only sensible pixels alpha=0 , keep all the original image pixels if there is valuable information in the corners alpha=1 , or get something in between. When alpha>0 , the undistorted result is likely to have some black pixels corresponding to "virtual" pixels outside of the captured distorted image. The original camera intrinsic matrix, distortion coefficients, the computed new camera intrinsic matrix, and newImageSize should be passed to initUndistortRectifyMap to produce the maps for remap .

◆ getUndistortRectangles()

void cv::getUndistortRectangles ( InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  R,
InputArray  newCameraMatrix,
Size  imgSize,
Rect_< double > &  inner,
Rect_< double > &  outer 
)

#include <opencv2/3d.hpp>

Returns the inscribed and bounding rectangles for the "undisorted" image plane.

The functions emulates undistortion of the image plane using the specified camera matrix, distortion coefficients, the optional 3D rotation and the "new" camera matrix. In the case of noticeable radial (or maybe pinclusion) distortion the rectangular image plane is distorted and turns into some convex or concave shape. The function computes approximate inscribed (inner) and bounding (outer) rectangles after such undistortion. The rectangles can be used to adjust the newCameraMatrix so that the result image, for example, fits all the data from the original image (at the expense of possibly big "black" areas) or, for another example, gets rid of black areas at the expense some lost data near the original image edge. The function getOptimalNewCameraMatrix uses this function to compute the optimal new camera matrix.

Parameters
cameraMatrixthe original camera matrix.
distCoeffsdistortion coefficients.
Rthe optional 3D rotation, applied before projection (see stereoRectify etc.)
newCameraMatrixthe new camera matrix after undistortion. Usually it matches the original cameraMatrix.
imgSizethe size of the image plane.
innerthe output maximal inscribed rectangle of the undistorted image plane.
outerthe output minimal bounding rectangle of the undistorted image plane.

◆ initInverseRectificationMap()

void cv::initInverseRectificationMap ( InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  R,
InputArray  newCameraMatrix,
const Size size,
int  m1type,
OutputArray  map1,
OutputArray  map2 
)
Python:
cv.initInverseRectificationMap(cameraMatrix, distCoeffs, R, newCameraMatrix, size, m1type[, map1[, map2]]) -> map1, map2

#include <opencv2/3d.hpp>

Computes the projection and inverse-rectification transformation map. In essense, this is the inverse of initUndistortRectifyMap to accomodate stereo-rectification of projectors ('inverse-cameras') in projector-camera pairs.

The function computes the joint projection and inverse rectification transformation and represents the result in the form of maps for remap. The projected image looks like a distorted version of the original which, once projected by a projector, should visually match the original. In case of a monocular camera, newCameraMatrix is usually equal to cameraMatrix, or it can be computed by getOptimalNewCameraMatrix for a better control over scaling. In case of a projector-camera pair, newCameraMatrix is normally set to P1 or P2 computed by stereoRectify .

The projector is oriented differently in the coordinate space, according to R. In case of projector-camera pairs, this helps align the projector (in the same manner as initUndistortRectifyMap for the camera) to create a stereo-rectified pair. This allows epipolar lines on both images to become horizontal and have the same y-coordinate (in case of a horizontally aligned projector-camera pair).

The function builds the maps for the inverse mapping algorithm that is used by remap. That is, for each pixel \((u, v)\) in the destination (projected and inverse-rectified) image, the function computes the corresponding coordinates in the source image (that is, in the original digital image). The following process is applied:

\[ \begin{array}{l} \text{newCameraMatrix}\\ x \leftarrow (u - {c'}_x)/{f'}_x \\ y \leftarrow (v - {c'}_y)/{f'}_y \\ \\\text{Undistortion} \\\scriptsize{\textit{though equation shown is for radial undistortion, function implements cv::undistortPoints()}}\\ r^2 \leftarrow x^2 + y^2 \\ \theta \leftarrow \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6}\\ x' \leftarrow \frac{x}{\theta} \\ y' \leftarrow \frac{y}{\theta} \\ \\\text{Rectification}\\ {[X\,Y\,W]} ^T \leftarrow R*[x' \, y' \, 1]^T \\ x'' \leftarrow X/W \\ y'' \leftarrow Y/W \\ \\\text{cameraMatrix}\\ map_x(u,v) \leftarrow x'' f_x + c_x \\ map_y(u,v) \leftarrow y'' f_y + c_y \end{array} \]

where \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) are the distortion coefficients vector distCoeffs.

In case of a stereo-rectified projector-camera pair, this function is called for the projector while initUndistortRectifyMap is called for the camera head. This is done after stereoRectify, which in turn is called after stereoCalibrate. If the projector-camera pair is not calibrated, it is still possible to compute the rectification transformations directly from the fundamental matrix using stereoRectifyUncalibrated. For the projector and camera, the function computes homography H as the rectification transformation in a pixel domain, not a rotation matrix R in 3D space. R can be computed from H as

\[\texttt{R} = \texttt{cameraMatrix} ^{-1} \cdot \texttt{H} \cdot \texttt{cameraMatrix}\]

where cameraMatrix can be chosen arbitrarily.

Parameters
cameraMatrixInput camera matrix \(A=\vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) .
distCoeffsInput vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
ROptional rectification transformation in the object space (3x3 matrix). R1 or R2, computed by stereoRectify can be passed here. If the matrix is empty, the identity transformation is assumed.
newCameraMatrixNew camera matrix \(A'=\vecthreethree{f_x'}{0}{c_x'}{0}{f_y'}{c_y'}{0}{0}{1}\).
sizeDistorted image size.
m1typeType of the first output map. Can be CV_32FC1, CV_32FC2 or CV_16SC2, see convertMaps
map1The first output map for remap.
map2The second output map for remap.

◆ initUndistortRectifyMap()

void cv::initUndistortRectifyMap ( InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  R,
InputArray  newCameraMatrix,
Size  size,
int  m1type,
OutputArray  map1,
OutputArray  map2 
)
Python:
cv.initUndistortRectifyMap(cameraMatrix, distCoeffs, R, newCameraMatrix, size, m1type[, map1[, map2]]) -> map1, map2

#include <opencv2/3d.hpp>

Computes the undistortion and rectification transformation map.

The function computes the joint undistortion and rectification transformation and represents the result in the form of maps for remap. The undistorted image looks like original, as if it is captured with a camera using the camera matrix =newCameraMatrix and zero distortion. In case of a monocular camera, newCameraMatrix is usually equal to cameraMatrix, or it can be computed by getOptimalNewCameraMatrix for a better control over scaling. In case of a stereo camera, newCameraMatrix is normally set to P1 or P2 computed by stereoRectify .

Also, this new camera is oriented differently in the coordinate space, according to R. That, for example, helps to align two heads of a stereo camera so that the epipolar lines on both images become horizontal and have the same y- coordinate (in case of a horizontally aligned stereo camera).

The function actually builds the maps for the inverse mapping algorithm that is used by remap. That is, for each pixel \((u, v)\) in the destination (corrected and rectified) image, the function computes the corresponding coordinates in the source image (that is, in the original image from camera). The following process is applied:

\[ \begin{array}{l} x \leftarrow (u - {c'}_x)/{f'}_x \\ y \leftarrow (v - {c'}_y)/{f'}_y \\ {[X\,Y\,W]} ^T \leftarrow R^{-1}*[x \, y \, 1]^T \\ x' \leftarrow X/W \\ y' \leftarrow Y/W \\ r^2 \leftarrow x'^2 + y'^2 \\ x'' \leftarrow x' \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6} + 2p_1 x' y' + p_2(r^2 + 2 x'^2) + s_1 r^2 + s_2 r^4\\ y'' \leftarrow y' \frac{1 + k_1 r^2 + k_2 r^4 + k_3 r^6}{1 + k_4 r^2 + k_5 r^4 + k_6 r^6} + p_1 (r^2 + 2 y'^2) + 2 p_2 x' y' + s_3 r^2 + s_4 r^4 \\ s\vecthree{x'''}{y'''}{1} = \vecthreethree{R_{33}(\tau_x, \tau_y)}{0}{-R_{13}((\tau_x, \tau_y)} {0}{R_{33}(\tau_x, \tau_y)}{-R_{23}(\tau_x, \tau_y)} {0}{0}{1} R(\tau_x, \tau_y) \vecthree{x''}{y''}{1}\\ map_x(u,v) \leftarrow x''' f_x + c_x \\ map_y(u,v) \leftarrow y''' f_y + c_y \end{array} \]

where \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) are the distortion coefficients.

In case of a stereo camera, this function is called twice: once for each camera head, after stereoRectify, which in its turn is called after stereoCalibrate. But if the stereo camera was not calibrated, it is still possible to compute the rectification transformations directly from the fundamental matrix using stereoRectifyUncalibrated. For each camera, the function computes homography H as the rectification transformation in a pixel domain, not a rotation matrix R in 3D space. R can be computed from H as

\[\texttt{R} = \texttt{cameraMatrix} ^{-1} \cdot \texttt{H} \cdot \texttt{cameraMatrix}\]

where cameraMatrix can be chosen arbitrarily.

Parameters
cameraMatrixInput camera matrix \(A=\vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) .
distCoeffsInput vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
ROptional rectification transformation in the object space (3x3 matrix). R1 or R2 , computed by stereoRectify can be passed here. If the matrix is empty, the identity transformation is assumed. In initUndistortRectifyMap R assumed to be an identity matrix.
newCameraMatrixNew camera matrix \(A'=\vecthreethree{f_x'}{0}{c_x'}{0}{f_y'}{c_y'}{0}{0}{1}\).
sizeUndistorted image size.
m1typeType of the first output map that can be CV_32FC1, CV_32FC2 or CV_16SC2, see convertMaps
map1The first output map.
map2The second output map.

◆ initWideAngleProjMap() [1/2]

float cv::initWideAngleProjMap ( InputArray  cameraMatrix,
InputArray  distCoeffs,
Size  imageSize,
int  destImageWidth,
int  m1type,
OutputArray  map1,
OutputArray  map2,
enum UndistortTypes  projType = PROJ_SPHERICAL_EQRECT,
double  alpha = 0 
)

#include <opencv2/3d.hpp>

initializes maps for remap for wide-angle

◆ initWideAngleProjMap() [2/2]

static float cv::initWideAngleProjMap ( InputArray  cameraMatrix,
InputArray  distCoeffs,
Size  imageSize,
int  destImageWidth,
int  m1type,
OutputArray  map1,
OutputArray  map2,
int  projType,
double  alpha = 0 
)
inlinestatic

#include <opencv2/3d.hpp>

Here is the call graph for this function:

◆ loadMesh()

void cv::loadMesh ( const String filename,
OutputArray  vertices,
OutputArrayOfArrays  indices,
OutputArray  normals = noArray(),
OutputArray  colors = noArray(),
OutputArray  texCoords = noArray() 
)
Python:
cv.loadMesh(filename[, vertices[, indices[, normals[, colors[, texCoords]]]]]) -> vertices, indices, normals, colors, texCoords

#include <opencv2/3d.hpp>

Loads a mesh from a file.

The function loads mesh from the specified file and returns it. If the mesh cannot be read, throws an error Vertex attributes (i.e. space and texture coodinates, normals and colors) are returned in same-sized arrays with corresponding elements having the same indices. This means that if a face uses a vertex with a normal or a texture coordinate with different indices (which is typical for OBJ files for example), this vertex will be duplicated for each face it uses.

Currently, the following file formats are supported:

  • Wavefront obj file *.obj (ONLY TRIANGULATED FACES)
  • Polygon File Format *.ply
    Parameters
    filenameName of the file
    verticesvertex coordinates, each value contains 3 floats
    indicesper-face list of vertices, each value is a vector of ints
    normalsper-vertex normals, each value contains 3 floats
    colorsper-vertex colors, each value contains 3 floats
    texCoordsper-vertex texture coordinates, each value contains 2 or 3 floats

◆ loadPointCloud()

void cv::loadPointCloud ( const String filename,
OutputArray  vertices,
OutputArray  normals = noArray(),
OutputArray  rgb = noArray() 
)
Python:
cv.loadPointCloud(filename[, vertices[, normals[, rgb]]]) -> vertices, normals, rgb

#include <opencv2/3d.hpp>

Loads a point cloud from a file.

The function loads point cloud from the specified file and returns it. If the cloud cannot be read, throws an error. Vertex coordinates, normals and colors are returned as they are saved in the file even if these arrays have different sizes and their elements do not correspond to each other (which is typical for OBJ files for example)

Currently, the following file formats are supported:

Parameters
filenameName of the file
verticesvertex coordinates, each value contains 3 floats
normalsper-vertex normals, each value contains 3 floats
rgbper-vertex colors, each value contains 3 floats

◆ matMulDeriv()

void cv::matMulDeriv ( InputArray  A,
InputArray  B,
OutputArray  dABdA,
OutputArray  dABdB 
)
Python:
cv.matMulDeriv(A, B[, dABdA[, dABdB]]) -> dABdA, dABdB

#include <opencv2/3d.hpp>

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

Parameters
AFirst multiplied matrix.
BSecond multiplied matrix.
dABdAFirst output derivative matrix d(A*B)/dA of size \(\texttt{A.rows*B.cols} \times {A.rows*A.cols}\) .
dABdBSecond output derivative matrix d(A*B)/dB of size \(\texttt{A.rows*B.cols} \times {B.rows*B.cols}\) .

The function computes partial derivatives of the elements of the matrix product \(A*B\) with regard to the elements of each of the two input matrices. The function is used to compute the Jacobian matrices in stereoCalibrate but can also be used in any other similar optimization function.

◆ normalEstimate()

void cv::normalEstimate ( OutputArray  normals,
OutputArray  curvatures,
InputArray  input_pts,
InputArrayOfArrays  nn_idx,
int  max_neighbor_num = 0 
)

#include <opencv2/3d/ptcloud.hpp>

Estimate the normal and curvature of each point in point cloud from NN results.

Normal estimation by PCA:

  • Input: Nearest neighbor points of a specific point: \( pt\_set \)
  • Step:
    1. Calculate the \( mean(\bar{x},\bar{y},\bar{z}) \) of \( pt\_set \);
    2. A 3x3 covariance matrix \( cov \) is obtained by \( mean^T \cdot mean \);
    3. Calculate the eigenvalues( \( λ_2 \ge λ_1 \ge λ_0 \)) and corresponding eigenvectors( \( v_2, v_1, v_0 \)) of \( cov \);
    4. \( v0 \) is the normal of the specific point, \( \frac{λ_0}{λ_0 + λ_1 + λ_2} \) is the curvature of the specific point;
  • Output: Normal and curvature of the specific point.
Parameters
[out]normalsNormal of each point, support vector<Point3f> and Mat of size Nx3.
[out]curvaturesCurvature of each point, support vector<float> and Mat.
input_ptsOriginal point cloud, support vector<Point3f> and Mat of size Nx3/3xN.
nn_idxIndex information of nearest neighbors of all points. The first nearest neighbor of each point is itself. Support vector<vector<int>>, vector<Mat> and Mat of size NxK. If the information in a row is [0, 2, 1, -5, -1, 4, 7 ... negative number], it will use only non-negative indexes until it meets a negative number or bound of this row i.e. [0, 2, 1].
max_neighbor_numThe maximum number of neighbors want to use including itself. Setting to a non-positive number or default will use the information from nn_idx.

◆ projectPoints() [1/2]

void cv::projectPoints ( InputArray  objectPoints,
InputArray  rvec,
InputArray  tvec,
InputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArray  imagePoints,
OutputArray  dpdr,
OutputArray  dpdt,
OutputArray  dpdf = noArray(),
OutputArray  dpdc = noArray(),
OutputArray  dpdk = noArray(),
OutputArray  dpdo = noArray(),
double  aspectRatio = 0. 
)
Python:
cv.projectPoints(objectPoints, rvec, tvec, cameraMatrix, distCoeffs[, imagePoints[, jacobian[, aspectRatio]]]) -> imagePoints, jacobian
cv.projectPointsSepJ(objectPoints, rvec, tvec, cameraMatrix, distCoeffs[, imagePoints[, dpdr[, dpdt[, dpdf[, dpdc[, dpdk[, dpdo[, aspectRatio]]]]]]]]) -> imagePoints, dpdr, dpdt, dpdf, dpdc, dpdk, dpdo

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

◆ projectPoints() [2/2]

void cv::projectPoints ( InputArray  objectPoints,
InputArray  rvec,
InputArray  tvec,
InputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArray  imagePoints,
OutputArray  jacobian = noArray(),
double  aspectRatio = 0 
)
Python:
cv.projectPoints(objectPoints, rvec, tvec, cameraMatrix, distCoeffs[, imagePoints[, jacobian[, aspectRatio]]]) -> imagePoints, jacobian
cv.projectPointsSepJ(objectPoints, rvec, tvec, cameraMatrix, distCoeffs[, imagePoints[, dpdr[, dpdt[, dpdf[, dpdc[, dpdk[, dpdo[, aspectRatio]]]]]]]]) -> imagePoints, dpdr, dpdt, dpdf, dpdc, dpdk, dpdo

#include <opencv2/3d.hpp>

Projects 3D points to an image plane.

Parameters
objectPointsArray of object points expressed wrt. the world coordinate frame. A 3xN/Nx3 1-channel or 1xN/Nx1 3-channel (or vector<Point3f> ), where N is the number of points in the view.
rvecThe rotation vector (Rodrigues) that, together with tvec, performs a change of basis from world to camera coordinate system, see calibrateCamera for details.
tvecThe translation vector, see parameter description above.
cameraMatrixCamera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\) . If the vector is empty, the zero distortion coefficients are assumed.
imagePointsOutput array of image points, 1xN/Nx1 2-channel, or vector<Point2f> .
jacobianOptional output 2Nx(10+<numDistCoeffs>) jacobian matrix of derivatives of image points with respect to components of the rotation vector, translation vector, focal lengths, coordinates of the principal point and the distortion coefficients. In the old interface different components of the jacobian are returned via different output parameters.
aspectRatioOptional "fixed aspect ratio" parameter. If the parameter is not 0, the function assumes that the aspect ratio ( \(f_x / f_y\)) is fixed and correspondingly adjusts the jacobian matrix.

The function computes the 2D projections of 3D points to the image plane, given intrinsic and extrinsic camera parameters. Optionally, the function computes Jacobians -matrices of partial derivatives of image points coordinates (as functions of all the input parameters) with respect to the particular parameters, intrinsic and/or extrinsic. The Jacobians are used during the global optimization in calibrateCamera, solvePnP, and stereoCalibrate. The function itself can also be used to compute a re-projection error, given the current intrinsic and extrinsic parameters.

Note
By setting rvec = tvec = \([0, 0, 0]\), or by setting cameraMatrix to a 3x3 identity matrix, or by passing zero distortion coefficients, one can get various useful partial cases of the function. This means, one can compute the distorted coordinates for a sparse set of points or apply a perspective transformation (and also compute the derivatives) in the ideal zero-distortion setup.

◆ randomSampling() [1/2]

void cv::randomSampling ( OutputArray  sampled_pts,
InputArray  input_pts,
float  sampled_scale,
RNG rng = nullptr 
)

#include <opencv2/3d/ptcloud.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters
sampled_ptsPoint cloud after sampling. Support cv::Mat(size * sampled_scale, 3, CV_32F), std::vector<cv::Point3f>.
input_ptsOriginal point cloud, vector of Point3 or Mat of size Nx3/3xN.
sampled_scaleRange (0, 1), the percentage of the sampled point cloud to the original size, that is, sampled size = original size * sampled_scale.
rngOptional random number generator used for cv::randShuffle; if it is nullptr, theRNG () is used instead.

◆ randomSampling() [2/2]

void cv::randomSampling ( OutputArray  sampled_pts,
InputArray  input_pts,
int  sampled_pts_size,
RNG rng = nullptr 
)

#include <opencv2/3d/ptcloud.hpp>

Point cloud sampling by randomly select points.

Use cv::randShuffle to shuffle the point index list, then take the points corresponding to the front part of the list.

Parameters
sampled_ptsPoint cloud after sampling. Support cv::Mat(sampled_pts_size, 3, CV_32F), std::vector<cv::Point3f>.
input_ptsOriginal point cloud, vector of Point3 or Mat of size Nx3/3xN.
sampled_pts_sizeThe desired point cloud size after sampling.
rngOptional random number generator used for cv::randShuffle; if it is nullptr, theRNG () is used instead.

◆ recoverPose() [1/4]

int cv::recoverPose ( InputArray  E,
InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix,
OutputArray  R,
OutputArray  t,
double  distanceThresh,
InputOutputArray  mask = noArray(),
OutputArray  triangulatedPoints = noArray() 
)
Python:
cv.recoverPose(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, E[, R[, t[, method[, prob[, threshold[, mask]]]]]]]) -> retval, E, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix[, R[, t[, mask]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2[, R[, t[, focal[, pp[, mask]]]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix, distanceThresh[, R[, t[, mask[, triangulatedPoints]]]]) -> retval, R, t, mask, triangulatedPoints

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters
EThe input essential matrix.
points1Array of N 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1.
cameraMatrixCamera intrinsic matrix \(\cameramatrix{A}\) . Note that this function assumes that points1 and points2 are feature points from cameras with the same camera intrinsic matrix.
ROutput rotation matrix. Together with the translation vector, this matrix makes up a tuple that performs a change of basis from the first camera's coordinate system to the second camera's coordinate system. Note that, in general, t can not be used for this tuple, see the parameter description below.
tOutput translation vector. This vector is obtained by decomposeEssentialMat and therefore is only known up to scale, i.e. t is the direction of the translation vector and has unit length.
distanceThreshthreshold distance which is used to filter out far away points (i.e. infinite points).
maskInput/output mask for inliers in points1 and points2. If it is not empty, then it marks inliers in points1 and points2 for the given essential matrix E. Only these inliers will be used to recover pose. In the output mask only inliers which pass the chirality check.
triangulatedPoints3D points which were reconstructed by triangulation.

This function differs from the one above that it outputs the triangulated 3D point that are used for the chirality check.

◆ recoverPose() [2/4]

int cv::recoverPose ( InputArray  E,
InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix,
OutputArray  R,
OutputArray  t,
InputOutputArray  mask = noArray() 
)
Python:
cv.recoverPose(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, E[, R[, t[, method[, prob[, threshold[, mask]]]]]]]) -> retval, E, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix[, R[, t[, mask]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2[, R[, t[, focal[, pp[, mask]]]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix, distanceThresh[, R[, t[, mask[, triangulatedPoints]]]]) -> retval, R, t, mask, triangulatedPoints

#include <opencv2/3d.hpp>

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.

Parameters
EThe input essential matrix.
points1Array of N 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
cameraMatrixCamera intrinsic matrix \(\cameramatrix{A}\) . Note that this function assumes that points1 and points2 are feature points from cameras with the same camera intrinsic matrix.
ROutput rotation matrix. Together with the translation vector, this matrix makes up a tuple that performs a change of basis from the first camera's coordinate system to the second camera's coordinate system. Note that, in general, t can not be used for this tuple, see the parameter described below.
tOutput translation vector. This vector is obtained by decomposeEssentialMat and therefore is only known up to scale, i.e. t is the direction of the translation vector and has unit length.
maskInput/output mask for inliers in points1 and points2. If it is not empty, then it marks inliers in points1 and points2 for the given essential matrix E. Only these inliers will be used to recover pose. In the output mask only inliers which pass the chirality check.

This function decomposes an essential matrix using decomposeEssentialMat and then verifies possible pose hypotheses by doing chirality check. The chirality check means that the triangulated 3D points should have positive depth. Some details can be found in [204].

This function can be used to process the output E and mask from findEssentialMat. In this scenario, points1 and points2 are the same input for findEssentialMat :

// Example. Estimation of fundamental matrix using the RANSAC algorithm
int point_count = 100;
vector<Point2f> points1(point_count);
vector<Point2f> points2(point_count);
// initialize the points here ...
for( int i = 0; i < point_count; i++ )
{
points1[i] = ...;
points2[i] = ...;
}
// cametra matrix with both focal lengths = 1, and principal point = (0, 0)
Mat cameraMatrix = Mat::eye(3, 3, CV_64F);
Mat E, R, t, mask;
E = findEssentialMat(points1, points2, cameraMatrix, RANSAC, 0.999, 1.0, mask);
recoverPose(E, points1, points2, cameraMatrix, R, t, mask);
static CV_NODISCARD_STD MatExpr eye(int rows, int cols, int type)
Returns an identity matrix of the specified size and type.
int recoverPose(InputArray points1, InputArray points2, InputArray cameraMatrix1, InputArray distCoeffs1, InputArray cameraMatrix2, InputArray distCoeffs2, OutputArray E, OutputArray R, OutputArray t, int method=cv::RANSAC, double prob=0.999, double threshold=1.0, InputOutputArray mask=noArray())
Recovers the relative camera rotation and the translation from corresponding points in two images fro...
Mat findEssentialMat(InputArray points1, InputArray points2, InputArray cameraMatrix, int method=RANSAC, double prob=0.999, double threshold=1.0, int maxIters=1000, OutputArray mask=noArray())
Calculates an essential matrix from the corresponding points in two images.
@ RANSAC
RANSAC algorithm.
Definition 3d.hpp:378
#define CV_64F
Definition interface.h:82

◆ recoverPose() [3/4]

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() 
)
Python:
cv.recoverPose(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, E[, R[, t[, method[, prob[, threshold[, mask]]]]]]]) -> retval, E, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix[, R[, t[, mask]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2[, R[, t[, focal[, pp[, mask]]]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix, distanceThresh[, R[, t[, mask[, triangulatedPoints]]]]) -> retval, R, t, mask, triangulatedPoints

#include <opencv2/3d.hpp>

This is an overloaded member function, provided for convenience. It differs from the above function only in what argument(s) it accepts.

Parameters
EThe input essential matrix.
points1Array of N 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
ROutput rotation matrix. Together with the translation vector, this matrix makes up a tuple that performs a change of basis from the first camera's coordinate system to the second camera's coordinate system. Note that, in general, t can not be used for this tuple, see the parameter description below.
tOutput translation vector. This vector is obtained by decomposeEssentialMat and therefore is only known up to scale, i.e. t is the direction of the translation vector and has unit length.
focalFocal length of the camera. Note that this function assumes that points1 and points2 are feature points from cameras with same focal length and principal point.
ppprincipal point of the camera.
maskInput/output mask for inliers in points1 and points2. If it is not empty, then it marks inliers in points1 and points2 for the given essential matrix E. Only these inliers will be used to recover pose. In the output mask only inliers which pass the chirality check.

This function differs from the one above that it computes camera intrinsic matrix from focal length and principal point:

\[A = \begin{bmatrix} f & 0 & x_{pp} \\ 0 & f & y_{pp} \\ 0 & 0 & 1 \end{bmatrix}\]

◆ recoverPose() [4/4]

int cv::recoverPose ( InputArray  points1,
InputArray  points2,
InputArray  cameraMatrix1,
InputArray  distCoeffs1,
InputArray  cameraMatrix2,
InputArray  distCoeffs2,
OutputArray  E,
OutputArray  R,
OutputArray  t,
int  method = cv::RANSAC,
double  prob = 0.999,
double  threshold = 1.0,
InputOutputArray  mask = noArray() 
)
Python:
cv.recoverPose(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2[, E[, R[, t[, method[, prob[, threshold[, mask]]]]]]]) -> retval, E, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix[, R[, t[, mask]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2[, R[, t[, focal[, pp[, mask]]]]]) -> retval, R, t, mask
cv.recoverPose(E, points1, points2, cameraMatrix, distanceThresh[, R[, t[, mask[, triangulatedPoints]]]]) -> retval, R, t, mask, triangulatedPoints

#include <opencv2/3d.hpp>

Recovers the relative camera rotation and the translation from corresponding points in two images from two different cameras, using chirality check. Returns the number of inliers that pass the check.

Parameters
points1Array of N 2D points from the first image. The point coordinates should be floating-point (single or double precision).
points2Array of the second image points of the same size and format as points1 .
cameraMatrix1Input/output camera matrix for the first camera, the same as in calibrateCamera. Furthermore, for the stereo case, additional flags may be used, see below.
distCoeffs1Input/output vector of distortion coefficients, the same as in calibrateCamera.
cameraMatrix2Input/output camera matrix for the first camera, the same as in calibrateCamera. Furthermore, for the stereo case, additional flags may be used, see below.
distCoeffs2Input/output vector of distortion coefficients, the same as in calibrateCamera.
EThe output essential matrix.
ROutput rotation matrix. Together with the translation vector, this matrix makes up a tuple that performs a change of basis from the first camera's coordinate system to the second camera's coordinate system. Note that, in general, t can not be used for this tuple, see the parameter described below.
tOutput translation vector. This vector is obtained by decomposeEssentialMat and therefore is only known up to scale, i.e. t is the direction of the translation vector and has unit length.
methodMethod for computing an essential matrix.
  • RANSAC for the RANSAC algorithm.
  • LMEDS for the LMedS algorithm.
probParameter used for the RANSAC or LMedS methods only. It specifies a desirable level of confidence (probability) that the estimated matrix is correct.
thresholdParameter used for RANSAC. It is the maximum distance from a point to an epipolar line in pixels, beyond which the point is considered an outlier and is not used for computing the final fundamental matrix. It can be set to something like 1-3, depending on the accuracy of the point localization, image resolution, and the image noise.
maskInput/output mask for inliers in points1 and points2. If it is not empty, then it marks inliers in points1 and points2 for the given essential matrix E. Only these inliers will be used to recover pose. In the output mask only inliers which pass the chirality check.

This function decomposes an essential matrix using decomposeEssentialMat and then verifies possible pose hypotheses by doing chirality check. The chirality check means that the triangulated 3D points should have positive depth. Some details can be found in [204].

This function can be used to process the output E and mask from findEssentialMat. In this scenario, points1 and points2 are the same input for findEssentialMat.:

// Example. Estimation of fundamental matrix using the RANSAC algorithm
int point_count = 100;
vector<Point2f> points1(point_count);
vector<Point2f> points2(point_count);
// initialize the points here ...
for( int i = 0; i < point_count; i++ )
{
points1[i] = ...;
points2[i] = ...;
}
// Input: camera calibration of both cameras, for example using intrinsic chessboard calibration.
Mat cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2;
// Output: Essential matrix, relative rotation and relative translation.
Mat E, R, t, mask;
recoverPose(points1, points2, cameraMatrix1, distCoeffs1, cameraMatrix2, distCoeffs2, E, R, t, mask);

◆ Rodrigues()

void cv::Rodrigues ( InputArray  src,
OutputArray  dst,
OutputArray  jacobian = noArray() 
)
Python:
cv.Rodrigues(src[, dst[, jacobian]]) -> dst, jacobian

#include <opencv2/3d.hpp>

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

Parameters
srcInput rotation vector (3x1 or 1x3) or rotation matrix (3x3).
dstOutput rotation matrix (3x3) or rotation vector (3x1 or 1x3), respectively.
jacobianOptional output Jacobian matrix, 3x9 or 9x3, which is a matrix of partial derivatives of the output array components with respect to the input array components.

\[\begin{array}{l} \theta \leftarrow norm(r) \\ r \leftarrow r/ \theta \\ R = \cos(\theta) I + (1- \cos{\theta} ) r r^T + \sin(\theta) \vecthreethree{0}{-r_z}{r_y}{r_z}{0}{-r_x}{-r_y}{r_x}{0} \end{array}\]

Inverse transformation can be also done easily, since

\[\sin ( \theta ) \vecthreethree{0}{-r_z}{r_y}{r_z}{0}{-r_x}{-r_y}{r_x}{0} = \frac{R - R^T}{2}\]

A rotation vector is a convenient and most compact representation of a rotation matrix (since any rotation matrix has just 3 degrees of freedom). The representation is used in the global 3D geometry optimization procedures like calibrateCamera, stereoCalibrate, or solvePnP .

Note
More information about the computation of the derivative of a 3D rotation matrix with respect to its exponential coordinate can be found in:
  • A Compact Formula for the Derivative of a 3-D Rotation in Exponential Coordinates, Guillermo Gallego, Anthony J. Yezzi [96]
Useful information on SE(3) and Lie Groups can be found in:
  • A tutorial on SE(3) transformation parameterizations and on-manifold optimization, Jose-Luis Blanco [29]
  • Lie Groups for 2D and 3D Transformation, Ethan Eade [76]
  • A micro Lie theory for state estimation in robotics, Joan Solà, Jérémie Deray, Dinesh Atchuthan [245]

◆ RQDecomp3x3()

Vec3d cv::RQDecomp3x3 ( InputArray  src,
OutputArray  mtxR,
OutputArray  mtxQ,
OutputArray  Qx = noArray(),
OutputArray  Qy = noArray(),
OutputArray  Qz = noArray() 
)
Python:
cv.RQDecomp3x3(src[, mtxR[, mtxQ[, Qx[, Qy[, Qz]]]]]) -> retval, mtxR, mtxQ, Qx, Qy, Qz

#include <opencv2/3d.hpp>

Computes an RQ decomposition of 3x3 matrices.

Parameters
src3x3 input matrix.
mtxROutput 3x3 upper-triangular matrix.
mtxQOutput 3x3 orthogonal matrix.
QxOptional output 3x3 rotation matrix around x-axis.
QyOptional output 3x3 rotation matrix around y-axis.
QzOptional output 3x3 rotation matrix around z-axis.

The function computes a RQ decomposition using the given rotations. This function is used in decomposeProjectionMatrix to decompose the left 3x3 submatrix of a projection matrix into a camera and a rotation matrix.

It optionally returns three rotation matrices, one for each axis, and the three Euler angles in degrees (as the return value) that could be used in OpenGL. Note, there is always more than one sequence of rotations about the three principal axes that results in the same orientation of an object, e.g. see [244] . Returned three rotation matrices and corresponding three Euler angles are only one of the possible solutions.

◆ sampsonDistance()

double cv::sampsonDistance ( InputArray  pt1,
InputArray  pt2,
InputArray  F 
)
Python:
cv.sampsonDistance(pt1, pt2, F) -> retval

#include <opencv2/3d.hpp>

Calculates the Sampson Distance between two points.

The function cv::sampsonDistance calculates and returns the first order approximation of the geometric error as:

\[ sd( \texttt{pt1} , \texttt{pt2} )= \frac{(\texttt{pt2}^t \cdot \texttt{F} \cdot \texttt{pt1})^2} {((\texttt{F} \cdot \texttt{pt1})(0))^2 + ((\texttt{F} \cdot \texttt{pt1})(1))^2 + ((\texttt{F}^t \cdot \texttt{pt2})(0))^2 + ((\texttt{F}^t \cdot \texttt{pt2})(1))^2} \]

The fundamental matrix may be calculated using the findFundamentalMat function. See [116] 11.4.3 for details.

Parameters
pt1first homogeneous 2d point
pt2second homogeneous 2d point
Ffundamental matrix
Returns
The computed Sampson distance.

◆ saveMesh()

void cv::saveMesh ( const String filename,
InputArray  vertices,
InputArrayOfArrays  indices,
InputArray  normals = noArray(),
InputArray  colors = noArray(),
InputArray  texCoords = noArray() 
)
Python:
cv.saveMesh(filename, vertices, indices[, normals[, colors[, texCoords]]]) -> None

#include <opencv2/3d.hpp>

Saves a mesh to a specified file.

The function saves mesh to the specified file. File format is chosen based on the filename extension.

Parameters
filenameName of the file.
verticesvertex coordinates, each value contains 3 floats
indicesper-face list of vertices, each value is a vector of ints
normalsper-vertex normals, each value contains 3 floats
colorsper-vertex colors, each value contains 3 floats
texCoordsper-vertex texture coordinates, each value contains 2 or 3 floats

◆ savePointCloud()

void cv::savePointCloud ( const String filename,
InputArray  vertices,
InputArray  normals = noArray(),
InputArray  rgb = noArray() 
)
Python:
cv.savePointCloud(filename, vertices[, normals[, rgb]]) -> None

#include <opencv2/3d.hpp>

Saves a point cloud to a specified file.

The function saves point cloud to the specified file. File format is chosen based on the filename extension.

Parameters
filenameName of the file
verticesvertex coordinates, each value contains 3 floats
normalsper-vertex normals, each value contains 3 floats
rgbper-vertex colors, each value contains 3 floats

◆ solveP3P()

int cv::solveP3P ( InputArray  objectPoints,
InputArray  imagePoints,
InputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArrayOfArrays  rvecs,
OutputArrayOfArrays  tvecs,
int  flags 
)
Python:
cv.solveP3P(objectPoints, imagePoints, cameraMatrix, distCoeffs, flags[, rvecs[, tvecs]]) -> retval, rvecs, tvecs

#include <opencv2/3d.hpp>

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

See also
Perspective-n-Point (PnP) pose computation
Parameters
objectPointsArray of object points in the object coordinate space, 3x3 1-channel or 1x3/3x1 3-channel. vector<Point3f> can be also passed here.
imagePointsArray of corresponding image points, 3x2 1-channel or 1x3/3x1 2-channel. vector<Point2f> can be also passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecsOutput rotation vectors (see Rodrigues ) that, together with tvecs, brings points from the model coordinate system to the camera coordinate system. A P3P problem has up to 4 solutions.
tvecsOutput translation vectors.
flagsMethod for solving a P3P problem:
  • SOLVEPNP_P3P Method is based on the paper of X.S. Gao, X.-R. Hou, J. Tang, H.-F. Chang "Complete Solution Classification for the Perspective-Three-Point Problem" ([97]).
  • SOLVEPNP_AP3P Method is based on the paper of T. Ke and S. Roumeliotis. "An Efficient Algebraic Solution to the Perspective-Three-Point Problem" ([141]).

The function estimates the object pose given 3 object points, their corresponding image projections, as well as the camera intrinsic matrix and the distortion coefficients.

Note
The solutions are sorted by reprojection errors (lowest to highest).

◆ solvePnP()

bool cv::solvePnP ( InputArray  objectPoints,
InputArray  imagePoints,
InputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArray  rvec,
OutputArray  tvec,
bool  useExtrinsicGuess = false,
int  flags = SOLVEPNP_ITERATIVE 
)
Python:
cv.solvePnP(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvec[, tvec[, useExtrinsicGuess[, flags]]]]) -> retval, rvec, tvec

#include <opencv2/3d.hpp>

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

See also
Perspective-n-Point (PnP) pose computation

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:

  • P3P methods (SOLVEPNP_P3P, SOLVEPNP_AP3P): need 4 input points to return a unique solution.
  • SOLVEPNP_IPPE Input points must be >= 4 and object points must be coplanar.
  • SOLVEPNP_IPPE_SQUARE Special case suitable for marker pose estimation. Number of input points must be 4. Object points must be defined in the following order:
    • point 0: [-squareLength / 2, squareLength / 2, 0]
    • point 1: [ squareLength / 2, squareLength / 2, 0]
    • point 2: [ squareLength / 2, -squareLength / 2, 0]
    • point 3: [-squareLength / 2, -squareLength / 2, 0]
  • for all the other flags, number of input points must be >= 4 and object points can be in any configuration.
Parameters
objectPointsArray of object points in the object coordinate space, Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3d> can be also passed here.
imagePointsArray of corresponding image points, Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2d> can be also passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecOutput rotation vector (see Rodrigues ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system.
tvecOutput translation vector.
useExtrinsicGuessParameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further optimizes them.
flagsMethod for solving a PnP problem: see calib3d_solvePnP_flags

More information about Perspective-n-Points is described in Perspective-n-Point (PnP) pose computation

Note
  • An example of how to use solvePnP for planar augmented reality can be found at opencv_source_code/samples/python/plane_ar.py
  • If you are using Python:
    • Numpy array slices won't work as input because solvePnP requires contiguous arrays (enforced by the assertion using cv::Mat::checkVector() around line 55 of modules/3d/src/solvepnp.cpp version 2.4.9)
    • The P3P algorithm requires image points to be in an array of shape (N,1,2) due to its calling of undistortPoints (around line 75 of modules/3d/src/solvepnp.cpp version 2.4.9) which requires 2-channel information.
    • Thus, given some data D = np.array(...) where D.shape = (N,M), in order to use a subset of it as, e.g., imagePoints, one must effectively copy it into a new array: imagePoints = np.ascontiguousarray(D[:,:2]).reshape((N,1,2))
  • The methods SOLVEPNP_DLS and SOLVEPNP_UPNP cannot be used as the current implementations are unstable and sometimes give completely wrong results. If you pass one of these two flags, SOLVEPNP_EPNP method will be used instead.
  • The minimum number of points is 4 in the general case. In the case of SOLVEPNP_P3P and SOLVEPNP_AP3P methods, it is required to use exactly 4 points (the first 3 points are used to estimate all the solutions of the P3P problem, the last one is used to retain the best solution that minimizes the reprojection error).
  • With SOLVEPNP_ITERATIVE method and useExtrinsicGuess=true, the minimum number of points is 3 (3 points are sufficient to compute a pose but there are up to 4 solutions). The initial solution should be close to the global solution to converge.
  • With SOLVEPNP_IPPE input points must be >= 4 and object points must be coplanar.
  • With SOLVEPNP_IPPE_SQUARE this is a special case suitable for marker pose estimation. Number of input points must be 4. Object points must be defined in the following order:
    • point 0: [-squareLength / 2, squareLength / 2, 0]
    • point 1: [ squareLength / 2, squareLength / 2, 0]
    • point 2: [ squareLength / 2, -squareLength / 2, 0]
    • point 3: [-squareLength / 2, -squareLength / 2, 0]

◆ solvePnPGeneric()

int cv::solvePnPGeneric ( InputArray  objectPoints,
InputArray  imagePoints,
InputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArrayOfArrays  rvecs,
OutputArrayOfArrays  tvecs,
bool  useExtrinsicGuess = false,
int  flags = SOLVEPNP_ITERATIVE,
InputArray  rvec = noArray(),
InputArray  tvec = noArray(),
OutputArray  reprojectionError = noArray() 
)
Python:
cv.solvePnPGeneric(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvecs[, tvecs[, useExtrinsicGuess[, flags[, rvec[, tvec[, reprojectionError]]]]]]]) -> retval, rvecs, tvecs, reprojectionError

#include <opencv2/3d.hpp>

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

See also
Perspective-n-Point (PnP) pose computation

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:

  • P3P methods (SOLVEPNP_P3P, SOLVEPNP_AP3P): 3 or 4 input points. Number of returned solutions can be between 0 and 4 with 3 input points.
  • SOLVEPNP_IPPE Input points must be >= 4 and object points must be coplanar. Returns 2 solutions.
  • SOLVEPNP_IPPE_SQUARE Special case suitable for marker pose estimation. Number of input points must be 4 and 2 solutions are returned. Object points must be defined in the following order:
    • point 0: [-squareLength / 2, squareLength / 2, 0]
    • point 1: [ squareLength / 2, squareLength / 2, 0]
    • point 2: [ squareLength / 2, -squareLength / 2, 0]
    • point 3: [-squareLength / 2, -squareLength / 2, 0]
  • for all the other flags, number of input points must be >= 4 and object points can be in any configuration. Only 1 solution is returned.
Parameters
objectPointsArray of object points in the object coordinate space, Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3d> can be also passed here.
imagePointsArray of corresponding image points, Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2d> can be also passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecsVector of output rotation vectors (see Rodrigues ) that, together with tvecs, brings points from the model coordinate system to the camera coordinate system.
tvecsVector of output translation vectors.
useExtrinsicGuessParameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further optimizes them.
flagsMethod for solving a PnP problem: see calib3d_solvePnP_flags
rvecRotation vector used to initialize an iterative PnP refinement algorithm, when flag is SOLVEPNP_ITERATIVE and useExtrinsicGuess is set to true.
tvecTranslation vector used to initialize an iterative PnP refinement algorithm, when flag is SOLVEPNP_ITERATIVE and useExtrinsicGuess is set to true.
reprojectionErrorOptional vector of reprojection error, that is the RMS error ( \( \text{RMSE} = \sqrt{\frac{\sum_{i}^{N} \left ( \hat{y_i} - y_i \right )^2}{N}} \)) between the input image points and the 3D object points projected with the estimated pose.

More information is described in Perspective-n-Point (PnP) pose computation

Note
  • An example of how to use solvePnP for planar augmented reality can be found at opencv_source_code/samples/python/plane_ar.py
  • If you are using Python:
    • Numpy array slices won't work as input because solvePnP requires contiguous arrays (enforced by the assertion using cv::Mat::checkVector() around line 55 of modules/3d/src/solvepnp.cpp version 2.4.9)
    • The P3P algorithm requires image points to be in an array of shape (N,1,2) due to its calling of undistortPoints (around line 75 of modules/3d/src/solvepnp.cpp version 2.4.9) which requires 2-channel information.
    • Thus, given some data D = np.array(...) where D.shape = (N,M), in order to use a subset of it as, e.g., imagePoints, one must effectively copy it into a new array: imagePoints = np.ascontiguousarray(D[:,:2]).reshape((N,1,2))
  • The methods SOLVEPNP_DLS and SOLVEPNP_UPNP cannot be used as the current implementations are unstable and sometimes give completely wrong results. If you pass one of these two flags, SOLVEPNP_EPNP method will be used instead.
  • The minimum number of points is 4 in the general case. In the case of SOLVEPNP_P3P and SOLVEPNP_AP3P methods, it is required to use exactly 4 points (the first 3 points are used to estimate all the solutions of the P3P problem, the last one is used to retain the best solution that minimizes the reprojection error).
  • With SOLVEPNP_ITERATIVE method and useExtrinsicGuess=true, the minimum number of points is 3 (3 points are sufficient to compute a pose but there are up to 4 solutions). The initial solution should be close to the global solution to converge.
  • With SOLVEPNP_IPPE input points must be >= 4 and object points must be coplanar.
  • With SOLVEPNP_IPPE_SQUARE this is a special case suitable for marker pose estimation. Number of input points must be 4. Object points must be defined in the following order:
    • point 0: [-squareLength / 2, squareLength / 2, 0]
    • point 1: [ squareLength / 2, squareLength / 2, 0]
    • point 2: [ squareLength / 2, -squareLength / 2, 0]
    • point 3: [-squareLength / 2, -squareLength / 2, 0]

◆ solvePnPRansac() [1/2]

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 
)
Python:
cv.solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvec[, tvec[, useExtrinsicGuess[, iterationsCount[, reprojectionError[, confidence[, inliers[, flags]]]]]]]]) -> retval, rvec, tvec, inliers
cv.solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvec[, tvec[, inliers[, params]]]]) -> retval, cameraMatrix, rvec, tvec, inliers

#include <opencv2/3d.hpp>

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

See also
Perspective-n-Point (PnP) pose computation
Parameters
objectPointsArray of object points in the object coordinate space, Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3d> can be also passed here.
imagePointsArray of corresponding image points, Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2d> can be also passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecOutput rotation vector (see Rodrigues ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system.
tvecOutput translation vector.
useExtrinsicGuessParameter used for SOLVEPNP_ITERATIVE. If true (1), the function uses the provided rvec and tvec values as initial approximations of the rotation and translation vectors, respectively, and further optimizes them.
iterationsCountNumber of iterations.
reprojectionErrorInlier threshold value used by the RANSAC procedure. The parameter value is the maximum allowed distance between the observed and computed point projections to consider it an inlier.
confidenceThe probability that the algorithm produces a useful result.
inliersOutput vector that contains indices of inliers in objectPoints and imagePoints .
flagsMethod for solving a PnP problem (see solvePnP ).

The function estimates an object pose given a set of object points, their corresponding image projections, as well as the camera intrinsic matrix and the distortion coefficients. This function finds such a pose that minimizes reprojection error, that is, the sum of squared distances between the observed projections imagePoints and the projected (using projectPoints ) objectPoints. The use of RANSAC makes the function resistant to outliers.

Note
  • An example of how to use solvePNPRansac for object detection can be found at opencv_source_code/samples/cpp/tutorial_code/3d/real_time_pose_estimation/
  • The default method used to estimate the camera pose for the Minimal Sample Sets step is SOLVEPNP_EPNP. Exceptions are:
  • The method used to estimate the camera pose using all the inliers is defined by the flags parameters unless it is equal to SOLVEPNP_P3P or SOLVEPNP_AP3P. In this case, the method SOLVEPNP_EPNP will be used instead.

◆ solvePnPRansac() [2/2]

bool cv::solvePnPRansac ( InputArray  objectPoints,
InputArray  imagePoints,
InputOutputArray  cameraMatrix,
InputArray  distCoeffs,
OutputArray  rvec,
OutputArray  tvec,
OutputArray  inliers,
const UsacParams params = UsacParams() 
)
Python:
cv.solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvec[, tvec[, useExtrinsicGuess[, iterationsCount[, reprojectionError[, confidence[, inliers[, flags]]]]]]]]) -> retval, rvec, tvec, inliers
cv.solvePnPRansac(objectPoints, imagePoints, cameraMatrix, distCoeffs[, rvec[, tvec[, inliers[, params]]]]) -> retval, cameraMatrix, rvec, tvec, inliers

#include <opencv2/3d.hpp>

◆ solvePnPRefineLM()

void cv::solvePnPRefineLM ( InputArray  objectPoints,
InputArray  imagePoints,
InputArray  cameraMatrix,
InputArray  distCoeffs,
InputOutputArray  rvec,
InputOutputArray  tvec,
TermCriteria  criteria = TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON) 
)
Python:
cv.solvePnPRefineLM(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec[, criteria]) -> rvec, tvec

#include <opencv2/3d.hpp>

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.

See also
Perspective-n-Point (PnP) pose computation
Parameters
objectPointsArray of object points in the object coordinate space, Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3d> can also be passed here.
imagePointsArray of corresponding image points, Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2d> can also be passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecInput/Output rotation vector (see Rodrigues ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system. Input values are used as an initial solution.
tvecInput/Output translation vector. Input values are used as an initial solution.
criteriaCriteria when to stop the Levenberg-Marquard iterative algorithm.

The function refines the object pose given at least 3 object points, their corresponding image projections, an initial solution for the rotation and translation vector, as well as the camera intrinsic matrix and the distortion coefficients. The function minimizes the projection error with respect to the rotation and the translation vectors, according to a Levenberg-Marquardt iterative minimization [174] [75] process.

◆ solvePnPRefineVVS()

void cv::solvePnPRefineVVS ( InputArray  objectPoints,
InputArray  imagePoints,
InputArray  cameraMatrix,
InputArray  distCoeffs,
InputOutputArray  rvec,
InputOutputArray  tvec,
TermCriteria  criteria = TermCriteria(TermCriteria::EPS+TermCriteria::COUNT, 20, FLT_EPSILON),
double  VVSlambda = 1 
)
Python:
cv.solvePnPRefineVVS(objectPoints, imagePoints, cameraMatrix, distCoeffs, rvec, tvec[, criteria[, VVSlambda]]) -> rvec, tvec

#include <opencv2/3d.hpp>

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.

See also
Perspective-n-Point (PnP) pose computation
Parameters
objectPointsArray of object points in the object coordinate space, Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3d> can also be passed here.
imagePointsArray of corresponding image points, Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2d> can also be passed here.
cameraMatrixInput camera intrinsic matrix \(\cameramatrix{A}\) .
distCoeffsInput vector of distortion coefficients \(\distcoeffs\). If the vector is NULL/empty, the zero distortion coefficients are assumed.
rvecInput/Output rotation vector (see Rodrigues ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system. Input values are used as an initial solution.
tvecInput/Output translation vector. Input values are used as an initial solution.
criteriaCriteria when to stop the Levenberg-Marquard iterative algorithm.
VVSlambdaGain for the virtual visual servoing control law, equivalent to the \(\alpha\) gain in the Damped Gauss-Newton formulation.

The function refines the object pose given at least 3 object points, their corresponding image projections, an initial solution for the rotation and translation vector, as well as the camera intrinsic matrix and the distortion coefficients. The function minimizes the projection error with respect to the rotation and the translation vectors, using a virtual visual servoing (VVS) [51] [178] scheme.

◆ triangleRasterize()

void cv::triangleRasterize ( InputArray  vertices,
InputArray  indices,
InputArray  colors,
InputOutputArray  colorBuf,
InputOutputArray  depthBuf,
InputArray  world2cam,
double  fovY,
double  zNear,
double  zFar,
const TriangleRasterizeSettings settings = TriangleRasterizeSettings() 
)
Python:
cv.triangleRasterize(vertices, indices, colors, colorBuf, depthBuf, world2cam, fovY, zNear, zFar[, settings]) -> colorBuf, depthBuf

#include <opencv2/3d.hpp>

Renders a set of triangles on a depth and color image.

Triangles can be drawn white (1.0, 1.0, 1.0), flat-shaded or with a color interpolation between vertices. In flat-shaded mode the 1st vertex color of each triangle is used to fill the whole triangle.

The world2cam is an inverted camera pose matrix in fact. It transforms vertices from world to camera coordinate system.

The camera coordinate system emulates the OpenGL's coordinate system having coordinate origin in a screen center, X axis pointing right, Y axis pointing up and Z axis pointing towards the viewer except that image is vertically flipped after the render. This means that all visible objects are placed in z-negative area, or exactly in -zNear > z > -zFar since zNear and zFar are positive. For example, at fovY = PI/2 the point (0, 1, -1) will be projected to (width/2, 0) screen point, (1, 0, -1) to (width/2 + height/2, height/2). Increasing fovY makes projection smaller and vice versa.

The function does not create or clear output images before the rendering. This means that it can be used for drawing over an existing image or for rendering a model into a 3D scene using pre-filled Z-buffer.

Empty scene results in a depth buffer filled by the maximum value since every pixel is infinitely far from the camera. Therefore, before rendering anything from scratch the depthBuf should be filled by zFar values (or by ones in INVDEPTH mode).

There are special versions of this function named triangleRasterizeDepth and triangleRasterizeColor for cases if a user needs a color image or a depth image alone; they may run slightly faster.

Parameters
verticesvertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
indicestriangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array. Should contain CV_32SC3 values or compatible
colorsper-vertex colors of CV_32FC3 type or compatible. Can be empty or the same size as vertices array. If the values are out of [0; 1] range, the result correctness is not guaranteed
colorBufan array representing the final rendered image. Should containt CV_32FC3 values and be the same size as depthBuf. Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
depthBufan array of floats containing resulting Z buffer. Should contain float values and be the same size as colorBuf. Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene. Empty scene corresponds to all values set to zFar (or to 1.0 in INVDEPTH mode)
world2cama 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
fovYfield of view in vertical direction, given in radians
zNearminimum Z value to render, everything closer is clipped
zFarmaximum Z value to render, everything farther is clipped
settingssee TriangleRasterizeSettings. By default the smooth shading is on, with CW culling and with disabled GL compatibility

◆ triangleRasterizeColor()

void cv::triangleRasterizeColor ( InputArray  vertices,
InputArray  indices,
InputArray  colors,
InputOutputArray  colorBuf,
InputArray  world2cam,
double  fovY,
double  zNear,
double  zFar,
const TriangleRasterizeSettings settings = TriangleRasterizeSettings() 
)
Python:
cv.triangleRasterizeColor(vertices, indices, colors, colorBuf, world2cam, fovY, zNear, zFar[, settings]) -> colorBuf

#include <opencv2/3d.hpp>

Overloaded version of triangleRasterize() with color-only rendering.

Parameters
verticesvertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
indicestriangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array. Should contain CV_32SC3 values or compatible
colorsper-vertex colors of CV_32FC3 type or compatible. Can be empty or the same size as vertices array. If the values are out of [0; 1] range, the result correctness is not guaranteed
colorBufan array representing the final rendered image. Should containt CV_32FC3 values and be the same size as depthBuf. Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene.
world2cama 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
fovYfield of view in vertical direction, given in radians
zNearminimum Z value to render, everything closer is clipped
zFarmaximum Z value to render, everything farther is clipped
settingssee TriangleRasterizeSettings. By default the smooth shading is on, with CW culling and with disabled GL compatibility

◆ triangleRasterizeDepth()

void cv::triangleRasterizeDepth ( InputArray  vertices,
InputArray  indices,
InputOutputArray  depthBuf,
InputArray  world2cam,
double  fovY,
double  zNear,
double  zFar,
const TriangleRasterizeSettings settings = TriangleRasterizeSettings() 
)
Python:
cv.triangleRasterizeDepth(vertices, indices, depthBuf, world2cam, fovY, zNear, zFar[, settings]) -> depthBuf

#include <opencv2/3d.hpp>

Overloaded version of triangleRasterize() with depth-only rendering.

Parameters
verticesvertices coordinates array. Should contain values of CV_32FC3 type or a compatible one (e.g. cv::Vec3f, etc.)
indicestriangle vertices index array, 3 per triangle. Each index indicates a vertex in a vertices array. Should contain CV_32SC3 values or compatible
depthBufan array of floats containing resulting Z buffer. Should contain float values and be the same size as colorBuf. Not cleared before rendering, i.e. the content is reused as there is some pre-rendered scene. Empty scene corresponds to all values set to zFar (or to 1.0 in INVDEPTH mode)
world2cama 4x3 or 4x4 float or double matrix containing inverted (sic!) camera pose
fovYfield of view in vertical direction, given in radians
zNearminimum Z value to render, everything closer is clipped
zFarmaximum Z value to render, everything farther is clipped
settingssee TriangleRasterizeSettings. By default the smooth shading is on, with CW culling and with disabled GL compatibility

◆ triangulatePoints()

void cv::triangulatePoints ( InputArray  projMatr1,
InputArray  projMatr2,
InputArray  projPoints1,
InputArray  projPoints2,
OutputArray  points4D 
)
Python:
cv.triangulatePoints(projMatr1, projMatr2, projPoints1, projPoints2[, points4D]) -> points4D

#include <opencv2/3d.hpp>

This function reconstructs 3-dimensional points (in homogeneous coordinates) by using their observations with a stereo camera.

Parameters
projMatr13x4 projection matrix of the first camera, i.e. this matrix projects 3D points given in the world's coordinate system into the first image.
projMatr23x4 projection matrix of the second camera, i.e. this matrix projects 3D points given in the world's coordinate system into the second image.
projPoints12xN array of feature points in the first image. In the case of the c++ version, it can be also a vector of feature points or two-channel matrix of size 1xN or Nx1.
projPoints22xN array of corresponding points in the second image. In the case of the c++ version, it can be also a vector of feature points or two-channel matrix of size 1xN or Nx1.
points4D4xN array of reconstructed points in homogeneous coordinates. These points are returned in the world's coordinate system.
Note
Keep in mind that all input data should be of float type in order for this function to work.
If the projection matrices from stereoRectify are used, then the returned points are represented in the first camera's rectified coordinate system.
See also
reprojectImageTo3D

◆ undistort()

void cv::undistort ( InputArray  src,
OutputArray  dst,
InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  newCameraMatrix = noArray() 
)
Python:
cv.undistort(src, cameraMatrix, distCoeffs[, dst[, newCameraMatrix]]) -> dst

#include <opencv2/3d.hpp>

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, \(f_x, f_y, c_x\) and \(c_y\) need to be scaled accordingly, while the distortion coefficients remain the same.

Parameters
srcInput (distorted) image.
dstOutput (corrected) image that has the same size and type as src .
cameraMatrixInput camera matrix \(A = \vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) .
distCoeffsInput vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
newCameraMatrixCamera matrix of the distorted image. By default, it is the same as cameraMatrix but you may additionally scale and shift the result by using a different matrix.

◆ undistortImagePoints()

void cv::undistortImagePoints ( InputArray  src,
OutputArray  dst,
InputArray  cameraMatrix,
InputArray  distCoeffs,
TermCriteria  = TermCriteria(TermCriteria::MAX_ITER+TermCriteria::EPS, 5, 0.01) 
)
Python:
cv.undistortImagePoints(src, cameraMatrix, distCoeffs[, dst[, arg1]]) -> dst

#include <opencv2/3d.hpp>

Compute undistorted image points position.

Parameters
srcObserved points position, 2xN/Nx2 1-channel or 1xN/Nx1 2-channel (CV_32FC2 or CV_64FC2) (or vector<Point2f> ).
dstOutput undistorted points position (1xN/Nx1 2-channel or vector<Point2f> ).
cameraMatrixCamera matrix \(\vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) .
distCoeffsDistortion coefficients

◆ undistortPoints()

void cv::undistortPoints ( InputArray  src,
OutputArray  dst,
InputArray  cameraMatrix,
InputArray  distCoeffs,
InputArray  R = noArray(),
InputArray  P = noArray(),
TermCriteria  criteria = TermCriteria(TermCriteria::MAX_ITER, 5, 0.01) 
)
Python:
cv.undistortPoints(src, cameraMatrix, distCoeffs[, dst[, R[, P[, criteria]]]]) -> dst

#include <opencv2/3d.hpp>

Computes the ideal point coordinates from the observed point coordinates.

The function is similar to undistort and initUndistortRectifyMap but it operates on a sparse set of points instead of a raster image. Also the function performs a reverse transformation to projectPoints. In case of a 3D object, it does not reconstruct its 3D coordinates, but for a planar object, it does, up to a translation vector, if the proper R is specified.

For each observed point coordinate \((u, v)\) the function computes:

\[ \begin{array}{l} x^{"} \leftarrow (u - c_x)/f_x \\ y^{"} \leftarrow (v - c_y)/f_y \\ (x',y') = undistort(x^{"},y^{"}, \texttt{distCoeffs}) \\ {[X\,Y\,W]} ^T \leftarrow R*[x' \, y' \, 1]^T \\ x \leftarrow X/W \\ y \leftarrow Y/W \\ \text{only performed if P is specified:} \\ u' \leftarrow x {f'}_x + {c'}_x \\ v' \leftarrow y {f'}_y + {c'}_y \end{array} \]

where undistort is an approximate iterative algorithm that estimates the normalized original point coordinates out of the normalized distorted point coordinates ("normalized" means that the coordinates do not depend on the camera matrix).

The function can be used for both a stereo camera head or a monocular camera (when R is empty).

Parameters
srcObserved point coordinates, 2xN/Nx2 1-channel or 1xN/Nx1 2-channel (CV_32FC2 or CV_64FC2) (or vector<Point2f> ).
dstOutput ideal point coordinates (1xN/Nx1 2-channel or vector<Point2f> ) after undistortion and reverse perspective transformation. If matrix P is identity or omitted, dst will contain normalized point coordinates.
cameraMatrixCamera matrix \(\vecthreethree{f_x}{0}{c_x}{0}{f_y}{c_y}{0}{0}{1}\) .
distCoeffsInput vector of distortion coefficients \((k_1, k_2, p_1, p_2[, k_3[, k_4, k_5, k_6[, s_1, s_2, s_3, s_4[, \tau_x, \tau_y]]]])\) of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
RRectification transformation in the object space (3x3 matrix). R1 or R2 computed by stereoRectify can be passed here. If the matrix is empty, the identity transformation is used.
PNew camera matrix (3x3) or new projection matrix (3x4) \(\begin{bmatrix} {f'}_x & 0 & {c'}_x & t_x \\ 0 & {f'}_y & {c'}_y & t_y \\ 0 & 0 & 1 & t_z \end{bmatrix}\). P1 or P2 computed by stereoRectify can be passed here. If the matrix is empty, the identity new camera matrix is used.
criteriatermination criteria for the iterative point undistortion algorithm

◆ voxelGridSampling()

int cv::voxelGridSampling ( OutputArray  sampled_point_flags,
InputArray  input_pts,
float  length,
float  width,
float  height 
)

#include <opencv2/3d/ptcloud.hpp>

Point cloud sampling by Voxel Grid filter downsampling.

Creates a 3D voxel grid (a set of tiny 3D boxes in space) over the input point cloud data, in each voxel (i.e., 3D box), all the points present will be approximated (i.e., downsampled) with the point closest to their centroid.

Parameters
[out]sampled_point_flagsFlags of the sampled point, (pass in std::vector<int> or std::vector<char> etc.) sampled_point_flags[i] is 1 means i-th point selected, 0 means it is not selected.
input_ptsOriginal point cloud, vector of Point3 or Mat of size Nx3/3xN.
lengthGrid length.
widthGrid width.
heightGrid height.
Returns
The number of points actually sampled.