#include <mrpt/slam/CLandmarksMap.h>
Public Member Functions | |
TInsertionOptions () | |
Initilization of default parameters. | |
void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) |
See utils::CLoadableOptions. | |
void | dumpToTextStream (utils::CStream &out) |
See utils::CLoadableOptions. | |
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. | |
bool | insert_SIFTs_from_stereo_images |
If set to true (default), the insertion of a CObservationStereoImages in the map will insert SIFT 3D features. | |
bool | insert_Landmarks_from_range_scans |
If set to true (default), inserting a CObservation2DRangeScan in the map will generate landmarks for each range. | |
float | SiftCorrRatioThreshold |
[For SIFT landmarks only] The ratio between the best and second best descriptor distances to set as correspondence (Default=0.4) | |
float | SiftLikelihoodThreshold |
[For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0.5) | |
float | SiftEDDThreshold |
[For SIFT landmarks only] The minimum Euclidean Descriptor Distance value of a match to set as correspondence (Default=200) | |
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 | |
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 | |
float | SIFTsLoadDistanceOfTheMean |
[For SIFT landmarks only] The distance (in meters) of the mean value of landmarks, for the initial position PDF (Default = 3m) | |
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) | |
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) | |
float | SIFTs_stdDisparity |
int | SIFTs_numberOfKLTKeypoints |
Number of points to extract in the image. | |
float | SIFTs_stereo_maxDepth |
Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation. | |
float | SIFTs_epipolar_TH |
Maximum distance (in pixels) from a point to a certain epipolar line to be considered a potential match. | |
bool | PLOT_IMAGES |
Indicates if the images (as well as the SIFT detected features) should be shown in a window. |
Definition at line 199 of file CLandmarksMap.h.
mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::TInsertionOptions | ( | ) |
Initilization of default parameters.
void mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::dumpToTextStream | ( | utils::CStream & | out | ) | [virtual] |
void mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::loadFromConfigFile | ( | const mrpt::utils::CConfigFileBase & | source, | |
const std::string & | section | |||
) | [virtual] |
bool mrpt::slam::CLandmarksMap::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 226 of file CLandmarksMap.h.
bool mrpt::slam::CLandmarksMap::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 218 of file CLandmarksMap.h.
bool mrpt::slam::CLandmarksMap::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 222 of file CLandmarksMap.h.
bool mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::PLOT_IMAGES |
Indicates if the images (as well as the SIFT detected features) should be shown in a window.
Definition at line 281 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 230 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 239 of file CLandmarksMap.h.
unsigned int mrpt::slam::CLandmarksMap::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 251 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::SiftLikelihoodThreshold |
[For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0.5)
Definition at line 234 of file CLandmarksMap.h.
unsigned int mrpt::slam::CLandmarksMap::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 245 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 277 of file CLandmarksMap.h.
int mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::SIFTs_numberOfKLTKeypoints |
float mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::SIFTs_stdDisparity |
Definition at line 265 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 265 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::CLandmarksMap::TInsertionOptions::SIFTs_stereo_maxDepth |
Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation.
Definition at line 273 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 257 of file CLandmarksMap.h.
float mrpt::slam::CLandmarksMap::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 261 of file CLandmarksMap.h.
Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN: at Thu Feb 26 02:19:01 EST 2009 |