MRPT  2.0.0
List of all members | Public Types | Public Member Functions | Public Attributes | Static Protected Member Functions
mrpt::vision::TMatchingOptions Struct Reference

Detailed Description

A structure containing options for the matching.

Definition at line 342 of file vision/include/mrpt/vision/types.h.

#include <mrpt/vision/types.h>

Inheritance diagram for mrpt::vision::TMatchingOptions:

Public Types

enum  TMatchingMethod {
  mmCorrelation = 0, mmDescriptorSIFT, mmDescriptorSURF, mmSAD,
  mmDescriptorORB
}
 Method for propagating the feature's image coordinate uncertainty into 3D space. More...
 

Public Member Functions

 TMatchingOptions ()
 Intrinsic parameters of the stereo rig. More...
 
void loadFromConfigFile (const mrpt::config::CConfigFileBase &source, const std::string &section) override
 This method load the options from a ".ini"-like file or memory-stored string list. More...
 
void dumpToTextStream (std::ostream &out) const override
 This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream. More...
 
bool operator== (const TMatchingOptions &o) const
 
void operator= (const TMatchingOptions &o)
 
void loadFromConfigFileName (const std::string &config_file, const std::string &section)
 Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More...
 
virtual void saveToConfigFile (mrpt::config::CConfigFileBase &target, const std::string &section) const
 This method saves the options to a ".ini"-like file or memory-stored string list. More...
 
void saveToConfigFileName (const std::string &config_file, const std::string &section) const
 Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More...
 
void dumpToConsole () const
 Just like dumpToTextStream() but sending the text to the console (std::cout) More...
 

Public Attributes

bool useEpipolarRestriction {true}
 Whether or not take into account the epipolar restriction for finding correspondences. More...
 
bool hasFundamentalMatrix {false}
 Whether or not there is a fundamental matrix. More...
 
bool parallelOpticalAxis {true}
 Whether or not the stereo rig has the optical axes parallel. More...
 
bool useXRestriction {true}
 Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example) More...
 
bool addMatches {false}
 Whether or not to add the matches found into the input matched list (if false the input list will be cleared before being filled with the new matches) More...
 
bool useDisparityLimits {false}
 Whether or not use limits (min,max) for the disparity, see also 'min_disp, max_disp'. More...
 
bool enable_robust_1to1_match
 Whether or not only permit matches that are consistent from left->right and right->left. More...
 
float min_disp {1.0f}
 Disparity limits, see also 'useDisparityLimits'. More...
 
float max_disp {1e4f}
 
mrpt::math::CMatrixDouble33 F
 
TMatchingMethod matching_method {mmCorrelation}
 Matching method. More...
 
float epipolar_TH {1.5f}
 Epipolar constraint (rows of pixels) More...
 
float maxEDD_TH {90.0f}
 Maximum Euclidean Distance Between SIFT Descriptors. More...
 
float EDD_RATIO {0.6f}
 Boundary Ratio between the two lowest EDD. More...
 
float minCC_TH {0.95f}
 Minimum Value of the Cross Correlation. More...
 
float minDCC_TH {0.025f}
 Minimum Difference Between the Maximum Cross Correlation Values. More...
 
float rCC_TH {0.92f}
 Maximum Ratio Between the two highest CC values. More...
 
float maxEDSD_TH {0.15f}
 Maximum Euclidean Distance Between SURF Descriptors. More...
 
float EDSD_RATIO {0.6f}
 Boundary Ratio between the two lowest SURF EDSD. More...
 
double maxSAD_TH {0.4}
 Minimum Euclidean Distance Between Sum of Absolute Differences. More...
 
double SAD_RATIO {0.5}
 Boundary Ratio between the two highest SAD. More...
 
double maxORB_dist
 Maximun distance between ORB descriptors. More...
 
bool estimateDepth {false}
 Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now). More...
 
double maxDepthThreshold {15.0}
 The maximum allowed depth for the matching. More...
 

Static Protected Member Functions

static void dumpVar_int (std::ostream &out, const char *varName, int v)
 Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More...
 
static void dumpVar_float (std::ostream &out, const char *varName, float v)
 
static void dumpVar_double (std::ostream &out, const char *varName, double v)
 
static void dumpVar_bool (std::ostream &out, const char *varName, bool v)
 
static void dumpVar_string (std::ostream &out, const char *varName, const std::string &v)
 

Member Enumeration Documentation

◆ TMatchingMethod

Method for propagating the feature's image coordinate uncertainty into 3D space.

Default value: Prop_Linear

Enumerator
mmCorrelation 

Matching by cross correlation of the image patches.

mmDescriptorSIFT 

Matching by Euclidean distance between SIFT descriptors.

mmDescriptorSURF 

