Solar
Public Member Functions | List of all members
SolAR::MODULES::OPENCV::SolARPoseEstimationSACPnpOpencv Class Reference

Finds the camera pose of 2D-3D points correspondences based on opencv Perspective-n-Points algorithm using Ransac method. UUID: 4d369049-809c-4e99-9994-5e8167bab808 More...

#include <SolARPoseEstimationSACPnpOpencv.h>

Inheritance diagram for SolAR::MODULES::OPENCV::SolARPoseEstimationSACPnpOpencv:
Inheritance graph
[legend]
Collaboration diagram for SolAR::MODULES::OPENCV::SolARPoseEstimationSACPnpOpencv:
Collaboration graph
[legend]

Public Member Functions

 SolARPoseEstimationSACPnpOpencv ()
 SolARPoseEstimationSACPnpOpencv constructor;.
 
 ~SolARPoseEstimationSACPnpOpencv () override
 SolARPoseEstimationSACPnpOpencv 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()) 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
 

Detailed Description

Finds the camera pose of 2D-3D points correspondences based on opencv Perspective-n-Points algorithm using Ransac method. UUID: 4d369049-809c-4e99-9994-5e8167bab808

Properties
iterationsCount number of iterations
type: int; range : [0..MAX INT]; default: 1000
reprojError 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
type: float; range : [0..MAX FLOAT]; default: 4.f
confidence the probability that the algorithm produces a useful result
type: float; range : [0..1]; default: 0.99f
minNbInliers the minimum of number of inliers to valid a good pose estimation
type: int; range : [0..MAX INT]; default: 10
method the method for solving the PnP problem (ITERATIVE, P3P, AP3P, EPNP, DLS, UPNP, IPPE, IPPE_SQUARE)
type: string; default: "ITERATIVE"

Member Function Documentation

◆ estimate()

FrameworkReturnCode SolAR::MODULES::OPENCV::SolARPoseEstimationSACPnpOpencv::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() 
)
override

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]inliersindices of inlier correspondences.
[out]pose,camerapose (pose of the camera defined in world corrdinate system) expressed as a Transform3D.
[in]initialPose(Optional), a transform3D to initialize the pose (reducing the convergence time and improving its success).

◆ setCameraParameters()

void SolAR::MODULES::OPENCV::SolARPoseEstimationSACPnpOpencv::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: