SaDVIO
|
Class for matching 2D line features. More...
#include <Line2DFeatureMatcher.h>
Public Member Functions | |
Line2DFeatureMatcher () | |
Line2DFeatureMatcher (std::shared_ptr< AFeatureDetector > detector) | |
uint | match (std::vector< std::shared_ptr< AFeature >> &features1, std::vector< std::shared_ptr< AFeature >> &features2, std::vector< std::shared_ptr< AFeature >> &features_init, vec_match &matches, vec_match &matches_with_ldmks, int searchAreaWidth=51, int searchAreaHeight=51) override |
Match features between two sets of features. More... | |
uint | ldmk_match (std::shared_ptr< ImageSensor > &sensor1, std::vector< std::shared_ptr< ALandmark >> &ldmks, int searchAreaWidth=51, int searchAreaHeight=51) override |
Match landmarks with features in a given sensor. More... | |
![]() | |
AFeatureMatcher () | |
AFeatureMatcher (std::shared_ptr< AFeatureDetector > detector) | |
Additional Inherited Members | |
![]() | |
vec_match | filterMatches (vec_feat_matches &matches12, vec_feat_matches &matches21, vec_feat_matches_scores &all_scores12, vec_feat_matches_scores &all_scores21) |
Filter matches based on the first and second best match scores. More... | |
![]() | |
std::shared_ptr< AFeatureDetector > | _detector |
feature detector for distance measurement More... | |
double | _first_second_match_score_ratio |
ratio between the first and second best match score to consider a match valid More... | |
std::string | _feature_label |
label for the features being matched More... | |
Class for matching 2D line features.
|
inline |
|
inline |
|
overridevirtual |
Match landmarks with features in a given sensor.
sensor1 | The sensor in which to match landmarks. |
ldmks | Vector of landmarks to match. |
searchAreaWidth | Width of the search area for matching (default is 51). |
searchAreaHeight | Height of the search area for matching (default is 51). |
Reimplemented from isae::AFeatureMatcher.
|
overridevirtual |
Match features between two sets of features.
features1 | First set of features. |
features2 | Second set of features. |
features_init | Initial set of features for matching. |
matches | Output vector to store matched features. |
matches_with_ldmks | Output vector to store matched features with landmarks. |
searchAreaWidth | Width of the search area for matching (default is 51). |
searchAreaHeight | Height of the search area for matching (default is 51). |
Reimplemented from isae::AFeatureMatcher.