Solar
|
Matches two sets of descriptors based on geometric constraints. UUID: 389ece8b-9e29-45ae-bd60-de1784ff0931
More...
#include <SolARDescriptorMatcherGeometricOpencv.h>
Public Member Functions | |
SolARDescriptorMatcherGeometricOpencv () | |
SolARDescriptorMatcherGeometricOpencv constructor. | |
~SolARDescriptorMatcherGeometricOpencv () override | |
SolARDescriptorMatcherGeometricOpencv destructor. | |
FrameworkReturnCode | match (const SRef< SolAR::datastructure::DescriptorBuffer > descriptors1, const SRef< SolAR::datastructure::DescriptorBuffer > descriptors2, const std::vector< SolAR::datastructure::Keypoint > &undistortedKeypoints1, const std::vector< SolAR::datastructure::Keypoint > &undistortedKeypoints2, const SolAR::datastructure::Transform3Df &pose1, const SolAR::datastructure::Transform3Df &pose2, const SolAR::datastructure::CameraParameters &camParams, std::vector< SolAR::datastructure::DescriptorMatch > &matches, const std::vector< uint32_t > &mask={}) override |
Match two sets of descriptors from two frames based on epipolar constraint. More... | |
void | unloadComponent () override |
Matches two sets of descriptors based on geometric constraints. UUID: 389ece8b-9e29-45ae-bd60-de1784ff0931
distanceRatio | distance ratio used to keep good matches. Several matches can correspond to a given keypoint of the first image. The first match with the best score is always retained. But here, we can also retain the second match if its distance or score is greater than the score of the best match * m_distanceRatio. |
type: float; range : [0..MAX FLOAT]; default: default: 0.75f | |
paddingRatio | |
type: float; range : [0..MAX FLOAT]; default: 0.003f | |
matchingDistanceMax | |
type: float; range : [0..MAX FLOAT]; default: 500.f |
|
override |
Match two sets of descriptors from two frames based on epipolar constraint.
[in] | descriptors1 | The first set of descriptors. |
[in] | descriptors2 | The second set of descriptors. |
[in] | undistortedKeypoints1 | The first set of undistorted keypoints. |
[in] | undistortedKeypoints2 | The second set of undistorted keypoints. |
[in] | pose1 | The first pose. |
[in] | pose2 | The second pose. |
[in] | camParams | The intrinsic parameters of the camera. |
[out] | matches | A vector of matches representing pairs of indices relatively to the first and second set of descriptors. |
[in] | mask | The indices of descriptors in the first frame are used for matching to the second frame. If it is empty then all will be used. |