9 #ifndef CLocalMetricHypothesis_H 10 #define CLocalMetricHypothesis_H 27 namespace poses {
class CPose3DPDFParticles; }
49 metricMaps( mapsInitializers ),
67 public
mrpt::utils::CSerializable
90 std::map<TPoseID,mrpt::obs::CSensoryFrame>
m_SFs;
108 unsigned int pose2idx(
const TPoseID &
id)
const;
116 void getAs3DScene( mrpt::opengl::CSetOfObjectsPtr &objs )
const;
126 void getPathParticles( std::map< TPoseID, mrpt::poses::CPose3DPDFParticles > &outList )
const;
136 void getRelativePose(
147 void changeCoordinateOrigin(
const TPoseID &newOrigin );
150 void rebuildMetricMaps();
157 void clearRobotPoses();
183 void updateAreaFromLMH(
185 bool eraseSFsFromLMH =
false );
196 void prediction_and_update_pfAuxiliaryPFOptimal(
202 void prediction_and_update_pfOptimalProposal(
216 mutable std::vector<double> m_maxLikelihood;
222 mutable unsigned int m_movementDrawsIdx;
This class provides simple critical sections functionality.
Implements a 2D local SLAM method based on a RBPF over an occupancy grid map.
THypothesisID m_ID
The unique ID of the hypothesis (Used for accessing mrpt::slam::CHierarchicalMHMap).
The virtual base class which provides a unified interface for all persistent objects in MRPT...
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
TMapPoseID2Pose3D robotPoses
std::vector< std::map< TPoseID, double > > m_log_w_metric_history
The historic log-weights of the metric observations inserted in this LMH, for each particle...
Column vector, like Eigen::MatrixX*, but automatically initialized to zeros since construction...
std::map< TYPE1, TYPE2, std::less< TYPE1 >, Eigen::aligned_allocator< std::pair< const TYPE1, TYPE2 > > > map_t
double m_log_w
Log-weight of this hypothesis.
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
A set of TMetricMapInitializer structures, passed to the constructor CMultiMetricMap::CMultiMetricMap...
An implementation of Hybrid Metric Topological SLAM (HMT-SLAM).
mrpt::slam::CIncrementalMapPartitioner partitioner
Declares a class for storing a collection of robot actions.
mrpt::obs::CActionRobotMovement2D m_accumRobotMovement
Used in CLSLAM_RBPF_2DLASER.
int64_t THypothesisID
An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...
Represents a probabilistic 2D movement of the robot mobile base.
A class for storing a list of text lines.
#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...
TPoseIDList m_posesPendingAddPartitioner
The list of poseIDs waiting to be added to the graph partitioner, what happens in the LSLAM thread ma...
std::map< TPoseID, CHMHMapNode::TNodeID > m_nodeIDmemberships
The hybrid map node membership for each robot pose.
mrpt::utils::safe_ptr< CHMTSLAM > m_parent
For quick access to our parent object.
Declares a class for storing a "sensory frame", a set of "observations" taken by the robot approximat...
This class is used in HMT-SLAM to represent each of the Local Metric Hypotheses (LMHs).
std::map< uint32_t, TPoseID > idx2pose
For the poses in "partitioner".
std::vector< TPoseID > TPoseIDList
Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class keeps the data re...
mrpt::aligned_containers< TPoseID, mrpt::poses::CPose3D >::map_t TMapPoseID2Pose3D
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...
bool m_accumRobotMovementIsValid
Used in CLSLAM_RBPF_2DLASER.
This class can be used to make partitions on a map/graph build from observations taken at some poses/...
std::deque< CParticleData > CParticleList
Use this type to refer to the list of particles m_particles.
std::map< TPoseID, mrpt::obs::CSensoryFrame > m_SFs
The SF gathered at each robot pose.
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
The configuration of a particle filter.
synch::CCriticalSection m_lock
Critical section for threads signaling they are working with the LMH.
std::set< CHMHMapNode::TNodeID > TNodeIDSet
This class stores any customizable set of metric maps.
CLSLAMParticleData(const mrpt::maps::TSetOfMetricMapInitializers *mapsInitializers=NULL)
synch::CCriticalSection lock
CS to access the entire struct.
#define DEFINE_SERIALIZABLE_POST_CUSTOM_BASE_LINKAGE(class_name, base_name, _LINKAGE_)
TNodeIDList m_areasPendingTBI
The list of area IDs waiting to be processed by the TBI (topological bayesian inference) engines to s...
TNodeIDSet m_neighbors
The list of all areas sourronding the current one (this includes the current area itself)...
mrpt::aligned_containers< CPose2D >::vector_t StdVector_CPose2D
Eigen aligment-compatible container.
A wrapper class for pointers that can be safely copied with "=" operator without problems.
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
mrpt::utils::TNodeID TNodeID
The type of the IDs of nodes.
TPoseID m_currentRobotPose
The current robot pose (its global unique ID) for this hypothesis.
mrpt::maps::CMultiMetricMap metricMaps