pub fn solve_pnp(
object_points: &impl ToInputArray,
image_points: &impl ToInputArray,
camera_matrix: &impl ToInputArray,
dist_coeffs: &impl ToInputArray,
rvec: &mut impl ToOutputArray,
tvec: &mut impl ToOutputArray,
use_extrinsic_guess: bool,
flags: i32,
) -> Result<bool>
Expand description
Finds an object pose from 3D-2D point correspondences.
§See also
[calib3d_solvePnP]
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
- objectPoints: Array 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.
- imagePoints: Array 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.
- cameraMatrix: Input camera intrinsic matrix
.
- distCoeffs: Input vector of distortion coefficients
. If the vector is NULL/empty, the zero distortion coefficients are assumed.
- rvec: Output rotation vector (see [Rodrigues] ) that, together with tvec, brings points from the model coordinate system to the camera coordinate system.
- tvec: Output translation vector.
- useExtrinsicGuess: Parameter 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.
- flags: Method for solving a PnP problem: see [calib3d_solvePnP_flags]
More information about Perspective-n-Points is described in [calib3d_solvePnP]
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/calib3d/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 undistort_points (around line 75 of modules/calib3d/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]
- With SOLVEPNP_SQPNP input points must be >= 3
§C++ default parameters
- use_extrinsic_guess: false
- flags: SOLVEPNP_ITERATIVE