Matching by Euclidean distance between SURF descriptors.

mmSAD 

Matching by sum of absolute differences of the image patches.

mmDescriptorORB 

Matching by Hamming distance between ORB descriptors.

Definition at line 347 of file vision/include/mrpt/vision/types.h.

Constructor & Destructor Documentation

◆ TMatchingOptions()

TMatchingOptions::TMatchingOptions ( )
default

Intrinsic parameters of the stereo rig.

Constructor

Member Function Documentation

◆ dumpToConsole()

void CLoadableOptions::dumpToConsole ( ) const
inherited

Just like dumpToTextStream() but sending the text to the console (std::cout)

Definition at line 43 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::dumpToTextStream().

Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::ros1bridge::MapHdl::loadMap(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::printParams(), and mrpt::apps::CGridMapAlignerApp::run().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ dumpToTextStream()

void TMatchingOptions::dumpToTextStream ( std::ostream &  out) const
overridevirtual

This method should clearly display all the contents of the structure in textual form, sending it to a std::ostream.

The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.

Reimplemented from mrpt::config::CLoadableOptions.

Definition at line 2070 of file vision_utils.cpp.

References mrpt::format(), and out.

Here is the call graph for this function:

◆ dumpVar_bool()

void CLoadableOptions::dumpVar_bool ( std::ostream &  out,
const char *  varName,
bool  v 
)
staticprotectedinherited

Definition at line 62 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_double()

void CLoadableOptions::dumpVar_double ( std::ostream &  out,
const char *  varName,
double  v 
)
staticprotectedinherited

Definition at line 56 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_float()

void CLoadableOptions::dumpVar_float ( std::ostream &  out,
const char *  varName,
float  v 
)
staticprotectedinherited

Definition at line 50 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_int()

void CLoadableOptions::dumpVar_int ( std::ostream &  out,
const char *  varName,
int  v 
)
staticprotectedinherited

Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.

Definition at line 44 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ dumpVar_string()

void CLoadableOptions::dumpVar_string ( std::ostream &  out,
const char *  varName,
const std::string &  v 
)
staticprotectedinherited

Definition at line 69 of file CLoadableOptions.cpp.

References mrpt::format(), LOADABLEOPTS_COLUMN_WIDTH, and out.

Here is the call graph for this function:

◆ loadFromConfigFile()

void TMatchingOptions::loadFromConfigFile ( const mrpt::config::CConfigFileBase source,
const std::string &  section 
)
overridevirtual

This method load the options from a ".ini"-like file or memory-stored string list.

Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" file:

[section]
resolution = 0.10 // blah blah...
modeSelection = 1 // 0=blah, 1=blah,...
See also
loadFromConfigFileName, saveToConfigFile

Implements mrpt::config::CLoadableOptions.

Definition at line 2003 of file vision_utils.cpp.

References iniFile().

Here is the call graph for this function:

◆ loadFromConfigFileName()

void CLoadableOptions::loadFromConfigFileName ( const std::string &  config_file,
const std::string &  section 
)
inherited

Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.

See also
loadFromConfigFile

Definition at line 22 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::loadFromConfigFile().

Referenced by mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ operator=()

void mrpt::vision::TMatchingOptions::operator= ( const TMatchingOptions o)
inline

◆ operator==()

bool mrpt::vision::TMatchingOptions::operator== ( const TMatchingOptions o) const
inline

◆ saveToConfigFile()

void CLoadableOptions::saveToConfigFile ( mrpt::config::CConfigFileBase target,
const std::string &  section 
) const
virtualinherited

This method saves the options to a ".ini"-like file or memory-stored string list.

See also
loadFromConfigFile, saveToConfigFileName

Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::maps::TSetOfMetricMapInitializers, mrpt::maps::COccupancyGridMap3D::TLikelihoodOptions, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::maps::COccupancyGridMap3D::TInsertionOptions, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::bayes::CParticleFilter::TParticleFilterOptions, mrpt::nav::CHolonomicND::TOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::maps::TMapGenericParams, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::nav::CHolonomicVFF::TOptions, mrpt::slam::CICP::TConfigParams, mrpt::slam::CIncrementalMapPartitioner::TOptions, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, mrpt::maps::TMetricMapInitializer, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CMultiObjMotionOpt_Scalarization::TParams, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.

Definition at line 29 of file CLoadableOptions.cpp.

Referenced by mrpt::config::CLoadableOptions::dumpToTextStream(), and mrpt::config::CLoadableOptions::saveToConfigFileName().

Here is the caller graph for this function:

◆ saveToConfigFileName()

void CLoadableOptions::saveToConfigFileName ( const std::string &  config_file,
const std::string &  section 
) const
inherited

Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.

See also
saveToConfigFile, loadFromConfigFileName

Definition at line 36 of file CLoadableOptions.cpp.

References mrpt::config::CLoadableOptions::saveToConfigFile().

Here is the call graph for this function:

Member Data Documentation

◆ addMatches

bool mrpt::vision::TMatchingOptions::addMatches {false}

Whether or not to add the matches found into the input matched list (if false the input list will be cleared before being filled with the new matches)

Definition at line 380 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ EDD_RATIO

float mrpt::vision::TMatchingOptions::EDD_RATIO {0.6f}

◆ EDSD_RATIO

float mrpt::vision::TMatchingOptions::EDSD_RATIO {0.6f}

Boundary Ratio between the two lowest SURF EDSD.

Definition at line 417 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ enable_robust_1to1_match

bool mrpt::vision::TMatchingOptions::enable_robust_1to1_match

Whether or not only permit matches that are consistent from left->right and right->left.

Definition at line 386 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ epipolar_TH

float mrpt::vision::TMatchingOptions::epipolar_TH {1.5f}

◆ estimateDepth

bool mrpt::vision::TMatchingOptions::estimateDepth {false}

Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now).

