9 #ifndef CMultiMetricMapPDF_H
10 #define CMultiMetricMapPDF_H
42 mapTillNow( mapsInitializers ),
62 public
mrpt::utils::CSerializable,
76 void prediction_and_update_pfStandardProposal(
83 void prediction_and_update_pfOptimalProposal(
90 void prediction_and_update_pfAuxiliaryPFOptimal(
100 bool averageMapIsUpdated;
108 std::vector<uint32_t> SF2robotPath;
129 void loadFromConfigFile(
131 const std::string §ion);
135 void dumpToTextStream(
CStream &out)
const;
172 virtual ~CMultiMetricMapPDF();
175 void clear(
const CPose2D &initialPose );
178 void clear(
const CPose3D &initialPose );
183 void getEstimatedPosePDFAtTime(
211 void getPath(
size_t i, std::deque<math::TPose3D> &out_path)
const;
215 double getCurrentEntropyOfPaths();
219 double getCurrentJointEntropy();
223 void updateSensoryFrameSequence();
227 void saveCurrentPathEstimationToTextFile(
const std::string &fil );
236 void rebuildAverageMap();
246 const TPose3D * getLastPose(
const size_t i)
const;
248 void PF_SLAM_implementation_custom_update_particle_with_new_pose(
250 const TPose3D &newPose)
const;
255 bool PF_SLAM_implementation_doWeHaveValidObservations(
256 const CParticleList &particles,
259 bool PF_SLAM_implementation_skipRobotMovement()
const;
262 double PF_SLAM_computeObservationLikelihoodForParticle(
264 const size_t particleIndexForMap,
size_t getNumberOfObservationsInSimplemap() const
Get the number of CSensoryFrame inserted into the internal member SFs.
The ICP algorithm configuration data.
This class stores any customizable set of metric maps.
The virtual base class which provides a unified interface for all persistent objects in MRPT...
Option set for KLD algorithm.
COccupancyGridMap2D::TLikelihoodOptions update_gridMapLikelihoodOptions
[update stage] If the likelihood is computed through the occupancy grid map, then this structure is p...
std::deque< TPose3D > robotPath
Declares a class for storing a collection of robot actions.
This class allows loading and storing values and vectors of different types from a configuration text...
A set of common data shared by PF implementations for both SLAM and localization. ...
CRBPFParticleData CParticleDataContent
This is the type inside the corresponding CParticleData class.
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
#define DEFINE_SERIALIZABLE_PRE_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This declaration must be inserted in all CSerializable classes definition, before the class declarati...
float newInfoIndex
An index [0,1] measuring how much information an observation aports to the map (Typ.
CMultiMetricMap mapTillNow
This class acts as a common interface to the different interfaces (see CParticleFilter::TParticleFilt...
CICP::TConfigParams icp_params
ICP parameters, used only when "PF_algorithm=2" in the particle filter.
This template class declares the array of particles and its internal data, managing some memory-relat...
This class stores a sequence of
pairs, thus a "metric map" can be t...
The struct for passing extra simulation parameters to the prediction/update stage when running a part...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define DEFINE_SERIALIZABLE(class_name)
This declaration must be inserted in all CSerializable classes definition, within the class declarati...
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
A class used to store a 2D pose.
This class implements a Rao-Blackwelized Particle Filter (RBPF) approach to map building (SLAM)...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
The configuration of a particle filter.
Auxiliary class used in mrpt::slam::CMultiMetricMapPDF.
int pfOptimalProposal_mapSelection
[pf optimal proposal only] Only for PF algorithm=2 (Exact "pfOptimalProposal") Select the map on whic...
Declares a class that represents a Rao-Blackwellized set of particles for solving the SLAM problem (T...
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
This is a virtual base class for sets of options than can be loaded from and/or saved to configuratio...
float ICPGlobalAlign_MinQuality
[prediction stage][pf optimal proposal only] If useICPGlobalAlign_withGrid=true, this is the minimum ...
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
A curiously recurring template pattern (CRTP) approach to providing the basic functionality of any CP...
With this struct options are provided to the observation likelihood computation process.