MRPT logo

mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams Struct Reference

The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter. More...

#include <mrpt/slam/CMultiMetricMapPDF.h>

Inheritance diagram for mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams:

mrpt::utils::CLoadableOptions

List of all members.

Public Member Functions

 TPredictionParams ()
 Default settings method.
void loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string &section)
 See utils::CLoadableOptions.
void dumpToTextStream (CStream &out)
 See utils::CLoadableOptions.

Public Attributes

int pfOptimalProposal_mapSelection
 [pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on which to calculate the optimal proposal distribution.
float ICPGlobalAlign_MinQuality
 [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.
COccupancyGridMap2D::TLikelihoodOptions update_gridMapLikelihoodOptions
 [update stage] If the likelihood is computed through the occupancy grid map, then this structure is passed to the map when updating the particles weights in the update stage.
TKLDParams KLD_params


Detailed Description

The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.

See also:
prediction_and_update

Definition at line 130 of file CMultiMetricMapPDF.h.


Constructor & Destructor Documentation

mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::TPredictionParams (  ) 

Default settings method.


Member Function Documentation

void mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream ( CStream out  )  [virtual]

void mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::loadFromConfigFile ( const mrpt::utils::CConfigFileBase source,
const std::string &  section 
) [virtual]


Member Data Documentation

float mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::ICPGlobalAlign_MinQuality

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

Definition at line 160 of file CMultiMetricMapPDF.h.

TKLDParams mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::KLD_params

Definition at line 166 of file CMultiMetricMapPDF.h.

int mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::pfOptimalProposal_mapSelection

[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 Default = 0

Definition at line 155 of file CMultiMetricMapPDF.h.

COccupancyGridMap2D::TLikelihoodOptions mrpt::slam::CMultiMetricMapPDF::CMultiMetricMapPDF::TPredictionParams::update_gridMapLikelihoodOptions

[update stage] If the likelihood is computed through the occupancy grid map, then this structure is passed to the map when updating the particles weights in the update stage.

Definition at line 164 of file CMultiMetricMapPDF.h.




Page generated by Doxygen 1.5.8 for MRPT 0.6.5 SVN: at Sun Aug 9 21:47:23 CEST 2009