[][src]Function opencv::calib3d::solve_pnp

pub fn solve_pnp(
    object_points: &dyn ToInputArray,
    image_points: &dyn ToInputArray,
    camera_matrix: &dyn ToInputArray,
    dist_coeffs: &dyn ToInputArray,
    rvec: &mut dyn ToOutputArray,
    tvec: &mut dyn ToOutputArray,
    use_extrinsic_guess: bool,
    flags: i32
) -> Result<bool>

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

  • P3P methods (@ref SOLVEPNP_P3P, @ref SOLVEPNP_AP3P): need 4 input points to return a unique solution.
  • @ref SOLVEPNP_IPPE Input points must be >= 4 and object points must be coplanar.
  • @ref 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 matrix inline formula .
  • distCoeffs: Input vector of distortion coefficients inline formula of 4, 5, 8, 12 or 14 elements. If the vector is NULL/empty, the zero distortion coefficients are assumed.
  • rvec: Output rotation vector (see @ref 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:
  • SOLVEPNP_ITERATIVE Iterative method is based on a Levenberg-Marquardt optimization. In this case the 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 .
  • 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" (gao2003complete). In this case the function requires exactly four object and image points.
  • SOLVEPNP_AP3P Method is based on the paper of T. Ke, S. Roumeliotis "An Efficient Algebraic Solution to the Perspective-Three-Point Problem" (Ke17). In this case the function requires exactly four object and image points.
  • SOLVEPNP_EPNP Method has been introduced by F. Moreno-Noguer, V. Lepetit and P. Fua in the paper "EPnP: Efficient Perspective-n-Point Camera Pose Estimation" (lepetit2009epnp).
  • SOLVEPNP_DLS Method is based on the paper of J. Hesch and S. Roumeliotis. "A Direct Least-Squares (DLS) Method for PnP" (hesch2011direct).
  • SOLVEPNP_UPNP Method is based on the paper of A. Penate-Sanchez, J. Andrade-Cetto, F. Moreno-Noguer. "Exhaustive Linearization for Robust Camera Pose and Focal Length Estimation" (penate2013exhaustive). In this case the function also estimates the parameters inline formula and inline formula assuming that both have the same value. Then the cameraMatrix is updated with the estimated focal length.
  • SOLVEPNP_IPPE Method is based on the paper of T. Collins and A. Bartoli. "Infinitesimal Plane-Based Pose Estimation" (Collins14). This method requires coplanar object points.
  • SOLVEPNP_IPPE_SQUARE Method is based on the paper of Toby Collins and Adrien Bartoli. "Infinitesimal Plane-Based Pose Estimation" (Collins14). This method is suitable for marker pose estimation. It requires 4 coplanar object points 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]

The function estimates the object pose given a set of object points, their corresponding image projections, as well as the camera matrix and the distortion coefficients, see the figure below (more precisely, the X-axis of the camera frame is pointing to the right, the Y-axis downward and the Z-axis forward).

Points expressed in the world frame inline formula are projected into the image plane inline formula using the perspective projection model inline formula and the camera intrinsic parameters matrix inline formula:

block formula

The estimated pose is thus the rotation (rvec) and the translation (tvec) vectors that allow transforming a 3D point expressed in the world frame into the camera frame:

block formula

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 cv::undistortPoints (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]

C++ default parameters

  • use_extrinsic_guess: false
  • flags: SOLVEPNP_ITERATIVE