Public Types | Public Member Functions | Protected Member Functions | Private Attributes
RobustFeatureMatcher Class Reference

Handles unguided feature matching and robust estimation. More...

#include <feature_matching.h>

List of all members.

Public Types

typedef shared_ptr
< EMatrixModelBuilder
MBuilderPtr

Public Member Functions

void nonsymetricalMatch (const std::vector< cv::KeyPoint > &train_keypoints, const std::vector< cv::KeyPoint > &query_keypoints, const cv::Mat &train_descriptors, const cv::Mat &query_descriptors, RobustFeatureMatcherStats &stats, vector< cv::DMatch > &matches)
 one-way matching with ratio test.
void outlierRemoval (const SE3 &T_c1c2, const ImageMatchVec &matches_c1c2, const vector< cv::DMatch > &dmatches_c1c2, RobustFeatureMatcherStats &stats, vector< cv::DMatch > &filtered_matches_c1c2)
 remove matches that are outliers in epipolar constraint given by T_c1c2.
bool ransacTest (const ImageMatchVec &matches_c1c2, const vector< cv::DMatch > &dmatches_c1c2, RobustFeatureMatcherStats &stats, vector< cv::DMatch > &filtered_matches_c1c2, SE3 &T_c1c2)
 produce relative pose estimate (model) and remove outliers of the model.
 RobustFeatureMatcher (shared_ptr< cv::DescriptorMatcher > _matcher, MBuilderPtr _mbuilder=MBuilderPtr(), MBuilderPtr _maximal_data_mbuilder=MBuilderPtr())
void setMaxOutlierRemovalError (double _e)
 Set maximum error under which data point is considered an inlier (RanSaC).
void setRansacIterationsNum (int num)
 Set number of RanSaC iteration in model estimation.
void setRanSaCModelMinInliersRatio (int ratio)
 Set the minimum number of inliers in valid model (RanSaC).
void setRatio (float r)
 Set max ratio between 1st and 2nd nearest neighbours to train descriptor.
void symaetricalMatch (const std::vector< cv::KeyPoint > &keypoints_c1, const std::vector< cv::KeyPoint > &keypoints_c2, const cv::Mat &descriptors_c1, const cv::Mat &descriptors_c2, RobustFeatureMatcherStats &stats, std::vector< cv::DMatch > &sym_matches_c1c2)
 symetrical matching of features produced by two calls to nonsymetricalMatch and symmetry test.

Protected Member Functions

void ratioTest (std::vector< std::vector< cv::DMatch > > &matches0, std::vector< cv::DMatch > &matches)
void symmetryTest (const vector< cv::DMatch > &matches_c1c2, const vector< cv::DMatch > &matches_c2c1, int keypoints2_size, vector< cv::DMatch > &symMatches)

Private Attributes

shared_ptr< cv::DescriptorMatcher > matcher
double max_outlier_removal_error
shared_ptr< EMatrixModelBuildermaximal_data_mbuilder
 if true, will use it to refine the E matrix
shared_ptr< EMatrixModelBuildermbuilder
int ransac_iterations
double ransac_model_min_inliers_ratio
float ratio
 max ratio between 1st and 2nd nearest neighbours.

Detailed Description

Handles unguided feature matching and robust estimation.

Uses OpenCV features2d framework for feature matching.

Robust estimation is done using a 5-point algorithm. Error functuion is angle between epipolar planes given by a match. match is a pair of corresponding points on the imaging surface.

Definition at line 186 of file feature_matching.h.


Member Typedef Documentation

Definition at line 198 of file feature_matching.h.


Constructor & Destructor Documentation

RobustFeatureMatcher::RobustFeatureMatcher ( shared_ptr< cv::DescriptorMatcher >  _matcher,
MBuilderPtr  _mbuilder = MBuilderPtr(),
MBuilderPtr  _maximal_data_mbuilder = MBuilderPtr() 
) [inline]
Parameters:
_matcherinstance of a class with OpenCVs DescriptorMatchers interface
_mbuilderclass with ModelBuilder interface for RanSaC. If _mbuilder=NULL then model estimation is not performed.
_maximal_data_mbuilderdummy parameter reserved for future functionality.

