class mrpt::slam::CGridMapAligner::TConfigParams

The ICP algorithm configuration data.

#include <mrpt/slam/CGridMapAligner.h>

class TConfigParams: public mrpt::config::CLoadableOptions
{
public:
    //
fields

    TAlignerMethod methodSelection {CGridMapAligner::amModifiedRANSAC};
    mrpt::vision::TDescriptorType feature_descriptor {             mrpt::vision::descPolarImages};
    mrpt::vision::CFeatureExtraction::TOptions feature_detector_options;
    float ransac_minSetSizeRatio {0.20f};
    float ransac_SOG_sigma_m {0.10f};
    float ransac_mahalanobisDistanceThreshold {6.0f};
    double ransac_chi2_quantile {0.99};
    double ransac_prob_good_inliers {0.9999};
    float featsPerSquareMeter {0.015f};
    float threshold_max {0.15f};
    float threshold_delta {0.10f};
    float min_ICP_goodness {0.30f};
    double max_ICP_mahadist {10.0};
    double maxKLd_for_merge {0.9};
    bool save_feat_coors {false};
    bool debug_show_corrs {false};
    bool debug_save_map_pairs {false};

    // construction

    TConfigParams();

    //
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

TAlignerMethod methodSelection {CGridMapAligner::amModifiedRANSAC}

The aligner method:

mrpt::vision::TDescriptorType feature_descriptor {           mrpt::vision::descPolarImages}

The feature descriptor to use: 0=detector already has descriptor, 1= SIFT, 2=SURF, 4=Spin images, 8=Polar images, 16=log-polar images.

mrpt::vision::CFeatureExtraction::TOptions feature_detector_options

All the parameters for the feature detector.

float ransac_minSetSizeRatio {0.20f}

RANSAC-step options:

See also:

CICP::robustRigidTransformation The ratio of landmarks that must be inliers to accepto an hypotheses (typ: 0.20)

float ransac_SOG_sigma_m {0.10f}

The square root of the uncertainty normalization variance var_m (see papers…)

float ransac_mahalanobisDistanceThreshold {6.0f}

[amRobustMatch method only] RANSAC-step options:

See also:

CICP::robustRigidTransformation

double ransac_chi2_quantile {0.99}

[amModifiedRANSAC method only] The quantile used for chi-square thresholding (default=0.99)

double ransac_prob_good_inliers {0.9999}

Probability of having a good inliers (def:0,9999), used for automatic number of iterations.

float featsPerSquareMeter {0.015f}

Features extraction from grid map: How many features to extract.

float threshold_max {0.15f}

Correspondences are considered if their distances are below this threshold (in the range [0,1]) (default=0.15).

float threshold_delta {0.10f}

Correspondences are considered if their distances to the best match are below this threshold (in the range [0,1]) (default=0.15).

float min_ICP_goodness {0.30f}

The minimum goodness (0-1) of the post-matching ICP to accept a hypothesis as good (default=0.30)

double max_ICP_mahadist {10.0}

The maximum Mahalanobis distance between the initial and final poses in the ICP not to discard the hypothesis (default=10)

double maxKLd_for_merge {0.9}

Maximum KL-divergence for merging modes of the SOG (default=0.9)

bool save_feat_coors {false}

DEBUG - Dump all feature correspondences in a directory “grid_feats”.

bool debug_show_corrs {false}

DEBUG - Show graphs with the details of each feature correspondences.

bool debug_save_map_pairs {false}

DEBUG - Save the pair of maps with all the pairings.

Construction

TConfigParams()

Initializer for default values:

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.