Classes | |
| class | Affine3DEstimatorCallback |
| class | EMEstimatorCallback |
| class | LMeDSPointSetRegistrator |
| class | LMSolver |
| class | PnPRansacCallback |
| class | PointSetRegistrator |
| class | RANSACPointSetRegistrator |
Functions | |
| template<typename T > | |
| int | compressElems (T *ptr, const uchar *mask, int mstep, int count) |
| cv::Ptr< PointSetRegistrator > | createLMeDSPointSetRegistrator (const cv::Ptr< PointSetRegistrator::Callback > &cb, int modelPoints, double confidence=0.99, int maxIters=1000) |
| Ptr< PointSetRegistrator > | createLMeDSPointSetRegistrator (const Ptr< PointSetRegistrator::Callback > &_cb, int _modelPoints, double _confidence, int _maxIters) |
| cv::Ptr< LMSolver > | createLMSolver (const cv::Ptr< LMSolver::Callback > &cb, int maxIters) |
| cv::Ptr< PointSetRegistrator > | createRANSACPointSetRegistrator (const cv::Ptr< PointSetRegistrator::Callback > &cb, int modelPoints, double threshold, double confidence=0.99, int maxIters=1000) |
| Ptr< PointSetRegistrator > | createRANSACPointSetRegistrator (const Ptr< PointSetRegistrator::Callback > &_cb, int _modelPoints, double _threshold, double _confidence, int _maxIters) |
| void | decomposeEssentialMat (InputArray _E, OutputArray _R1, OutputArray _R2, OutputArray _t) |
| cv::Mat | findEssentialMat (cv::InputArray _points1, cv::InputArray _points2, cv::InputArray _cameraMatrix, int method, double prob, double threshold, cv::OutputArray _mask=cv::noArray()) |
| cv::Mat | findEssentialMat (InputArray _points1, InputArray _points2, InputArray _cameraMatrix, int method, double prob, double threshold, OutputArray _mask) |
| int | RANSACUpdateNumIters (double p, double ep, int modelPoints, int maxIters) |
| int | recoverPose (cv::InputArray E, cv::InputArray _points1, cv::InputArray _points2, cv::InputArray _cameraMatrix, cv::OutputArray _R, cv::OutputArray _t, double distanceThresh, cv::InputOutputArray _mask, cv::OutputArray triangulatedPoints) |
| int | recoverPose (InputArray E, InputArray _points1, InputArray _points2, InputArray _cameraMatrix, OutputArray _R, OutputArray _t, double distanceThresh, InputOutputArray _mask, OutputArray triangulatedPoints) |
| bool | solvePnPRansac (cv::InputArray objectPoints, cv::InputArray imagePoints, cv::InputArray cameraMatrix, cv::InputArray distCoeffs, cv::OutputArray rvec, cv::OutputArray tvec, bool useExtrinsicGuess=false, int iterationsCount=100, float reprojectionError=8.0, double confidence=0.99, cv::OutputArray inliers=cv::noArray(), int flags=CV_ITERATIVE) |
| Finds an object pose from 3D-2D point correspondences using the RANSAC scheme. More... | |
| bool | solvePnPRansac (InputArray _opoints, InputArray _ipoints, InputArray _cameraMatrix, InputArray _distCoeffs, OutputArray _rvec, OutputArray _tvec, bool useExtrinsicGuess, int iterationsCount, float reprojectionError, double confidence, OutputArray _inliers, int flags) |
|
inline |
Definition at line 141 of file solvepnp.h.
| cv::Ptr<PointSetRegistrator> cv3::createLMeDSPointSetRegistrator | ( | const cv::Ptr< PointSetRegistrator::Callback > & | cb, |
| int | modelPoints, | ||
| double | confidence = 0.99, |
||
| int | maxIters = 1000 |
||
| ) |
| Ptr<PointSetRegistrator> cv3::createLMeDSPointSetRegistrator | ( | const Ptr< PointSetRegistrator::Callback > & | _cb, |
| int | _modelPoints, | ||
| double | _confidence, | ||
| int | _maxIters | ||
| ) |
Definition at line 555 of file solvepnp.cpp.
| cv::Ptr<LMSolver> cv3::createLMSolver | ( | const cv::Ptr< LMSolver::Callback > & | cb, |
| int | maxIters | ||
| ) |
| cv::Ptr<PointSetRegistrator> cv3::createRANSACPointSetRegistrator | ( | const cv::Ptr< PointSetRegistrator::Callback > & | cb, |
| int | modelPoints, | ||
| double | threshold, | ||
| double | confidence = 0.99, |
||
| int | maxIters = 1000 |
||
| ) |
| Ptr<PointSetRegistrator> cv3::createRANSACPointSetRegistrator | ( | const Ptr< PointSetRegistrator::Callback > & | _cb, |
| int | _modelPoints, | ||
| double | _threshold, | ||
| double | _confidence, | ||
| int | _maxIters | ||
| ) |
Definition at line 546 of file solvepnp.cpp.
| void cv3::decomposeEssentialMat | ( | InputArray | _E, |
| OutputArray | _R1, | ||
| OutputArray | _R2, | ||
| OutputArray | _t | ||
| ) |
Definition at line 453 of file five-point.cpp.
| cv::Mat cv3::findEssentialMat | ( | cv::InputArray | _points1, |
| cv::InputArray | _points2, | ||
| cv::InputArray | _cameraMatrix, | ||
| int | method, | ||
| double | prob, | ||
| double | threshold, | ||
| cv::OutputArray | _mask = cv::noArray() |
||
| ) |
| cv::Mat cv3::findEssentialMat | ( | InputArray | _points1, |
| InputArray | _points2, | ||
| InputArray | _cameraMatrix, | ||
| int | method, | ||
| double | prob, | ||
| double | threshold, | ||
| OutputArray | _mask | ||
| ) |
Definition at line 405 of file five-point.cpp.
| int cv3::RANSACUpdateNumIters | ( | double | p, |
| double | ep, | ||
| int | modelPoints, | ||
| int | maxIters | ||
| ) |
Definition at line 216 of file solvepnp.cpp.
| int cv3::recoverPose | ( | cv::InputArray | E, |
| cv::InputArray | _points1, | ||
| cv::InputArray | _points2, | ||
| cv::InputArray | _cameraMatrix, | ||
| cv::OutputArray | _R, | ||
| cv::OutputArray | _t, | ||
| double | distanceThresh, | ||
| cv::InputOutputArray | _mask, | ||
| cv::OutputArray | triangulatedPoints | ||
| ) |
| int cv3::recoverPose | ( | InputArray | E, |
| InputArray | _points1, | ||
| InputArray | _points2, | ||
| InputArray | _cameraMatrix, | ||
| OutputArray | _R, | ||
| OutputArray | _t, | ||
| double | distanceThresh, | ||
| InputOutputArray | _mask, | ||
| OutputArray | triangulatedPoints | ||
| ) |
Definition at line 477 of file five-point.cpp.
| bool cv3::solvePnPRansac | ( | cv::InputArray | objectPoints, |
| cv::InputArray | imagePoints, | ||
| cv::InputArray | cameraMatrix, | ||
| cv::InputArray | distCoeffs, | ||
| cv::OutputArray | rvec, | ||
| cv::OutputArray | tvec, | ||
| bool | useExtrinsicGuess = false, |
||
| int | iterationsCount = 100, |
||
| float | reprojectionError = 8.0, |
||
| double | confidence = 0.99, |
||
| cv::OutputArray | inliers = cv::noArray(), |
||
| int | flags = CV_ITERATIVE |
||
| ) |
Finds an object pose from 3D-2D point correspondences using the RANSAC scheme.
| objectPoints | Array of object points in the object coordinate space, 3xN/Nx3 1-channel or 1xN/Nx1 3-channel, where N is the number of points. vector<Point3f> can be also passed here. |
| imagePoints | Array of corresponding image points, 2xN/Nx2 1-channel or 1xN/Nx1 2-channel, where N is the number of points. vector<Point2f> can be also passed here. |
| cameraMatrix | Input camera matrix . |
| distCoeffs | Input vector of distortion coefficients 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 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. |
| iterationsCount | Number of iterations. |
| reprojectionError | Inlier 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. |
| confidence | The probability that the algorithm produces a useful result. |
| inliers | Output vector that contains indices of inliers in objectPoints and imagePoints . |
| flags | Method 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 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.
| bool cv3::solvePnPRansac | ( | InputArray | _opoints, |
| InputArray | _ipoints, | ||
| InputArray | _cameraMatrix, | ||
| InputArray | _distCoeffs, | ||
| OutputArray | _rvec, | ||
| OutputArray | _tvec, | ||
| bool | useExtrinsicGuess, | ||
| int | iterationsCount, | ||
| float | reprojectionError, | ||
| double | confidence, | ||
| OutputArray | _inliers, | ||
| int | flags | ||
| ) |
Definition at line 112 of file solvepnp.cpp.