The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.
Definition at line 117 of file CMultiMetricMapPDF.h.
#include <mrpt/maps/CMultiMetricMapPDF.h>
Public Member Functions | |
TPredictionParams () | |
Default settings method. More... | |
void | loadFromConfigFile (const mrpt::utils::CConfigFileBase &source, const std::string §ion) override |
This method load the options from a ".ini"-like file or memory-stored string list. More... | |
void | dumpToTextStream (mrpt::utils::CStream &out) const override |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream. More... | |
void | loadFromConfigFileName (const std::string &config_file, const std::string §ion) |
Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file. More... | |
virtual void | saveToConfigFile (mrpt::utils::CConfigFileBase &target, const std::string §ion) const |
This method saves the options to a ".ini"-like file or memory-stored string list. More... | |
void | saveToConfigFileName (const std::string &config_file, const std::string §ion) const |
Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file. More... | |
void | dumpToConsole () const |
Just like dumpToTextStream() but sending the text to the console (std::cout) More... | |
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. More... | |
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. More... | |
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. More... | |
mrpt::slam::TKLDParams | KLD_params |
mrpt::slam::CICP::TConfigParams | icp_params |
ICP parameters, used only when "PF_algorithm=2" in the particle filter. More... | |
Static Protected Member Functions | |
static void | dumpVar_int (CStream &out, const char *varName, int v) |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR. More... | |
static void | dumpVar_float (CStream &out, const char *varName, float v) |
static void | dumpVar_double (CStream &out, const char *varName, double v) |
static void | dumpVar_bool (CStream &out, const char *varName, bool v) |
static void | dumpVar_string (CStream &out, const char *varName, const std::string &v) |
CMultiMetricMapPDF::TPredictionParams::TPredictionParams | ( | ) |
Default settings method.
Definition at line 633 of file CMultiMetricMapPDF.cpp.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Definition at line 44 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::dumpToTextStream(), and loadable_opts_my_cout.
Referenced by mrpt::hmtslam::CTopLCDetector_GridMatching::computeTopologicalObservationModel(), and mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams().
|
overridevirtual |
This method should clearly display all the contents of the structure in textual form, sending it to a CStream.
The default implementation in this base class relies on saveToConfigFile() to generate a plain text representation of all the parameters.
Reimplemented from mrpt::utils::CLoadableOptions.
Definition at line 645 of file CMultiMetricMapPDF.cpp.
References mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 65 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 59 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 54 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
Definition at line 49 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
staticprotectedinherited |
Definition at line 71 of file CLoadableOptions.cpp.
References LOADABLEOPTS_COLUMN_WIDTH, and mrpt::utils::CStream::printf().
|
overridevirtual |
This method load the options from a ".ini"-like file or memory-stored string list.
Only those parameters found in the given "section" and having the same name that the variable are loaded. Those not found in the file will stay with their previous values (usually the default values loaded at initialization). An example of an ".ini" file:
Implements mrpt::utils::CLoadableOptions.
Definition at line 667 of file CMultiMetricMapPDF.cpp.
References MRPT_LOAD_CONFIG_VAR, and mrpt::utils::CConfigFileBase::read_int().
|
inherited |
Behaves like loadFromConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to load the file.
Definition at line 22 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::loadFromConfigFile().
Referenced by mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams().
|
virtualinherited |
This method saves the options to a ".ini"-like file or memory-stored string list.
Reimplemented in mrpt::vision::TMultiResDescOptions, mrpt::vision::TMultiResDescMatchOptions, mrpt::nav::CPTG_RobotShape_Circular, mrpt::nav::CPTG_RobotShape_Polygonal, mrpt::nav::CParameterizedTrajectoryGenerator, mrpt::nav::CAbstractPTGBasedReactive::TAbstractPTGNavigatorParams, mrpt::nav::CAbstractNavigator::TAbstractNavigatorParams, mrpt::nav::CPTG_DiffDrive_CollisionGridBased, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::bayes::CParticleFilter::TParticleFilterOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::nav::CHolonomicND::TOptions, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, mrpt::nav::CHolonomicVFF::TOptions, mrpt::maps::CPointCloudFilterByDistance::TOptions, mrpt::nav::CPTG_DiffDrive_C, mrpt::nav::CPTG_DiffDrive_alpha, mrpt::nav::CMultiObjMotionOpt_Scalarization::TParams, mrpt::nav::CPTG_DiffDrive_CC, mrpt::nav::CPTG_DiffDrive_CCS, mrpt::nav::CPTG_DiffDrive_CS, and mrpt::nav::CPTG_Holo_Blend.
Definition at line 29 of file CLoadableOptions.cpp.
References MRPT_UNUSED_PARAM.
Referenced by mrpt::utils::CLoadableOptions::dumpToTextStream(), and mrpt::utils::CLoadableOptions::saveToConfigFileName().
|
inherited |
Behaves like saveToConfigFile, but you can pass directly a file name and a temporary CConfigFile object will be created automatically to save the file.
Definition at line 37 of file CLoadableOptions.cpp.
References mrpt::utils::CLoadableOptions::saveToConfigFile().
mrpt::slam::CICP::TConfigParams mrpt::maps::CMultiMetricMapPDF::TPredictionParams::icp_params |
ICP parameters, used only when "PF_algorithm=2" in the particle filter.
Definition at line 159 of file CMultiMetricMapPDF.h.
float mrpt::maps::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 147 of file CMultiMetricMapPDF.h.
mrpt::slam::TKLDParams mrpt::maps::CMultiMetricMapPDF::TPredictionParams::KLD_params |
Definition at line 155 of file CMultiMetricMapPDF.h.
Referenced by mrpt::maps::CMultiMetricMapPDF::prediction_and_update().
int mrpt::maps::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 3: Pointsmap -> Uses Scan matching-based approximation with a map of points (based on Stachniss' work) Default = 0
Definition at line 140 of file CMultiMetricMapPDF.h.
COccupancyGridMap2D::TLikelihoodOptions mrpt::maps::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 153 of file CMultiMetricMapPDF.h.
Page generated by Doxygen 1.8.14 for MRPT 1.9.9 Git: ae4571287 Thu Nov 23 00:06:53 2017 +0100 at dom oct 27 23:51:55 CET 2019 |