Main MRPT website > C++ reference
MRPT logo
Public Member Functions | Public Attributes

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


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 140 of file CMultiMetricMapPDF.h.

#include <mrpt/slam/CMultiMetricMapPDF.h>

Inheritance diagram for mrpt::slam::CMultiMetricMapPDF::TPredictionParams:
Inheritance graph
[legend]

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) const
 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
CICP::TConfigParams icp_params
 ICP parameters, used only when "PF_algorithm=2" in the particle filter.

Constructor & Destructor Documentation

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

Default settings method.


Member Function Documentation

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

Member Data Documentation

ICP parameters, used only when "PF_algorithm=2" in the particle filter.

Definition at line 178 of file CMultiMetricMapPDF.h.

[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 170 of file CMultiMetricMapPDF.h.

Definition at line 176 of file CMultiMetricMapPDF.h.

[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

Definition at line 165 of file CMultiMetricMapPDF.h.

[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 174 of file CMultiMetricMapPDF.h.




Page generated by Doxygen 1.7.3 for MRPT 0.9.4 SVN: at Sat Mar 26 06:40:17 UTC 2011