Data Structures | |
struct | PoseHypothesis |
A struct to describe the Pose hypothesis returned by RANSAC-based pose estimation. More... | |
Functions | |
uint32_t | EvaluateRansacFormula (const float successRate, const float outlierRatio, const uint32_t sampleSize) |
A function to calculate the number of RANSAC rounds necessary to sample at least a single uncontaminated sample set with a certain success rate given the expected ratio of outliers. More... | |
Pose3d | ComputeCameraPoseEpnp (const Array< Vector3d > &points3, const Array< Vector2d > &points2, const Vector2d focal, const Vector2d principal) |
A function to compute the pose of a camera give the camera instrinsics and at least 6 2D-3D point correspondences without outliers. More... | |
std::vector< PoseHypothesis > | ComputeCameraPoseEpnpRansac (const Array< Vector3d > &points3, const Array< Vector2d > &points2, const Vector2d focal, const Vector2d principal, const uint32_t numExperiments, const double ransacThreshold, const uint32_t maxTopPoses, const uint32_t seed) |
A function to compute the pose of a pinhole camera from at least 6 2D-3D point correspondences with outliers using RANSAC. More... | |
Pose3d | ComputeCameraPoseIterativePnp (const Array< Vector3d > &points3, const Array< Vector2d > &points2, const Vector2d focal, const Vector2d principal, const Pose3d &initialGuess, size_t iterations=5) |
A function to compute the pose of a camera give the camera instrinsics iteratively. More... | |
Pose3d cvcore::vision3d::ComputeCameraPoseEpnp | ( | const Array< Vector3d > & | points3, |
const Array< Vector2d > & | points2, | ||
const Vector2d | focal, | ||
const Vector2d | principal | ||
) |
A function to compute the pose of a camera give the camera instrinsics and at least 6 2D-3D point correspondences without outliers.
Assumptions No lens distortions, you need to un-distort points in advance. Using Right handed coordinate system.
points3 | Array of 3d world coordinates |
points2 | Array of 2d projection points in pixels. |
focal | Focal length in horizontal axis and vertical axis in pixel units. |
principal | Principal point / image center in x axis and y axis. |
std::vector<PoseHypothesis> cvcore::vision3d::ComputeCameraPoseEpnpRansac | ( | const Array< Vector3d > & | points3, |
const Array< Vector2d > & | points2, | ||
const Vector2d | focal, | ||
const Vector2d | principal, | ||
const uint32_t | numExperiments, | ||
const double | ransacThreshold, | ||
const uint32_t | maxTopPoses, | ||
const uint32_t | seed | ||
) |
A function to compute the pose of a pinhole camera from at least 6 2D-3D point correspondences with outliers using RANSAC.
points3 | Array of 3d world coordinates |
points2 | Array of 2d projection points in pixels. |
focal | Focal length in horizontal axis and vertical axis in pixel units. |
principal | Principal point / image center in x axis and y axis. |
numExperiments | Number of RANSAC iterations or experiments to run. |
ransacThreshold | RANSAC threshold in terms of reprojection error in pixels. |
maxTopPoses | Maximum number of pose hypotheses to return. |
seed | Integer seed for random number generation. |
Pose3d cvcore::vision3d::ComputeCameraPoseIterativePnp | ( | const Array< Vector3d > & | points3, |
const Array< Vector2d > & | points2, | ||
const Vector2d | focal, | ||
const Vector2d | principal, | ||
const Pose3d & | initialGuess, | ||
size_t | iterations = 5 |
||
) |
A function to compute the pose of a camera give the camera instrinsics iteratively.
Assumptions No lens distortions, you need to un-distort points in advance. Using Right handed coordinate system.
points3 | Array of 3d world coordinates |
points2 | Array of 2d projection points in pixels. |
focal | Focal length in horizontal axis and vertical axis in pixel units. |
principal | Principal point / image center in x axis and y axis. |
initialGuess | Inital condition for the Iterative solver. |
iterations | Iterations of Iterative solver. |
uint32_t cvcore::vision3d::EvaluateRansacFormula | ( | const float | successRate, |
const float | outlierRatio, | ||
const uint32_t | sampleSize | ||
) |
A function to calculate the number of RANSAC rounds necessary to sample at least a single uncontaminated sample set with a certain success rate given the expected ratio of outliers.
successRate | : Required probability in the range (0,0.9999] of finding the solution. As success_rate tends to 1.0, the number of experiments tends to Inf. |
outlierRatio | : Maximum expected ratio of outliers in the open interval [0,0.9]. |
sampleSize | : The minimum number of samples necessary to fit the model (at least 1). |