The struct for passing extra simulation parameters to the prediction/update stage when running a particle filter.
Definition at line 107 of file maps/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) MRPT_OVERRIDE |
This method load the options from a ".ini"-like file or memory-stored string list. More... | |
void | dumpToTextStream (mrpt::utils::CStream &out) const MRPT_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) |
mrpt::maps::CMultiMetricMapPDF::TPredictionParams::TPredictionParams | ( | ) |
Default settings method.
|
inherited |
Just like dumpToTextStream() but sending the text to the console (std::cout)
Referenced by mrpt::graphslam::deciders::CRangeScanEdgeRegistrationDecider< GRAPH_T >::printParams(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::printParams(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::printParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::printParams(), and mrpt::graphslam::deciders::CLoopCloserERD< GRAPH_T >::printParams().
|
virtual |
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.
|
staticprotectedinherited |
|
staticprotectedinherited |
|
staticprotectedinherited |
|
staticprotectedinherited |
Used to print variable info from dumpToTextStream with the macro LOADABLEOPTS_DUMP_VAR.
|
staticprotectedinherited |
|
virtual |
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.
|
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.
Referenced by mrpt::graphslam::deciders::CRangeScanEdgeRegistrationDecider< GRAPH_T >::loadParams(), mrpt::graphslam::deciders::CICPCriteriaNRD< GRAPH_T >::loadParams(), mrpt::graphslam::deciders::CICPCriteriaERD< GRAPH_T >::loadParams(), mrpt::graphslam::optimizers::CLevMarqGSO< GRAPH_T >::loadParams(), and mrpt::graphslam::deciders::CLoopCloserERD< 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::CHolonomicND::TOptions, mrpt::nav::CWaypointsNavigator::TWaypointsNavigatorParams, mrpt::nav::CHolonomicFullEval::TOptions, mrpt::nav::CReactiveNavigationSystem::TReactiveNavigatorParams, mrpt::nav::CHolonomicVFF::TOptions, mrpt::nav::CMultiObjectiveMotionOptimizerBase::TParamsBase, 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.
|
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.
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 137 of file maps/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 129 of file maps/CMultiMetricMapPDF.h.
mrpt::slam::TKLDParams mrpt::maps::CMultiMetricMapPDF::TPredictionParams::KLD_params |
Definition at line 135 of file maps/CMultiMetricMapPDF.h.
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 124 of file maps/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 133 of file maps/CMultiMetricMapPDF.h.
Page generated by Doxygen 1.8.13 for MRPT 1.5.3 at Mon Oct 30 10:27:08 UTC 2017 |