struct mrpt::maps::CLandmarksMap::TInsertionOptions

Overview

With this struct options are provided to the observation insertion process.

#include <mrpt/maps/CLandmarksMap.h>

struct TInsertionOptions: public mrpt::config::CLoadableOptions
{
    // fields

    bool insert_SIFTs_from_monocular_images {true};
    bool insert_SIFTs_from_stereo_images {true};
    bool insert_Landmarks_from_range_scans {true};
    float SiftCorrRatioThreshold {0.4f};
    float SiftLikelihoodThreshold {0.5f};
    float SiftEDDThreshold {200.0f};
    unsigned int SIFTMatching3DMethod {0};
    unsigned int SIFTLikelihoodMethod {0};
    float SIFTsLoadDistanceOfTheMean {3.0f};
    float SIFTsLoadEllipsoidWidth {0.05f};
    float SIFTs_stdXY {2.0f};
    float SIFTs_stdDisparity {1.0f};
    int SIFTs_numberOfKLTKeypoints {60};
    float SIFTs_stereo_maxDepth {15.0f};
    float SIFTs_epipolar_TH {1.5f};
    bool PLOT_IMAGES {false};
    mrpt::vision::CFeatureExtraction::TOptions SIFT_feat_options;

    // construction

    TInsertionOptions();

    // methods

    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section);
    virtual void dumpToTextStream(std::ostream& out) const;
};

Inherited Members

public:
    // methods

    virtual void loadFromConfigFile(const mrpt::config::CConfigFileBase& source, const std::string& section) = 0;
    void loadFromConfigFileName(const std::string& config_file, const std::string& section);
    virtual void saveToConfigFile(mrpt::config::CConfigFileBase& target, const std::string& section) const;
    void saveToConfigFileName(const std::string& config_file, const std::string& section) const;
    void dumpToConsole() const;
    virtual void dumpToTextStream(std::ostream& out) const;

Fields

bool insert_SIFTs_from_monocular_images {true}

If set to true (default), the insertion of a CObservationImage in the map will insert SIFT 3D features.

bool insert_SIFTs_from_stereo_images {true}

If set to true (default), the insertion of a CObservationStereoImages in the map will insert SIFT 3D features.

bool insert_Landmarks_from_range_scans {true}

If set to true (default), inserting a CObservation2DRangeScan in the map will generate landmarks for each range.

float SiftCorrRatioThreshold {0.4f}

[For SIFT landmarks only] The ratio between the best and second best descriptor distances to set as correspondence (Default=0.4)

float SiftLikelihoodThreshold {0.5f}

[For SIFT landmarks only] The minimum likelihood value of a match to set as correspondence (Default=0.5)

float SiftEDDThreshold {200.0f}

[For SIFT landmarks only] The minimum Euclidean Descriptor Distance value of a match to set as correspondence (Default=200)

unsigned int SIFTMatching3DMethod {0}

[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 {0}

[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 {3.0f}

[For SIFT landmarks only] The distance (in meters) of the mean value of landmarks, for the initial position PDF (Default = 3m)

float SIFTsLoadEllipsoidWidth {0.05f}

[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 {2.0f}

[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)

int SIFTs_numberOfKLTKeypoints {60}

Number of points to extract in the image.

float SIFTs_stereo_maxDepth {15.0f}

Maximum depth of 3D landmarks when loading a landmarks map from a stereo image observation.

float SIFTs_epipolar_TH {1.5f}

Maximum distance (in pixels) from a point to a certain epipolar line to be considered a potential match.

bool PLOT_IMAGES {false}

Indicates if the images (as well as the SIFT detected features) should be shown in a window.

mrpt::vision::CFeatureExtraction::TOptions SIFT_feat_options

Parameters of the SIFT feature detector/descriptors while inserting images in the landmark map.

There exists another SIFT_feat_options field in the likelihoodOptions member.

All parameters of this field can be loaded from a config file. See mrpt::vision::CFeatureExtraction::TOptions for the names of the expected fields.

Construction

TInsertionOptions()

Initialization of default parameters.

Methods

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

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

virtual void dumpToTextStream(std::ostream& out) const

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.