Solar
Public Member Functions | List of all members
SolAR::api::solver::pose::I3DTransformFinderFrom2D2D Class Referenceabstract

Finds the 3D transform between two cameras knowing the keypoints that match between them. UUID: 6063a606-9d30-11e8-98d0-529269fb1459 More...

#include <I3DTransformFinderFrom2D2D.h>

Inheritance diagram for SolAR::api::solver::pose::I3DTransformFinderFrom2D2D:
Inheritance graph
[legend]
Collaboration diagram for SolAR::api::solver::pose::I3DTransformFinderFrom2D2D:
Collaboration graph
[legend]

Public Member Functions

 I3DTransformFinderFrom2D2D ()=default
 I3DTransformFinderFrom2D2D default constructor.
 
virtual ~I3DTransformFinderFrom2D2D ()=default
 I3DTransformFinderFrom2D2D default destructor.
 
virtual void setCameraParameters (const SolAR::datastructure::CamCalibration &intrinsicParams, const SolAR::datastructure::CamDistortion &distorsionParams)=0
 this method is used to set intrinsic parameters and distorsion of the camera More...
 
virtual FrameworkReturnCode estimate (const std::vector< SolAR::datastructure::Point2Df > &pointsView1, const std::vector< SolAR::datastructure::Point2Df > &pointsView2, const SolAR::datastructure::Transform3Df &poseView1, SolAR::datastructure::Transform3Df &poseView2, std::vector< SolAR::datastructure::DescriptorMatch > &inlierMatches)=0
 Estimates camera pose from a set of 2D points of the first image which match with a set of 2D points of the second image. More...
 
virtual FrameworkReturnCode estimate (const std::vector< SolAR::datastructure::Keypoint > &pointsView1, const std::vector< SolAR::datastructure::Keypoint > &pointsView2, const SolAR::datastructure::Transform3Df &poseView1, SolAR::datastructure::Transform3Df &poseView2, std::vector< SolAR::datastructure::DescriptorMatch > &inlierMatches)=0
 Estimates camera pose from a set of keypoints of the first image which match with a set of keypoints of the second image. More...
 

Detailed Description

Finds the 3D transform between two cameras knowing the keypoints that match between them. UUID: 6063a606-9d30-11e8-98d0-529269fb1459

Member Function Documentation

◆ estimate() [1/2]

virtual FrameworkReturnCode SolAR::api::solver::pose::I3DTransformFinderFrom2D2D::estimate ( const std::vector< SolAR::datastructure::Keypoint > &  pointsView1,
const std::vector< SolAR::datastructure::Keypoint > &  pointsView2,
const SolAR::datastructure::Transform3Df poseView1,
SolAR::datastructure::Transform3Df poseView2,
std::vector< SolAR::datastructure::DescriptorMatch > &  inlierMatches 
)
pure virtual

Estimates camera pose from a set of keypoints of the first image which match with a set of keypoints of the second image.

Parameters
[in]pointsView1Set of keypoints seen in view 1.
[in]pointsView2Set of keypoints seen in view 2 and matching with the 2D points of the view 1.
[in]poseView1Camera pose (3D transform of the camera of the view1 defined in world corrdinate system).
[out]poseView2Camera pose (3D transform of the camera of the view2 defined in world corrdinate system).
[in,out]inlierMatchesa vector of matches that will be used for the pose estimation. This vector wll be updates as some input matches will be considered as outliers. If this vector is empty, we consider that the ith point of pointsView1 matches with the ith point of pointsView2.
Returns
FrameworkReturnCode::SUCCESS if succeed, else FrameworkReturnCode::_ERROR

◆ estimate() [2/2]

virtual FrameworkReturnCode SolAR::api::solver::pose::I3DTransformFinderFrom2D2D::estimate ( const std::vector< SolAR::datastructure::Point2Df > &  pointsView1,
const std::vector< SolAR::datastructure::Point2Df > &  pointsView2,
const SolAR::datastructure::Transform3Df poseView1,
SolAR::datastructure::Transform3Df poseView2,
std::vector< SolAR::datastructure::DescriptorMatch > &  inlierMatches 
)
pure virtual

Estimates camera pose from a set of 2D points of the first image which match with a set of 2D points of the second image.

Parameters
[in]pointsView1Set of 2D points seen in view 1.
[in]pointsView2Set of 2D points seen in view 2 and matching with the 2D points of the view 1.
[in]poseView1Camera pose (3D transform of the camera of the view1 defined in world corrdinate system).
[out]poseView2Camera pose (3D transform of the camera of the view2 defined in world corrdinate system).
[in,out]inlierMatchesa vector of matches that will be used for the pose estimation. This vector wll be updates as some input matches will be considered as outliers. If this vector is empty, we consider that the ith point of pointsView1 matches with the ith point of pointsView2.
Returns
FrameworkReturnCode::SUCCESS if succeed, else FrameworkReturnCode::_ERROR

◆ setCameraParameters()

virtual void SolAR::api::solver::pose::I3DTransformFinderFrom2D2D::setCameraParameters ( const SolAR::datastructure::CamCalibration intrinsicParams,
const SolAR::datastructure::CamDistortion distorsionParams 
)
pure virtual

this method is used to set intrinsic parameters and distorsion of the camera

Parameters
[in]intrinsicParamscamera calibration matrix parameters.
[in]distorsionParamscamera distorsion parameters.

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