Solar
Public Member Functions | List of all members
SolAR::MODULES::OPENGV::PoseEstimationSACEPnp Class Reference

Finds the camera pose of 2D-3D points correspondences based on opengv Efficient Perspective-n-Point algorithm with a RANdom SAmple Consensus. UUID: a2c38e05-40d9-47fc-aad4-1ea2255333d5 More...

#include <PoseEstimationSACEPnp.h>

Inheritance diagram for SolAR::MODULES::OPENGV::PoseEstimationSACEPnp:
Inheritance graph
[legend]
Collaboration diagram for SolAR::MODULES::OPENGV::PoseEstimationSACEPnp:
Collaboration graph
[legend]

Public Member Functions

 PoseEstimationSACEPnp ()
 SolARPoseEstimationSACEPnp constructor;.
 
 ~PoseEstimationSACEPnp ()
 SolARPoseEstimationSACEPnp destructor;.
 
FrameworkReturnCode estimate (const std::vector< datastructure::Point2Df > &imagePoints, const std::vector< datastructure::Point3Df > &worldPoints, std::vector< uint32_t > &inliers, datastructure::Transform3Df &pose, const datastructure::Transform3Df initialPose=datastructure::Transform3Df::Identity())
 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
 

Detailed Description

Finds the camera pose of 2D-3D points correspondences based on opengv Efficient Perspective-n-Point algorithm with a RANdom SAmple Consensus. UUID: a2c38e05-40d9-47fc-aad4-1ea2255333d5

Member Function Documentation

◆ estimate()

FrameworkReturnCode SolAR::MODULES::OPENGV::PoseEstimationSACEPnp::estimate ( const std::vector< datastructure::Point2Df > &  imagePoints,
const std::vector< datastructure::Point3Df > &  worldPoints,
std::vector< uint32_t > &  inliers,
datastructure::Transform3Df &  pose,
const datastructure::Transform3Df  initialPose = datastructure::Transform3Df::Identity() 
)

Estimates camera pose from a set of 2D image points of their corresponding 3D world points.

Parameters
[in]imagePoints,setof 2d_points seen in view_1.
[in]worldPoints,setof 3d_points corresponding to view_1.
[out]pose,camerapose (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::PoseEstimationSACEPnp::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]Cameracalibration matrix parameters.
[in]Cameradistorsion parameters.

The documentation for this class was generated from the following file: