struct mrpt::maps::CLandmarksMap::TLikelihoodOptions
Overview
With this struct options are provided to the likelihood computations.
#include <mrpt/maps/CLandmarksMap.h> struct TLikelihoodOptions: public mrpt::config::CLoadableOptions { // structs struct TGPSOrigin; // fields unsigned int rangeScan2D_decimation {20}; double SIFTs_sigma_euclidean_dist {0.30f}; double SIFTs_sigma_descriptor_dist {100.0f}; float SIFTs_mahaDist_std {4.0f}; float SIFTnullCorrespondenceDistance {4.0f}; int SIFTs_decimation {1}; mrpt::vision::CFeatureExtraction::TOptions SIFT_feat_options; float beaconRangesStd {0.08f}; bool beaconRangesUseObservationStd {false}; float extRobotPoseStd {0.05f}; struct mrpt::maps::CLandmarksMap::TLikelihoodOptions::TGPSOrigin GPSOrigin; float GPS_sigma {1.0f}; // construction TLikelihoodOptions(); // 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
unsigned int rangeScan2D_decimation {20}
The number of rays from a 2D range scan will be decimated by this factor (default = 1, no decimation)
int SIFTs_decimation {1}
Considers 1 out of “SIFTs_decimation” visual landmarks in the observation during the likelihood computation.
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 insertionOptions 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.
float beaconRangesStd {0.08f}
The standard deviation used for Beacon ranges likelihood (default=0.08) [meters].
See also:
bool beaconRangesUseObservationStd {false}
(Default: false) If true, beaconRangesStd
is ignored and each individual CObservationBeaconRanges::stdError
field is used instead.
float extRobotPoseStd {0.05f}
The standard deviation used for external robot poses likelihood (default=0.05) [meters].
float GPS_sigma {1.0f}
A constant “sigma” for GPS localization data (in meters)
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.