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

Finds the camera pose based on a 2D-2D points correspondences between two images. UUID: 52babb5e-9d33-11e8-98d0-529269fb1459 More...

#include <SolARPoseFinderFrom2D2DOpencv.h>

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

Public Member Functions

 SolARPoseFinderFrom2D2DOpencv ()
 SolARPoseFinderFrom2D2DOpencv constructor;.
 
 ~SolARPoseFinderFrom2D2DOpencv () override
 SolARPoseFinderFrom2D2DOpencv destructor;.
 
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...
 
FrameworkReturnCode estimate (const std::vector< datastructure::Point2Df > &matchedPointsView1, const std::vector< datastructure::Point2Df > &matchedPointsView2, const datastructure::Transform3Df &poseView1, datastructure::Transform3Df &poseView2, std::vector< datastructure::DescriptorMatch > &inlierMatches) override
 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...
 
FrameworkReturnCode estimate (const std::vector< datastructure::Keypoint > &matchedPointsView1, const std::vector< datastructure::Keypoint > &matchedPointsView2, const datastructure::Transform3Df &poseView1, datastructure::Transform3Df &poseView2, std::vector< datastructure::DescriptorMatch > &inlierMatches) override
 Estimates camera pose from a set of keypoints of the first image which match with a set of keypoints of the second image. More...
 
void unloadComponent () override final
 

Detailed Description

Finds the camera pose based on a 2D-2D points correspondences between two images. UUID: 52babb5e-9d33-11e8-98d0-529269fb1459

This component first compute the essential Matrix between the two images, and then estimate the pose of the second camera (position and orientation of the camera defined in the world coordinate system) knowing the pose of the first camera. To do so, the component needs to know the intrinsic parameter of the camera. During the essential matrix estimation, the OpenCV method filters the matches based on a RANSAC approach by removing those that are to distant to the epipolar line. The estimation of the pose of the second camera is based on the recoverPose method of OpenCV which decomposes the essential matrix and selects among the four solutions the one that have the most important number of 3D points in front of the camera (cheirality check).

Properties
outlierDistanceRatio here we are using a RANSAC method to remove outlier.
This attribute is the ratio between the maximum distance in pixels between source points and the maximum distance in pixels to the epipolar line for which point is considered as a outlier.
The higher is this ratio, the more you will keep inliers to estimate your 2D transform, but the less this estimation will be correct.
By default, this value is set to the one proposed by [Snavely07 4.1]
type: float; range : [0..MAX FLOAT]; default: 0.006f
outlierDistanceRatio the probability that the algorithm produces a useful result
type: float; range : [0..1]; default: 0.99f

Member Function Documentation

◆ estimate() [1/2]

FrameworkReturnCode SolAR::MODULES::OPENCV::SolARPoseFinderFrom2D2DOpencv::estimate ( const std::vector< datastructure::Keypoint > &  matchedPointsView1,
const std::vector< datastructure::Keypoint > &  matchedPointsView2,
const datastructure::Transform3Df &  poseView1,
datastructure::Transform3Df &  poseView2,
std::vector< datastructure::DescriptorMatch > &  inlierMatches 
)
override

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]pointsView1,Setof keypoints seen in view 1.
[in]pointsView2,Setof keypoints seen in view 2 and matching with the 2D points of the view 1.
[in]poseView1,Camerapose (3D transform of the camera of the view1 defined in world corrdinate system).
[out]poseView2,Camerapose (3D transform of the camera of the view2 defined in world corrdinate system).
[in|out]inlierMatches, a 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.

◆ estimate() [2/2]

FrameworkReturnCode SolAR::MODULES::OPENCV::SolARPoseFinderFrom2D2DOpencv::estimate ( const std::vector< datastructure::Point2Df > &  matchedPointsView1,
const std::vector< datastructure::Point2Df > &  matchedPointsView2,
const datastructure::Transform3Df &  poseView1,
datastructure::Transform3Df &  poseView2,
std::vector< datastructure::DescriptorMatch > &  inlierMatches 
)
override

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]pointsView1,Setof 2D points seen in view 1.
[in]pointsView2,Setof 2D points seen in view 2 and matching with the 2D points of the view 1.
[in]poseView1,Camerapose (3D transform of the camera of the view1 defined in world corrdinate system).
[out]poseView2,Camerapose (3D transform of the camera of the view2 defined in world corrdinate system).
[in|out]inlierMatches, a 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.

◆ setCameraParameters()

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