struct mrpt::maps::CMultiMetricMapPDF::TPredictionParams¶
The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.
See also:
#include <mrpt/maps/CMultiMetricMapPDF.h> struct TPredictionParams: public mrpt::config::CLoadableOptions { // fields int pfOptimalProposal_mapSelection {0}; float ICPGlobalAlign_MinQuality {0.70f}; mrpt::slam::TKLDParams KLD_params; mrpt::slam::CICP::TConfigParams icp_params; // 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¶
int pfOptimalProposal_mapSelection {0}
[pf optimal proposal only] Only for PF algorithm=2 (Exact “pfOptimalProposal”) Select the map on which to calculate the optimal proposal distribution.
Values: 0: Gridmap -> Uses Scan matching-based approximation (based on Stachniss’ work) 1: Landmarks -> Uses matching to approximate optimal 2: Beacons -> Used for exact optimal proposal in RO-SLAM 3: Pointsmap -> Uses Scan matching-based approximation with a map of points (based on Stachniss’ work) Default = 0
float ICPGlobalAlign_MinQuality {0.70f}
[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum quality ratio [0,1] of the alignment such as it will be accepted.
Otherwise, raw odometry is used for those bad cases (default=0.7).
mrpt::slam::CICP::TConfigParams icp_params
ICP parameters, used only when “PF_algorithm=2” in the particle filter.
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.