With this struct options are provided to the observation insertion process.
Definition at line 182 of file CLandmarksMap.h.
#include <mrpt/slam/CLandmarksMap.h>

Public Member Functions | |
| TInsertionOptions () | |
| Initilization of default parameters. More... | |
| void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) |
| See utils::CLoadableOptions. More... | |
| void | dumpToTextStream (CStream &out) const |
| See utils::CLoadableOptions. More... | |
| 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 | insert_SIFTs_from_monocular_images |
| If set to true (default), the insertion of a CObservationImage in the map will insert SIFT 3D features. More... | |
| bool | insert_SIFTs_from_stereo_images |
| If set to true (default), the insertion of a CObservationStereoImages in the map will insert SIFT 3D features. More... | |
| bool | insert_Landmarks_from_range_scans |
| If set to true (default), inserting a CObservation2DRangeScan in the map will generate landmarks for each range. More... | |
| float | SiftCorrRatioThreshold |
| [For SIFT landmarks only] The ratio between the best and second best descriptor distances to set as correspondence (Default=0.4) More... | |
| float | SiftLikelihoodThreshold |
| [For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0.5) More... | |
| float | SiftEDDThreshold |
| [For SIFT landmarks only] The minimum Euclidean Descriptor Distance value of a match to set as correspondence (Default=200) More... | |
| unsigned int | SIFTMatching3DMethod |
| [For SIFT landmarks only] Method to compute 3D matching (Default = 0 (Our method)) 0: Our method -> Euclidean Distance between Descriptors and 3D position 1: Sim, Elinas, Griffin, Little -> Euclidean Distance between Descriptors More... | |
| unsigned int | SIFTLikelihoodMethod |
| [For SIFT landmarks only] Method to compute the likelihood (Default = 0 (Our method)) 0: Our method -> Euclidean Distance between Descriptors and 3D position 1: Sim, Elinas, Griffin, Little -> 3D position More... | |
| float | SIFTsLoadDistanceOfTheMean |
| [For SIFT landmarks only] The distance (in meters) of the mean value of landmarks, for the initial position PDF (Default = 3m) More... | |
| float | SIFTsLoadEllipsoidWidth |
| [For SIFT landmarks only] The width (in meters, standard deviation) of the ellipsoid in the axis perpendicular to the main directiom (Default = 0.05f) More... | |
| float | SIFTs_stdXY |
| [For SIFT landmarks only] The standard deviation (in pixels) for the SIFTs detector (This is used for the Jacobbian to project stereo images to 3D) More... | |
| float | SIFTs_stdDisparity |
| int | SIFTs_numberOfKLTKeypoints |
| Number of points to extract in the image. More... | |
| float | SIFTs_stereo_maxDepth |
| Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation. More... | |
| float | SIFTs_epipolar_TH |
| Maximum distance (in pixels) from a point to a certain epipolar line to be considered a potential match. More... | |
| bool | PLOT_IMAGES |
| Indicates if the images (as well as the SIFT detected features) should be shown in a window. More... | |
| mrpt::vision::CFeatureExtraction::TOptions | SIFT_feat_options |
| Parameters of the SIFT feature detector/descriptors while inserting images in the landmark map. 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) |
| mrpt::slam::CLandmarksMap::TInsertionOptions::TInsertionOptions | ( | ) |
Initilization of default parameters.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
|
virtual |
Reimplemented from mrpt::utils::CLoadableOptions.
|
staticprotectedinherited |
|
staticprotectedinherited |
|
staticprotectedinherited |
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
|
staticprotectedinherited |
|
virtual |
Implements mrpt::utils::CLoadableOptions.
|
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.
|
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::srba::RbaEngine< KF2KF_POSE_TYPE, LM_TYPE, OBS_TYPE, RBA_OPTIONS >::TSRBAParameters, mrpt::reactivenav::CHolonomicND::TOptions, and mrpt::reactivenav::CHolonomicVFF::TOptions.
|
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.
| bool mrpt::slam::CLandmarksMap::TInsertionOptions::insert_Landmarks_from_range_scans |
If set to true (default), inserting a CObservation2DRangeScan in the map will generate landmarks for each range.
Definition at line 209 of file CLandmarksMap.h.
| bool mrpt::slam::CLandmarksMap::TInsertionOptions::insert_SIFTs_from_monocular_images |
If set to true (default), the insertion of a CObservationImage in the map will insert SIFT 3D features.
Definition at line 201 of file CLandmarksMap.h.
| bool mrpt::slam::CLandmarksMap::TInsertionOptions::insert_SIFTs_from_stereo_images |
If set to true (default), the insertion of a CObservationStereoImages in the map will insert SIFT 3D features.
Definition at line 205 of file CLandmarksMap.h.
| bool mrpt::slam::CLandmarksMap::TInsertionOptions::PLOT_IMAGES |
Indicates if the images (as well as the SIFT detected features) should be shown in a window.
Definition at line 264 of file CLandmarksMap.h.
| mrpt::vision::CFeatureExtraction::TOptions mrpt::slam::CLandmarksMap::TInsertionOptions::SIFT_feat_options |
Parameters of the SIFT feature detector/descriptors while inserting images in the landmark map.
Definition at line 270 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SiftCorrRatioThreshold |
[For SIFT landmarks only] The ratio between the best and second best descriptor distances to set as correspondence (Default=0.4)
Definition at line 213 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SiftEDDThreshold |
[For SIFT landmarks only] The minimum Euclidean Descriptor Distance value of a match to set as correspondence (Default=200)
Definition at line 222 of file CLandmarksMap.h.
| unsigned int mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTLikelihoodMethod |
[For SIFT landmarks only] Method to compute the likelihood (Default = 0 (Our method)) 0: Our method -> Euclidean Distance between Descriptors and 3D position 1: Sim, Elinas, Griffin, Little -> 3D position
Definition at line 234 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SiftLikelihoodThreshold |
[For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0.5)
Definition at line 217 of file CLandmarksMap.h.
| unsigned int mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTMatching3DMethod |
[For SIFT landmarks only] Method to compute 3D matching (Default = 0 (Our method)) 0: Our method -> Euclidean Distance between Descriptors and 3D position 1: Sim, Elinas, Griffin, Little -> Euclidean Distance between Descriptors
Definition at line 228 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTs_epipolar_TH |
Maximum distance (in pixels) from a point to a certain epipolar line to be considered a potential match.
Definition at line 260 of file CLandmarksMap.h.
| int mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTs_numberOfKLTKeypoints |
Number of points to extract in the image.
Definition at line 252 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTs_stdDisparity |
Definition at line 248 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTs_stdXY |
[For SIFT landmarks only] The standard deviation (in pixels) for the SIFTs detector (This is used for the Jacobbian to project stereo images to 3D)
Definition at line 248 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTs_stereo_maxDepth |
Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation.
Definition at line 256 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTsLoadDistanceOfTheMean |
[For SIFT landmarks only] The distance (in meters) of the mean value of landmarks, for the initial position PDF (Default = 3m)
Definition at line 240 of file CLandmarksMap.h.
| float mrpt::slam::CLandmarksMap::TInsertionOptions::SIFTsLoadEllipsoidWidth |
[For SIFT landmarks only] The width (in meters, standard deviation) of the ellipsoid in the axis perpendicular to the main directiom (Default = 0.05f)
Definition at line 244 of file CLandmarksMap.h.
| Page generated by Doxygen 1.8.8 for MRPT 1.2.2 SVN:Unversioned directory at Tue Oct 14 02:14:08 UTC 2014 |