Definition at line 432 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ F

mrpt::math::CMatrixDouble33 mrpt::vision::TMatchingOptions::F

Definition at line 391 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ hasFundamentalMatrix

bool mrpt::vision::TMatchingOptions::hasFundamentalMatrix {false}

Whether or not there is a fundamental matrix.

Definition at line 371 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ matching_method

TMatchingMethod mrpt::vision::TMatchingOptions::matching_method {mmCorrelation}

◆ max_disp

float mrpt::vision::TMatchingOptions::max_disp {1e4f}

Definition at line 389 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ maxDepthThreshold

double mrpt::vision::TMatchingOptions::maxDepthThreshold {15.0}

The maximum allowed depth for the matching.

If its computed depth is larger than this, the match won't be considered.

Definition at line 435 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ maxEDD_TH

float mrpt::vision::TMatchingOptions::maxEDD_TH {90.0f}

Maximum Euclidean Distance Between SIFT Descriptors.

Definition at line 401 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ maxEDSD_TH

float mrpt::vision::TMatchingOptions::maxEDSD_TH {0.15f}

Maximum Euclidean Distance Between SURF Descriptors.

Definition at line 415 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ maxORB_dist

double mrpt::vision::TMatchingOptions::maxORB_dist

Maximun distance between ORB descriptors.

Definition at line 427 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ maxSAD_TH

double mrpt::vision::TMatchingOptions::maxSAD_TH {0.4}

Minimum Euclidean Distance Between Sum of Absolute Differences.

Definition at line 421 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ min_disp

float mrpt::vision::TMatchingOptions::min_disp {1.0f}

Disparity limits, see also 'useDisparityLimits'.

Definition at line 389 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ minCC_TH

float mrpt::vision::TMatchingOptions::minCC_TH {0.95f}

Minimum Value of the Cross Correlation.

Definition at line 407 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ minDCC_TH

float mrpt::vision::TMatchingOptions::minDCC_TH {0.025f}

Minimum Difference Between the Maximum Cross Correlation Values.

Definition at line 409 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ parallelOpticalAxis

bool mrpt::vision::TMatchingOptions::parallelOpticalAxis {true}

Whether or not the stereo rig has the optical axes parallel.

Definition at line 373 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ rCC_TH

float mrpt::vision::TMatchingOptions::rCC_TH {0.92f}

Maximum Ratio Between the two highest CC values.

Definition at line 411 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ SAD_RATIO

double mrpt::vision::TMatchingOptions::SAD_RATIO {0.5}

Boundary Ratio between the two highest SAD.

Definition at line 423 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ useDisparityLimits

bool mrpt::vision::TMatchingOptions::useDisparityLimits {false}

Whether or not use limits (min,max) for the disparity, see also 'min_disp, max_disp'.

Definition at line 383 of file vision/include/mrpt/vision/types.h.

Referenced by operator=(), and operator==().

◆ useEpipolarRestriction

bool mrpt::vision::TMatchingOptions::useEpipolarRestriction {true}

Whether or not take into account the epipolar restriction for finding correspondences.

Definition at line 369 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().

◆ useXRestriction

bool mrpt::vision::TMatchingOptions::useXRestriction {true}

Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example)

Definition at line 376 of file vision/include/mrpt/vision/types.h.

Referenced by mrpt::vision::matchFeatures(), operator=(), and operator==().




Page generated by Doxygen 1.8.14 for MRPT 2.0.0 Git: b38439d21 Tue Mar 31 19:58:06 2020 +0200 at miƩ abr 1 00:50:30 CEST 2020