A structure containing options for the matching.
Definition at line 268 of file vision/include/mrpt/vision/types.h.
#include <mrpt/vision/types.h>
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 () | |
Constructor. More... | |
void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) MRPT_OVERRIDE |
This method load the options from a ".ini"-like file or memory-stored string list. More... | |
void | dumpToTextStream (mrpt::utils::CStream &out) const MRPT_OVERRIDE |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream. More... | |
bool | operator== (const TMatchingOptions &o) const |
void | operator= (const TMatchingOptions &o) |
void | loadFromConfigFileName (const std::string &config_file, const std::string §ion) |
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::utils::CConfigFileBase &target, const std::string §ion) 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 §ion) 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 |
Whether or not take into account the epipolar restriction for finding correspondences. More... | |
bool | hasFundamentalMatrix |
Whether or not there is a fundamental matrix. More... | |
bool | parallelOpticalAxis |
Whether or not the stereo rig has the optical axes parallel. More... | |
bool | useXRestriction |
Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example) More... | |
bool | addMatches |
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 |
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 |
float | max_disp |
Disparity limits, see also 'useDisparityLimits'. More... | |
mrpt::math::CMatrixDouble33 | F |
TMatchingMethod | matching_method |
Matching method. More... | |
float | epipolar_TH |
Epipolar constraint (rows of pixels) More... | |
float | maxEDD_TH |
Maximum Euclidean Distance Between SIFT Descriptors. More... | |
float | EDD_RATIO |
Boundary Ratio between the two lowest EDD. More... | |
float | minCC_TH |
Minimum Value of the Cross Correlation. More... | |
float | minDCC_TH |
Minimum Difference Between the Maximum Cross Correlation Values. More... | |
float | rCC_TH |
Maximum Ratio Between the two highest CC values. More... | |
float | maxEDSD_TH |
Maximum Euclidean Distance Between SURF Descriptors. More... | |
float | EDSD_RATIO |
Boundary Ratio between the two lowest SURF EDSD. More... | |
double | maxSAD_TH |
Minimum Euclidean Distance Between Sum of Absolute Differences. More... | |
double | SAD_RATIO |
Boundary Ratio between the two highest SAD. More... | |
double | maxORB_dist |
Maximun distance between ORB descriptors. More... | |
bool | estimateDepth |
Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now). More... | |
double | maxDepthThreshold |
The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered. More... | |
Static Protected Member Functions | |
static void | dumpVar_int (CStream &out, const char *varName, int v) |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More... | |
static void | dumpVar_float (CStream &out, const char *varName, float v) |
static void | dumpVar_double (CStream &out, const char *varName, double v) |
static void | dumpVar_bool (CStream &out, const char *varName, bool v) |
static void | dumpVar_string (CStream &out, const char *varName, const std::string &v) |
Method for propagating the feature's image coordinate uncertainty into 3D space.
Default value: Prop_Linear
Definition at line 273 of file vision/include/mrpt/vision/types.h.
TMatchingOptions::TMatchingOptions | ( | ) |
Constructor.
Definition at line 2209 of file vision_utils.cpp.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Definition at line 47 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::dumpToTextStream(), and loadable_opts_my_cout.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), mrpt::hmtslam::CHMTSLAM::loadOptions(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams().
|
virtual |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.
Reimplemented from mrpt::utils::CLoadableOptions.
Definition at line 2306 of file vision_utils.cpp.
References addMatches, EDD_RATIO, EDSD_RATIO, epipolar_TH, estimateDepth, hasFundamentalMatrix, matching_method, max_disp, maxDepthThreshold, maxEDD_TH, maxEDSD_TH, maxORB_dist, maxSAD_TH, min_disp, minCC_TH, minDCC_TH, mmCorrelation, mmDescriptorORB, mmDescriptorSIFT, mmDescriptorSURF, mmSAD, parallelOpticalAxis, mrpt::utils::CStream::printf(), rCC_TH, SAD_RATIO, useDisparityLimits, useEpipolarRestriction, and useXRestriction.
|
staticprotectedinherited |
Definition at line 67 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 62 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 57 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
Definition at line 52 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 72 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
virtual |
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:
Implements mrpt::utils::CLoadableOptions.
Definition at line 2249 of file vision_utils.cpp.
References addMatches, EDD_RATIO, EDSD_RATIO, epipolar_TH, estimateDepth, hasFundamentalMatrix, matching_method, max_disp, maxDepthThreshold, maxEDD_TH, maxEDSD_TH, maxORB_dist, maxSAD_TH, min_disp, minCC_TH, minDCC_TH, mmCorrelation, mmDescriptorORB, mmDescriptorSIFT, mmDescriptorSURF, mmSAD, parallelOpticalAxis, rCC_TH, mrpt::utils::CConfigFileBase::read_bool(), mrpt::utils::CConfigFileBase::read_float(), mrpt::utils::CConfigFileBase::read_int(), SAD_RATIO, useDisparityLimits, useEpipolarRestriction, and useXRestriction.
|
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.
Definition at line 23 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::loadFromConfigFile().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
inline |
Definition at line 372 of file vision/include/mrpt/vision/types.h.
References COPY_MEMBER.
|
inline |
Definition at line 343 of file vision/include/mrpt/vision/types.h.
References CHECK_MEMBER.
|
virtualinherited |
This method saves the options to a ".ini"-like file or memory-stored string list.
Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CHolonomicND::TOptions, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::nav::CHolonomicVFF::TOptions, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, 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 31 of file CLoadableOptions.cpp.
References MRPT_UNUSED_PARAM.
Referenced by mrpt::utils::CLoadableOptions::dumpToTextStream(), and mrpt::utils::CLoadableOptions::saveToConfigFileName().
|
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.
Definition at line 39 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::saveToConfigFile().
bool mrpt::vision::TMatchingOptions::addMatches |
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 297 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::EDD_RATIO |
Boundary Ratio between the two lowest EDD.
Definition at line 311 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::EDSD_RATIO |
Boundary Ratio between the two lowest SURF EDSD.
Definition at line 320 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
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 299 of file vision/include/mrpt/vision/types.h.
float mrpt::vision::TMatchingOptions::epipolar_TH |
Epipolar constraint (rows of pixels)
Definition at line 307 of file vision/include/mrpt/vision/types.h.
Referenced by mrpt::vision::checkTrackedFeatures(), dumpToTextStream(), loadFromConfigFile(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::matchFeatures().
bool mrpt::vision::TMatchingOptions::estimateDepth |
Whether or not estimate the 3D position of the real features for the matches (only with parallelOpticalAxis by now).
Definition at line 330 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
mrpt::math::CMatrixDouble33 mrpt::vision::TMatchingOptions::F |
Definition at line 303 of file vision/include/mrpt/vision/types.h.
bool mrpt::vision::TMatchingOptions::hasFundamentalMatrix |
Whether or not there is a fundamental matrix.
Definition at line 294 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
TMatchingMethod mrpt::vision::TMatchingOptions::matching_method |
Matching method.
Definition at line 306 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::max_disp |
Disparity limits, see also 'useDisparityLimits'.
Definition at line 301 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), and loadFromConfigFile().
double mrpt::vision::TMatchingOptions::maxDepthThreshold |
The maximum allowed depth for the matching. If its computed depth is larger than this, the match won't be considered.
Definition at line 331 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::maxEDD_TH |
Maximum Euclidean Distance Between SIFT Descriptors.
Definition at line 310 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), mrpt::maps::CLandmarksMap::loadSiftFeaturesFromStereoImageObservation(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::maxEDSD_TH |
Maximum Euclidean Distance Between SURF Descriptors.
Definition at line 319 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
double mrpt::vision::TMatchingOptions::maxORB_dist |
Maximun distance between ORB descriptors.
Definition at line 327 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
double mrpt::vision::TMatchingOptions::maxSAD_TH |
Minimum Euclidean Distance Between Sum of Absolute Differences.
Definition at line 323 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::min_disp |
Definition at line 301 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), and loadFromConfigFile().
float mrpt::vision::TMatchingOptions::minCC_TH |
Minimum Value of the Cross Correlation.
Definition at line 314 of file vision/include/mrpt/vision/types.h.
Referenced by mrpt::vision::checkTrackedFeatures(), dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::minDCC_TH |
Minimum Difference Between the Maximum Cross Correlation Values.
Definition at line 315 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), and loadFromConfigFile().
bool mrpt::vision::TMatchingOptions::parallelOpticalAxis |
Whether or not the stereo rig has the optical axes parallel.
Definition at line 295 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
float mrpt::vision::TMatchingOptions::rCC_TH |
Maximum Ratio Between the two highest CC values.
Definition at line 316 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
double mrpt::vision::TMatchingOptions::SAD_RATIO |
Boundary Ratio between the two highest SAD.
Definition at line 324 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
bool mrpt::vision::TMatchingOptions::useDisparityLimits |
Whether or not use limits (min,max) for the disparity, see also 'min_disp, max_disp'.
Definition at line 298 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), and loadFromConfigFile().
bool mrpt::vision::TMatchingOptions::useEpipolarRestriction |
Whether or not take into account the epipolar restriction for finding correspondences.
Definition at line 293 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
bool mrpt::vision::TMatchingOptions::useXRestriction |
Whether or not employ the x-coord restriction for finding correspondences (bumblebee camera, for example)
Definition at line 296 of file vision/include/mrpt/vision/types.h.
Referenced by dumpToTextStream(), loadFromConfigFile(), and mrpt::vision::matchFeatures().
Page generated by Doxygen 1.8.14 for MRPT 1.5.9 Git: 690a4699f Wed Apr 15 19:29:53 2020 +0200 at miƩ abr 15 19:30:12 CEST 2020 |