|
NVIDIA DeepStream SDK API Reference
|
7.0 Release
|
Go to the documentation of this file.
51 const float outlierRatio,
52 const uint32_t sampleSize);
91 const uint32_t numExperiments,
const double ransacThreshold,
92 const uint32_t maxTopPoses,
const uint32_t seed);
111 const Pose3d& initialGuess,
size_t iterations = 5);
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 o...
std::vector< uint32_t > inliers
Implementation of Array class.
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.
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 uncontamina...
A struct to describe the Pose hypothesis returned by RANSAC-based pose estimation.
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 cor...