The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter. More...
#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 |
| CICP::TConfigParams | icp_params |
| ICP parameters, used only when "PF_algorithm=2" in the particle filter. | |
The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.
Definition at line 139 of file CMultiMetricMapPDF.h.
| mrpt::slam::CMultiMetricMapPDF::TPredictionParams::TPredictionParams | ( | ) |
Default settings method.
| void mrpt::slam::CMultiMetricMapPDF::TPredictionParams::dumpToTextStream | ( | CStream & | out | ) | const [virtual] |
Implements mrpt::utils::CLoadableOptions.
| void mrpt::slam::CMultiMetricMapPDF::TPredictionParams::loadFromConfigFile | ( | const mrpt::utils::CConfigFileBase & | source, | |
| const std::string & | section | |||
| ) | [virtual] |
Implements mrpt::utils::CLoadableOptions.
ICP parameters, used only when "PF_algorithm=2" in the particle filter.
Definition at line 177 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 169 of file CMultiMetricMapPDF.h.
Definition at line 175 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 164 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 173 of file CMultiMetricMapPDF.h.
| Page generated by Doxygen 1.6.1 for MRPT 0.9.0 SVN: at Mon Jun 7 06:47:58 UTC 2010 |