#include <mrpt/slam/CMultiMetricMapPDF.h>
Public Member Functions | |
TPredictionParams () | |
Default settings method. | |
void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) |
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 |
Definition at line 130 of file CMultiMetricMapPDF.h.
mrpt::slam::CMultiMetricMapPDF::TPredictionParams::TPredictionParams | ( | ) |
Default settings method.
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] |
[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 159 of file CMultiMetricMapPDF.h.
Definition at line 165 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 Default = 0
Definition at line 154 of file CMultiMetricMapPDF.h.
COccupancyGridMap2D::TLikelihoodOptions mrpt::slam::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 163 of file CMultiMetricMapPDF.h.
Page generated by Doxygen 1.5.9 for MRPT 0.7.1 SVN: at Mon Aug 17 22:21:34 EDT 2009 |