Struct CMultiMetricMapPDF::TPredictionParams
Defined in File CMultiMetricMapPDF.h
Nested Relationships
This struct is a nested type of Class CMultiMetricMapPDF.
Inheritance Relationships
Base Type
public mrpt::config::CLoadableOptions
Struct Documentation
-
struct TPredictionParams : public mrpt::config::CLoadableOptions
The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.
See also
prediction_and_update
Public Functions
-
TPredictionParams() = default
Default settings method
-
void loadFromConfigFile(const mrpt::config::CConfigFileBase &source, const std::string §ion) override
-
void dumpToTextStream(std::ostream &out) const override
Public Members
-
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::TKLDParams KLD_params
-
mrpt::slam::CICP::TConfigParams icp_params
ICP parameters, used only when “PF_algorithm=2” in the particle filter.
-
TPredictionParams() = default