Definition at line 206 of file feature_matching.h.


Member Function Documentation

void RobustFeatureMatcher::nonsymetricalMatch ( const std::vector< cv::KeyPoint > &  train_keypoints,
const std::vector< cv::KeyPoint > &  query_keypoints,
const cv::Mat &  train_descriptors,
const cv::Mat &  query_descriptors,
RobustFeatureMatcherStats stats,
vector< cv::DMatch > &  matches 
)

one-way matching with ratio test.

Parameters:
statsmatching statistics (only relevant parts are filled with meaningful values).

Definition at line 129 of file feature_matching.cpp.

void RobustFeatureMatcher::outlierRemoval ( const SE3 &  T_c1c2,
const ImageMatchVec matches_c1c2,
const vector< cv::DMatch > &  dmatches_c1c2,
RobustFeatureMatcherStats stats,
vector< cv::DMatch > &  filtered_matches_c1c2 
)

remove matches that are outliers in epipolar constraint given by T_c1c2.

Parameters:
T_c1c2transform from camera1 coordinate frame to camera 2 coordinate frame. First camera that cooresponds to train keypoints in cv::DMatch.

Definition at line 283 of file feature_matching.cpp.

bool RobustFeatureMatcher::ransacTest ( const ImageMatchVec matches_c1c2,
const vector< cv::DMatch > &  dmatches_c1c2,
RobustFeatureMatcherStats stats,
vector< cv::DMatch > &  filtered_matches_c1c2,
SE3 &  T_c1c2 
)

produce relative pose estimate (model) and remove outliers of the model.

Parameters:
T_c1c2has the same semantics as in outlierRemoval.
See also:
outlierRemoval

Definition at line 228 of file feature_matching.cpp.

void RobustFeatureMatcher::ratioTest ( std::vector< std::vector< cv::DMatch > > &  matches0,
std::vector< cv::DMatch > &  matches 
) [protected]

Definition at line 184 of file feature_matching.cpp.

Set maximum error under which data point is considered an inlier (RanSaC).

Definition at line 231 of file feature_matching.h.

Set number of RanSaC iteration in model estimation.

Definition at line 221 of file feature_matching.h.

Set the minimum number of inliers in valid model (RanSaC).

Definition at line 216 of file feature_matching.h.

void RobustFeatureMatcher::setRatio ( float  r) [inline]

Set max ratio between 1st and 2nd nearest neighbours to train descriptor.

Definition at line 226 of file feature_matching.h.

void RobustFeatureMatcher::symaetricalMatch ( const std::vector< cv::KeyPoint > &  keypoints_c1,
const std::vector< cv::KeyPoint > &  keypoints_c2,
const cv::Mat &  descriptors_c1,
const cv::Mat &  descriptors_c2,
RobustFeatureMatcherStats stats,
std::vector< cv::DMatch > &  sym_matches_c1c2 
)

symetrical matching of features produced by two calls to nonsymetricalMatch and symmetry test.

Definition at line 155 of file feature_matching.cpp.

void RobustFeatureMatcher::symmetryTest ( const vector< cv::DMatch > &  matches_c1c2,
const vector< cv::DMatch > &  matches_c2c1,
int  keypoints2_size,
vector< cv::DMatch > &  symMatches 
) [protected]

Definition at line 203 of file feature_matching.cpp.


Member Data Documentation

shared_ptr<cv::DescriptorMatcher> RobustFeatureMatcher::matcher [private]

Definition at line 192 of file feature_matching.h.

Definition at line 191 of file feature_matching.h.

if true, will use it to refine the E matrix

Definition at line 195 of file feature_matching.h.

Definition at line 193 of file feature_matching.h.

Definition at line 189 of file feature_matching.h.

Definition at line 190 of file feature_matching.h.

float RobustFeatureMatcher::ratio [private]

max ratio between 1st and 2nd nearest neighbours.

Definition at line 188 of file feature_matching.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pose_estimation
Author(s): Jiri Divis/jiridivis@gmail.com
autogenerated on Wed Mar 27 2013 21:00:15