Finds the camera pose of 2D-3D points correspondences based on opengv Universal Perspective-n-Point algorithm. UUID: 922e9db6-e424-4518-ad26-31201471ff00
More...
#include <PoseEstimationUPnp.h>
|
| PoseEstimationUPnp () |
| PoseEstimationUPnp constructor;.
|
|
| ~PoseEstimationUPnp () |
| PoseEstimationUPnp destructor;.
|
|
FrameworkReturnCode | estimate (const std::vector< datastructure::Point2Df > &imagePoints, const std::vector< datastructure::Point3Df > &worldPoints, datastructure::Transform3Df &pose, const datastructure::Transform3Df initialPose=datastructure::Transform3Df::Identity()) override |
| Estimates camera pose from a set of 2D image points of their corresponding 3D world points. More...
|
|
void | setCameraParameters (const datastructure::CamCalibration &intrinsicParams, const datastructure::CamDistortion &distorsionParams) override |
| this method is used to set intrinsic parameters and distorsion of the camera More...
|
|
void | unloadComponent () override final |
|
Finds the camera pose of 2D-3D points correspondences based on opengv Universal Perspective-n-Point algorithm. UUID: 922e9db6-e424-4518-ad26-31201471ff00
◆ estimate()
FrameworkReturnCode SolAR::MODULES::OPENGV::PoseEstimationUPnp::estimate |
( |
const std::vector< datastructure::Point2Df > & |
imagePoints, |
|
|
const std::vector< datastructure::Point3Df > & |
worldPoints, |
|
|
datastructure::Transform3Df & |
pose, |
|
|
const datastructure::Transform3Df |
initialPose = datastructure::Transform3Df::Identity() |
|
) |
| |
|
override |
Estimates camera pose from a set of 2D image points of their corresponding 3D world points.
- Parameters
-
[in] | imagePoints,set | of 2d_points seen in view_1. |
[in] | worldPoints,set | of 3d_points corresponding to view_1. |
[out] | pose,camera | pose (pose the camera defined in world corrdinate system) expressed as a Transform3D. |
[in] | initialPose | (Optional), a tranfsform3D to initialize the pose (reducing the convergence time and improving its success). If your world points are planar, do not use this argument. |
◆ setCameraParameters()
void SolAR::MODULES::OPENGV::PoseEstimationUPnp::setCameraParameters |
( |
const datastructure::CamCalibration & |
intrinsicParams, |
|
|
const datastructure::CamDistortion & |
distorsionParams |
|
) |
| |
|
override |
this method is used to set intrinsic parameters and distorsion of the camera
- Parameters
-
[in] | Camera | calibration matrix parameters. |
[in] | Camera | distorsion parameters. |
The documentation for this class was generated from the following file: