Main MRPT website > C++ reference for MRPT 1.9.9
List of all members | Public Types | Public Member Functions | Static Public Member Functions | Protected Member Functions | Protected Attributes | Friends
mrpt::hmtslam::CHierarchicalMHMap Class Reference

Detailed Description

The most high level class for storing hybrid, multi-hypothesis maps in a graph-based model.

This class is used within the HMT-SLAM implementation in CHMTSLAM.

See also
CHMTSLAM, CHMHMapArc, CHMHMapNode, CHierarchicalMHMapPartition

Definition at line 29 of file CHierarchicalMHMap.h.

#include <mrpt/hmtslam/CHierarchicalMHMap.h>

Inheritance diagram for mrpt::hmtslam::CHierarchicalMHMap:
Inheritance graph

Public Types

typedef TNodeList::iterator iterator
 
typedef TNodeList::const_iterator const_iterator
 
typedef std::vector< CHMHMapNode::TNodeIDTNodeIDsList
 A type that reprensents a sequence of node IDs. More...
 

Public Member Functions

voidoperator new (size_t size)
 
voidoperator new[] (size_t size)
 
void operator delete (void *ptr) noexcept
 
void operator delete[] (void *ptr) noexcept
 
void operator delete (void *memory, void *ptr) noexcept
 
voidoperator new (size_t size, const std::nothrow_t &) noexcept
 
void operator delete (void *ptr, const std::nothrow_t &) noexcept
 
 CHierarchicalMHMap ()
 Default constructor. More...
 
void dumpAsXMLfile (std::string fileName) const
 Destructor. More...
 
void loadFromXMLfile (std::string fileName)
 Load a graph from a XML file. More...
 
virtual ~CHierarchicalMHMap ()
 
void clear ()
 Erase all the contents of map (It delete all nodes/arcs objects) More...
 
virtual mxArraywriteToMatlab () const
 Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class. More...
 
const_iterator begin () const
 Returns an iterator to the first node in the graph. More...
 
iterator begin ()
 Returns an iterator to the first node in the graph. More...
 
const_iterator end () const
 Returns an iterator to the end of the list of nodes in the graph. More...
 
iterator end ()
 Returns an iterator to the end of the list of nodes in the graph. More...
 
size_t nodeCount () const
 Returns the number of nodes in the partition: More...
 
size_t arcCount () const
 Returns the number of arcs in the partition: More...
 
CHMHMapNode::Ptr getFirstNode ()
 Returns the first node in the graph, or nullptr if it does not exist. More...
 
CHMHMapNode::Ptr getNodeByID (CHMHMapNode::TNodeID id)
 Returns the node with the given ID, or nullptr if it does not exist. More...
 
const CHMHMapNode::Ptr getNodeByID (CHMHMapNode::TNodeID id) const
 Returns the node with the given ID, or nullptr if it does not exist. More...
 
CHMHMapNode::Ptr getNodeByLabel (const std::string &label, const THypothesisID &hypothesisID)
 Returns the node with the given label (case insensitive) for some given hypothesis ID, or nullptr if it does not exist. More...
 
const CHMHMapNode::Ptr getNodeByLabel (const std::string &label, const THypothesisID &hypothesisID) const
 Returns the node with the given label (case insensitive) for some given hypothesis ID, or nullptr if it does not exist. More...
 
void saveAreasDiagramForMATLAB (const std::string &filName, const CHMHMapNode::TNodeID &idReferenceNode, const THypothesisID &hypothesisID) const
 Returns a partition of this graph only with nodes at a given level in the hierarchy (0=ground level,1=parent level,etc) More...
 
void saveAreasDiagramWithEllipsedForMATLAB (const std::string &filName, const CHMHMapNode::TNodeID &idReferenceNode, const THypothesisID &hypothesisID, float uncertaintyExagerationFactor=1.0f, bool drawArcs=false, unsigned int numberOfIterationsForOptimalGlobalPoses=4) const
 Saves a MATLAB script that represents graphically the nodes with type="Area" in this hierarchical-map(partition), using the stated node as global coordinates reference, and drawing the ellipses of the localization uncertainty for each node. More...
 
void saveGlobalMapForMATLAB (const std::string &filName, const THypothesisID &hypothesisID, const CHMHMapNode::TNodeID &idReferenceNode) const
 Saves a MATLAB script that represents graphically the reconstructed "global map" ADDITIONAL NOTES: More...
 
void findPathBetweenNodes (const CHMHMapNode::TNodeID &nodeFrom, const CHMHMapNode::TNodeID &nodeTo, const THypothesisID &hypothesisID, TArcList &out_path, bool direction=false) const
 The Dijkstra algorithm for finding the shortest path between a pair of nodes. More...
 
void computeCoordinatesTransformationBetweenNodes (const CHMHMapNode::TNodeID &nodeFrom, const CHMHMapNode::TNodeID &nodeTo, mrpt::poses::CPose3DPDFParticles &posePDF, const THypothesisID &hypothesisID, unsigned int particlesCount=100, float additionalNoiseXYratio=0.02, float additionalNoisePhiRad=mrpt::utils::DEG2RAD(0.1)) const
 Draw a number of samples according to the PDF of the coordinates transformation between a pair of "Area"'s nodes. More...
 
float computeMatchProbabilityBetweenNodes (const CHMHMapNode::TNodeID &nodeFrom, const CHMHMapNode::TNodeID &nodeTo, float &maxMatchProb, mrpt::poses::CPose3DPDFSOG &estimatedRelativePose, const THypothesisID &hypothesisID, unsigned int monteCarloSamplesPose=300)
 Computes the probability [0,1] of two areas' gridmaps to "match" (loop closure), according to the grid maps and pose uncertainty from information in arcs (uses a Monte Carlo aproximation) If there is not enough information or a robust estimation cannot be found, there will not be particles in "estimatedRelativePose". More...
 
void findArcsBetweenNodes (const CHMHMapNode::TNodeID &node1, const CHMHMapNode::TNodeID &node2, const THypothesisID &hypothesisID, TArcList &out_listArcs) const
 Returns all the arcs between a pair of nodes: More...
 
void findArcsOfTypeBetweenNodes (const CHMHMapNode::TNodeID &node1id, const CHMHMapNode::TNodeID &node2id, const THypothesisID &hypothesisID, const std::string &arcType, TArcList &ret) const
 Returns the arcs between a pair of nodes of a given type. More...
 
CHMHMapArc::Ptr findArcOfTypeBetweenNodes (const CHMHMapNode::TNodeID &node1id, const CHMHMapNode::TNodeID &node2id, const THypothesisID &hypothesisID, const std::string &arcType, bool &isInverted) const
 Returns the first arc between a pair of nodes of a given type, and if it is in the opposite direction. More...
 
bool areNodesNeightbour (const CHMHMapNode::TNodeID &node1, const CHMHMapNode::TNodeID &node2, const THypothesisID &hypothesisID, const char *requiredAnnotation=nullptr) const
 Returns whether two nodes are "neightbour", i.e. More...
 
void computeGloballyConsistentNodeCoordinates (std::map< CHMHMapNode::TNodeID, mrpt::poses::CPose3DPDFGaussian, std::less< CHMHMapNode::TNodeID >, Eigen::aligned_allocator< std::pair< const CHMHMapNode::TNodeID, mrpt::poses::CPose3DPDFGaussian >>> &nodePoses, const CHMHMapNode::TNodeID &idReferenceNode, const THypothesisID &hypothesisID, const unsigned int &numberOfIterations=2) const
 This methods implements a Lu&Milios-like globally optimal estimation for the global coordinates of all the nodes in the graph according to all available arcs with relative pose information. More...
 
void getAs3DScene (mrpt::opengl::COpenGLScene &outScene, const CHMHMapNode::TNodeID &idReferenceNode, const THypothesisID &hypothesisID, const unsigned int &numberOfIterationsForOptimalGlobalPoses=5, const bool &showRobotPoseIDs=true) const
 Returns a 3D scene reconstruction of the hierarchical map. More...
 
void dumpAsText (utils::CStringList &s) const
 Return a textual description of the whole graph. More...
 
double computeOverlapProbabilityBetweenNodes (const CHMHMapNode::TNodeID &nodeFrom, const CHMHMapNode::TNodeID &nodeTo, const THypothesisID &hypothesisID, const size_t &monteCarloSamples=100, const float margin_to_substract=6) const
 Computes the probability [0,1] of two areas' gridmaps to overlap, via a Monte Carlo aproximation. More...
 
RTTI classes and functions
mrpt::utils::CObject::Ptr duplicateGetSmartPtr () const
 Returns a copy of the object, indepently of its class, as a smart pointer (the newly created object will exist as long as any copy of this smart pointer). More...
 

Static Public Member Functions

static voidoperator new (size_t size, void *ptr)
 

Protected Member Functions

void onNodeAddition (CHMHMapNode::Ptr &node)
 Event handler to be called just after a node has being created: it will be added to the internal list. More...
 
void onArcAddition (CHMHMapArc::Ptr &arc)
 Event handler to be called just after an arc has being created: it will be added to the internal list. More...
 
void onNodeDestruction (CHMHMapNode *node)
 Event handler to be called just before a node is being destroyed: it will be removed from the internal list. More...
 
void onArcDestruction (CHMHMapArc *arc)
 Event handler to be called just before an arc is being destroyed: it will be removed from the internal list. More...
 
CSerializable virtual methods
void writeToStream (mrpt::utils::CStream &out, int *getVersion) const override
 Introduces a pure virtual method responsible for writing to a CStream. More...
 
void readFromStream (mrpt::utils::CStream &in, int version) override
 Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori. More...
 

Protected Attributes

TNodeList m_nodes
 The internal list of nodes and arcs in the whole hierarchical model. More...
 
TArcList m_arcs
 

Friends

class CHMHMapArc
 
class CHMHMapNode
 

RTTI stuff

using Ptr = std::shared_ptr< CHierarchicalMHMap >
 
using ConstPtr = std::shared_ptr< const CHierarchicalMHMap >
 
static mrpt::utils::CLASSINIT _init_CHierarchicalMHMap
 
static const mrpt::utils::TRuntimeClassId runtimeClassId
 
static constexpr const char * className = "CHierarchicalMHMap"
 
static const mrpt::utils::TRuntimeClassId_GetBaseClass ()
 
static const mrpt::utils::TRuntimeClassIdGetRuntimeClassIdStatic ()
 
static mrpt::utils::CObjectCreateObject ()
 
template<typename... Args>
static Ptr Create (Args &&... args)
 
virtual const mrpt::utils::TRuntimeClassIdGetRuntimeClass () const override
 Returns information about the class of an object in runtime. More...
 
virtual mrpt::utils::CObjectclone () const override
 Returns a deep copy (clone) of the object, indepently of its class. More...
 

Member Typedef Documentation

◆ const_iterator

typedef TNodeList::const_iterator mrpt::hmtslam::CHierarchicalMapMHPartition::const_iterator
inherited

Definition at line 51 of file CHierarchicalMapMHPartition.h.

◆ ConstPtr

Definition at line 35 of file CHierarchicalMHMap.h.

◆ iterator

typedef TNodeList::iterator mrpt::hmtslam::CHierarchicalMapMHPartition::iterator
inherited

Definition at line 50 of file CHierarchicalMapMHPartition.h.

◆ Ptr

A typedef for the associated smart pointer

Definition at line 35 of file CHierarchicalMHMap.h.

◆ TNodeIDsList

A type that reprensents a sequence of node IDs.

Definition at line 64 of file CHierarchicalMapMHPartition.h.

Constructor & Destructor Documentation

◆ CHierarchicalMHMap()

CHierarchicalMHMap::CHierarchicalMHMap ( )

Default constructor.

Definition at line 26 of file CHierarchicalMHMap.cpp.

◆ ~CHierarchicalMHMap()

CHierarchicalMHMap::~CHierarchicalMHMap ( )
virtual

Definition at line 30 of file CHierarchicalMHMap.cpp.

References mrpt::utils::clear().

Here is the call graph for this function:

Member Function Documentation

◆ _GetBaseClass()

static const mrpt::utils::TRuntimeClassId* mrpt::hmtslam::CHierarchicalMHMap::_GetBaseClass ( )
staticprotected

◆ arcCount()

size_t CHierarchicalMapMHPartition::arcCount ( ) const
inherited

Returns the number of arcs in the partition:

Definition at line 44 of file CHierarchicalMapMHPartition.cpp.

◆ areNodesNeightbour()

bool CHierarchicalMapMHPartition::areNodesNeightbour ( const CHMHMapNode::TNodeID node1,
const CHMHMapNode::TNodeID node2,
const THypothesisID hypothesisID,
const char *  requiredAnnotation = nullptr 
) const
inherited

Returns whether two nodes are "neightbour", i.e.

have a direct arc between them

Definition at line 1072 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, and MRPT_START.

◆ begin() [1/2]

const_iterator mrpt::hmtslam::CHierarchicalMapMHPartition::begin ( ) const
inlineinherited

Returns an iterator to the first node in the graph.

Definition at line 54 of file CHierarchicalMapMHPartition.h.

References mrpt::hmtslam::CHierarchicalMapMHPartition::m_nodes.

◆ begin() [2/2]

iterator mrpt::hmtslam::CHierarchicalMapMHPartition::begin ( )
inlineinherited

Returns an iterator to the first node in the graph.

Definition at line 56 of file CHierarchicalMapMHPartition.h.

References mrpt::hmtslam::CHierarchicalMapMHPartition::m_nodes.

◆ clear()

void CHierarchicalMHMap::clear ( )

Erase all the contents of map (It delete all nodes/arcs objects)

Definition at line 34 of file CHierarchicalMHMap.cpp.

◆ clone()

virtual mrpt::utils::CObject* mrpt::hmtslam::CHierarchicalMHMap::clone ( ) const
overridevirtual

Returns a deep copy (clone) of the object, indepently of its class.

Implements mrpt::utils::CObject.

◆ computeCoordinatesTransformationBetweenNodes()

void CHierarchicalMapMHPartition::computeCoordinatesTransformationBetweenNodes ( const CHMHMapNode::TNodeID nodeFrom,
const CHMHMapNode::TNodeID nodeTo,
mrpt::poses::CPose3DPDFParticles posePDF,
const THypothesisID hypothesisID,
unsigned int  particlesCount = 100,
float  additionalNoiseXYratio = 0.02,
float  additionalNoisePhiRad = mrpt::utils::DEG2RAD(0.1) 
) const
inherited

◆ computeGloballyConsistentNodeCoordinates()

void CHierarchicalMapMHPartition::computeGloballyConsistentNodeCoordinates ( std::map< CHMHMapNode::TNodeID, mrpt::poses::CPose3DPDFGaussian, std::less< CHMHMapNode::TNodeID >, Eigen::aligned_allocator< std::pair< const CHMHMapNode::TNodeID, mrpt::poses::CPose3DPDFGaussian >>> &  nodePoses,
const CHMHMapNode::TNodeID idReferenceNode,
const THypothesisID hypothesisID,
const unsigned int &  numberOfIterations = 2 
) const
inherited

This methods implements a Lu&Milios-like globally optimal estimation for the global coordinates of all the nodes in the graph according to all available arcs with relative pose information.

Global coordinates will be computed relative to the node "idReferenceNode".

Exceptions
std::exceptionIf there is any node without a pose arc, invalid (non invertible) matrixes, etc...
See also
computeCoordinatesTransformationBetweenNodes

Definition at line 1328 of file CHierarchicalMapMHPartition.cpp.

References ARC_ANNOTATION_DELTA, mrpt::poses::CPose3DPDFGaussianInf::copyFrom(), mrpt::poses::CPose3DPDFGaussian::cov, mrpt::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::dijkstra_nodes_estimate(), mrpt::graphs::CDirectedGraph< TYPE_EDGES, EDGE_ANNOTATIONS >::insertEdgeAtEnd(), mrpt::poses::CPose3DPDFGaussian::mean, MRPT_END, MRPT_START, mrpt::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::nodes, mrpt::graphslam::optimize_graph_spa_levmarq(), and mrpt::graphs::CNetworkOfPoses< CPOSE, MAPS_IMPLEMENTATION, NODE_ANNOTATIONS, EDGE_ANNOTATIONS >::root.

Here is the call graph for this function:

◆ computeMatchProbabilityBetweenNodes()

float CHierarchicalMapMHPartition::computeMatchProbabilityBetweenNodes ( const CHMHMapNode::TNodeID nodeFrom,
const CHMHMapNode::TNodeID nodeTo,
float &  maxMatchProb,
mrpt::poses::CPose3DPDFSOG estimatedRelativePose,
const THypothesisID hypothesisID,
unsigned int  monteCarloSamplesPose = 300 
)
inherited

Computes the probability [0,1] of two areas' gridmaps to "match" (loop closure), according to the grid maps and pose uncertainty from information in arcs (uses a Monte Carlo aproximation) If there is not enough information or a robust estimation cannot be found, there will not be particles in "estimatedRelativePose".

Definition at line 994 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, MRPT_START, MRPT_UNUSED_PARAM, and THROW_EXCEPTION.

◆ computeOverlapProbabilityBetweenNodes()

double CHierarchicalMapMHPartition::computeOverlapProbabilityBetweenNodes ( const CHMHMapNode::TNodeID nodeFrom,
const CHMHMapNode::TNodeID nodeTo,
const THypothesisID hypothesisID,
const size_t &  monteCarloSamples = 100,
const float  margin_to_substract = 6 
) const
inherited

Computes the probability [0,1] of two areas' gridmaps to overlap, via a Monte Carlo aproximation.

Exceptions
std::exceptionIf there is not enought information in arcs, etc...
Parameters
margin_to_substractIn meters, the area of each gridmap is "eroded" this amount to compensate the area in excess usually found in gridmaps.

Definition at line 1583 of file CHierarchicalMapMHPartition.cpp.

References ASSERT_, mrpt::bayes::CParticleFilterData< T >::m_particles, MRPT_END, MRPT_START, NODE_ANNOTATION_METRIC_MAPS, and mrpt::math::RectanglesIntersection().

Here is the call graph for this function:

◆ Create()

template<typename... Args>
static Ptr mrpt::hmtslam::CHierarchicalMHMap::Create ( Args &&...  args)
inlinestatic

Definition at line 35 of file CHierarchicalMHMap.h.

◆ CreateObject()

static mrpt::utils::CObject* mrpt::hmtslam::CHierarchicalMHMap::CreateObject ( )
static

◆ dumpAsText()

void CHierarchicalMapMHPartition::dumpAsText ( utils::CStringList s) const
inherited

◆ dumpAsXMLfile()

void CHierarchicalMHMap::dumpAsXMLfile ( std::string  fileName) const

Destructor.

Save the whole graph as a XML file

Definition at line 291 of file CHierarchicalMHMap.cpp.

References ASSERT_, mrpt::poses::CPoint< DERIVEDCLASS >::asString(), mrpt::utils::CSimpleDatabase::createTable(), mrpt::format(), IS_CLASS, mrpt::utils::ObjectToString(), and mrpt::utils::CSimpleDatabase::saveAsXML().

Here is the call graph for this function:

◆ end() [1/2]

const_iterator mrpt::hmtslam::CHierarchicalMapMHPartition::end ( ) const
inlineinherited

Returns an iterator to the end of the list of nodes in the graph.

Definition at line 58 of file CHierarchicalMapMHPartition.h.

References mrpt::hmtslam::CHierarchicalMapMHPartition::m_nodes.

◆ end() [2/2]

iterator mrpt::hmtslam::CHierarchicalMapMHPartition::end ( )
inlineinherited

Returns an iterator to the end of the list of nodes in the graph.

Definition at line 60 of file CHierarchicalMapMHPartition.h.

References mrpt::hmtslam::CHierarchicalMapMHPartition::m_nodes.

◆ findArcOfTypeBetweenNodes()

CHMHMapArc::Ptr CHierarchicalMapMHPartition::findArcOfTypeBetweenNodes ( const CHMHMapNode::TNodeID node1id,
const CHMHMapNode::TNodeID node2id,
const THypothesisID hypothesisID,
const std::string arcType,
bool &  isInverted 
) const
inherited

Returns the first arc between a pair of nodes of a given type, and if it is in the opposite direction.

Returns
The arc, or nullptr if not found.

Definition at line 1549 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, and MRPT_START.

◆ findArcsBetweenNodes()

void CHierarchicalMapMHPartition::findArcsBetweenNodes ( const CHMHMapNode::TNodeID node1,
const CHMHMapNode::TNodeID node2,
const THypothesisID hypothesisID,
TArcList out_listArcs 
) const
inherited

Returns all the arcs between a pair of nodes:

Definition at line 1013 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, and MRPT_START.

◆ findArcsOfTypeBetweenNodes()

void CHierarchicalMapMHPartition::findArcsOfTypeBetweenNodes ( const CHMHMapNode::TNodeID node1id,
const CHMHMapNode::TNodeID node2id,
const THypothesisID hypothesisID,
const std::string arcType,
TArcList ret 
) const
inherited

Returns the arcs between a pair of nodes of a given type.

Definition at line 1042 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, and MRPT_START.

◆ findPathBetweenNodes()

void CHierarchicalMapMHPartition::findPathBetweenNodes ( const CHMHMapNode::TNodeID nodeFrom,
const CHMHMapNode::TNodeID nodeTo,
const THypothesisID hypothesisID,
TArcList out_path,
bool  direction = false 
) const
inherited

The Dijkstra algorithm for finding the shortest path between a pair of nodes.

Returns
The sequence of arcs connecting the nodes.It will be empty if no path is found or when the starting and ending node coincide.

Definition at line 735 of file CHierarchicalMapMHPartition.cpp.

References ASSERT_, ASSERTMSG_, MRPT_END, and MRPT_START.

◆ getAs3DScene()

void CHierarchicalMapMHPartition::getAs3DScene ( mrpt::opengl::COpenGLScene outScene,
const CHMHMapNode::TNodeID idReferenceNode,
const THypothesisID hypothesisID,
const unsigned int &  numberOfIterationsForOptimalGlobalPoses = 5,
const bool &  showRobotPoseIDs = true 
) const
inherited

Returns a 3D scene reconstruction of the hierarchical map.

See "computeGloballyConsistentNodeCoordinates" for the meaning of "numberOfIterationsForOptimalGlobalPoses"

Definition at line 1108 of file CHierarchicalMapMHPartition.cpp.

References mrpt::poses::CPose3D::addComponents(), mrpt::opengl::COpenGLScene::clear(), mrpt::maps::CMultiMetricMap::getAs3DObject(), mrpt::opengl::COpenGLScene::insert(), MRPT_END, MRPT_START, NODE_ANNOTATION_METRIC_MAPS, NODE_ANNOTATION_POSES_GRAPH, mrpt::poses::CPose3D::normalizeAngles(), mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::x(), and mrpt::poses::CPoseOrPoint< DERIVEDCLASS >::y().

Here is the call graph for this function:

◆ getFirstNode()

CHMHMapNode::Ptr CHierarchicalMapMHPartition::getFirstNode ( )
inherited

Returns the first node in the graph, or nullptr if it does not exist.

Returns
A pointer to the object. DO NOT DELETE this object, if you want to modify it in someway, first obtain a copy by invoking "CSerializable::duplicate"

Definition at line 118 of file CHierarchicalMapMHPartition.cpp.

◆ getNodeByID() [1/2]

CHMHMapNode::Ptr CHierarchicalMapMHPartition::getNodeByID ( CHMHMapNode::TNodeID  id)
inherited

Returns the node with the given ID, or nullptr if it does not exist.

Returns
A pointer to the object. DO NOT DELETE this object, if you want to modify it in someway, first obtain a copy by invoking "CSerializable::duplicate"

Definition at line 48 of file CHierarchicalMapMHPartition.cpp.

References AREAID_INVALID, MRPT_END, and MRPT_START.

◆ getNodeByID() [2/2]

const CHMHMapNode::Ptr CHierarchicalMapMHPartition::getNodeByID ( CHMHMapNode::TNodeID  id) const
inherited

Returns the node with the given ID, or nullptr if it does not exist.

Returns
A pointer to the object. DO NOT DELETE this object, if you want to modify it in someway, first obtain a copy by invoking "CSerializable::duplicate"

Definition at line 62 of file CHierarchicalMapMHPartition.cpp.

References AREAID_INVALID, MRPT_END, and MRPT_START.

◆ getNodeByLabel() [1/2]

CHMHMapNode::Ptr CHierarchicalMapMHPartition::getNodeByLabel ( const std::string label,
const THypothesisID hypothesisID 
)
inherited

Returns the node with the given label (case insensitive) for some given hypothesis ID, or nullptr if it does not exist.

Returns
A pointer to the object. DO NOT DELETE this object, if you want to modify it in someway, first obtain a copy by invoking "CSerializable::duplicate"

Definition at line 77 of file CHierarchicalMapMHPartition.cpp.

References mrpt::system::os::_strcmpi(), MRPT_END, and MRPT_START.

Here is the call graph for this function:

◆ getNodeByLabel() [2/2]

const CHMHMapNode::Ptr CHierarchicalMapMHPartition::getNodeByLabel ( const std::string label,
const THypothesisID hypothesisID 
) const
inherited

Returns the node with the given label (case insensitive) for some given hypothesis ID, or nullptr if it does not exist.

Returns
A pointer to the object. DO NOT DELETE this object, if you want to modify it in someway, first obtain a copy by invoking "CSerializable::duplicate"

Definition at line 97 of file CHierarchicalMapMHPartition.cpp.

References mrpt::system::os::_strcmpi(), MRPT_END, and MRPT_START.

Here is the call graph for this function:

◆ GetRuntimeClass()

virtual const mrpt::utils::TRuntimeClassId* mrpt::hmtslam::CHierarchicalMHMap::GetRuntimeClass ( ) const
overridevirtual

Returns information about the class of an object in runtime.

Reimplemented from mrpt::utils::CSerializable.

◆ GetRuntimeClassIdStatic()

static const mrpt::utils::TRuntimeClassId& mrpt::hmtslam::CHierarchicalMHMap::GetRuntimeClassIdStatic ( )
static

◆ loadFromXMLfile()

void CHierarchicalMHMap::loadFromXMLfile ( std::string  fileName)

Load a graph from a XML file.

Definition at line 184 of file CHierarchicalMHMap.cpp.

References COMMON_TOPOLOG_HYP, mrpt::utils::CSimpleDatabase::getTable(), mrpt::utils::CSimpleDatabase::loadFromXML(), NODE_ANNOTATION_PLACE_POSE, and mrpt::system::tokenize().

Here is the call graph for this function:

◆ nodeCount()

size_t CHierarchicalMapMHPartition::nodeCount ( ) const
inherited

Returns the number of nodes in the partition:

Definition at line 40 of file CHierarchicalMapMHPartition.cpp.

◆ onArcAddition()

void CHierarchicalMHMap::onArcAddition ( CHMHMapArc::Ptr arc)
protected

Event handler to be called just after an arc has being created: it will be added to the internal list.

Definition at line 172 of file CHierarchicalMHMap.cpp.

◆ onArcDestruction()

void CHierarchicalMHMap::onArcDestruction ( CHMHMapArc arc)
protected

Event handler to be called just before an arc is being destroyed: it will be removed from the internal list.

Note
At *addition we use a smart pointer to assure all the implied guys use the same smrt. pnt., but at destructors the objects don't know anything but "this", thus the usage of plain pointers.

Definition at line 140 of file CHierarchicalMHMap.cpp.

◆ onNodeAddition()

void CHierarchicalMHMap::onNodeAddition ( CHMHMapNode::Ptr node)
protected

Event handler to be called just after a node has being created: it will be added to the internal list.

Definition at line 151 of file CHierarchicalMHMap.cpp.

References ASSERT_.

◆ onNodeDestruction()

void CHierarchicalMHMap::onNodeDestruction ( CHMHMapNode node)
protected

Event handler to be called just before a node is being destroyed: it will be removed from the internal list.

Note
At *addition we use a smart pointer to assure all the implied guys use the same smrt. pnt., but at destructors the objects don't know anything but "this", thus the usage of plain pointers.

Definition at line 127 of file CHierarchicalMHMap.cpp.

References mrpt::hmtslam::CHMHMapNode::getID().

Here is the call graph for this function:

◆ operator delete() [1/3]

void mrpt::hmtslam::CHierarchicalMHMap::operator delete ( void memory,
void ptr 
)
inlinenoexcept

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator delete() [2/3]

void mrpt::hmtslam::CHierarchicalMHMap::operator delete ( void ptr)
inlinenoexcept

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator delete() [3/3]

void mrpt::hmtslam::CHierarchicalMHMap::operator delete ( void ptr,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator delete[]()

void mrpt::hmtslam::CHierarchicalMHMap::operator delete[] ( void ptr)
inlinenoexcept

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator new() [1/3]

void* mrpt::hmtslam::CHierarchicalMHMap::operator new ( size_t  size,
const std::nothrow_t &   
)
inlinenoexcept

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator new() [2/3]

void* mrpt::hmtslam::CHierarchicalMHMap::operator new ( size_t  size)
inline

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator new() [3/3]

static void* mrpt::hmtslam::CHierarchicalMHMap::operator new ( size_t  size,
void ptr 
)
inlinestatic

Definition at line 35 of file CHierarchicalMHMap.h.

◆ operator new[]()

void* mrpt::hmtslam::CHierarchicalMHMap::operator new[] ( size_t  size)
inline

Definition at line 35 of file CHierarchicalMHMap.h.

◆ readFromStream()

void CHierarchicalMHMap::readFromStream ( mrpt::utils::CStream in,
int  version 
)
overrideprotectedvirtual

Introduces a pure virtual method responsible for loading from a CStream This can not be used directly be users, instead use "stream >> object;" for reading it from a stream or "stream >> object_ptr;" if the class is unknown apriori.

Parameters
inThe input binary stream where the object data must read from.
versionThe version of the object stored in the stream: use this version number in your code to know how to read the incoming data.
Exceptions
std::exceptionOn any error, see CStream::ReadBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 85 of file CHierarchicalMHMap.cpp.

References mrpt::utils::clear(), and MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION.

Here is the call graph for this function:

◆ saveAreasDiagramForMATLAB()

void CHierarchicalMapMHPartition::saveAreasDiagramForMATLAB ( const std::string filName,
const CHMHMapNode::TNodeID idReferenceNode,
const THypothesisID hypothesisID 
) const
inherited

Returns a partition of this graph only with nodes at a given level in the hierarchy (0=ground level,1=parent level,etc)

  • The partition may be empty if no node fulfills the condition.
  • All arcs STARTING at each node from the partition will be added to the partition as well.
  • Levels in the hierarchy here stands for arcs of type "arcType_Belongs" only.
    See also
    CHMHMapArc Saves a MATLAB script that represents graphically the nodes with type="Area" in this hierarchical-map(partition), using the stated node as global coordinates reference. ADDITIONAL NOTES:
  • Coordinates are computed simply as the mean value of the first arc with an annotation "RelativePose", added to the pose of the original node.
  • If the coordinates of any node can not be computed (no arcs,...), an exception will be raised.

Definition at line 129 of file CHierarchicalMapMHPartition.cpp.

References MRPT_UNUSED_PARAM.

◆ saveAreasDiagramWithEllipsedForMATLAB()

void CHierarchicalMapMHPartition::saveAreasDiagramWithEllipsedForMATLAB ( const std::string filName,
const CHMHMapNode::TNodeID idReferenceNode,
const THypothesisID hypothesisID,
float  uncertaintyExagerationFactor = 1.0f,
bool  drawArcs = false,
unsigned int  numberOfIterationsForOptimalGlobalPoses = 4 
) const
inherited

Saves a MATLAB script that represents graphically the nodes with type="Area" in this hierarchical-map(partition), using the stated node as global coordinates reference, and drawing the ellipses of the localization uncertainty for each node.

ADDITIONAL NOTES:

  • Coordinates are computed simply as the mean value of the first arc with an annotation "RelativePose", added to the pose of the original node.
  • If the coordinates of any node can not be computed (no arcs,...), an exception will be raised.

Definition at line 308 of file CHierarchicalMapMHPartition.cpp.

References MRPT_UNUSED_PARAM.

◆ saveGlobalMapForMATLAB()

void CHierarchicalMapMHPartition::saveGlobalMapForMATLAB ( const std::string filName,
const THypothesisID hypothesisID,
const CHMHMapNode::TNodeID idReferenceNode 
) const
inherited

Saves a MATLAB script that represents graphically the reconstructed "global map" ADDITIONAL NOTES:

  • Coordinates are computed simply as the mean value of the first arc with an annotation "RelativePose", added to the pose of the original node.
  • If the coordinates of any node can not be computed (no arcs,...), an exception will be raised.

Definition at line 487 of file CHierarchicalMapMHPartition.cpp.

References MRPT_END, MRPT_START, and MRPT_UNUSED_PARAM.

◆ writeToMatlab()

virtual mxArray* mrpt::utils::CSerializable::writeToMatlab ( ) const
inlinevirtualinherited

Introduces a pure virtual method responsible for writing to a mxArray Matlab object, typically a MATLAB struct whose contents are documented in each derived class.

Returns
A new mxArray (caller is responsible of memory freeing) or nullptr is class does not support conversion to MATLAB.

Definition at line 89 of file CSerializable.h.

◆ writeToStream()

void CHierarchicalMHMap::writeToStream ( mrpt::utils::CStream out,
int *  getVersion 
) const
overrideprotectedvirtual

Introduces a pure virtual method responsible for writing to a CStream.

This can not be used directly be users, instead use "stream << object;" for writing it to a stream.

Parameters
outThe output binary stream where object must be dumped.
getVersionIf nullptr, the object must be dumped. If not, only the version of the object dump must be returned in this pointer. This enables the versioning of objects dumping and backward compatibility with previously stored data.
Exceptions
std::exceptionOn any error, see CStream::WriteBuffer
See also
CStream

Implements mrpt::utils::CSerializable.

Definition at line 58 of file CHierarchicalMHMap.cpp.

Friends And Related Function Documentation

◆ CHMHMapArc

friend class CHMHMapArc
friend

Definition at line 32 of file CHierarchicalMHMap.h.

◆ CHMHMapNode

friend class CHMHMapNode
friend

Definition at line 33 of file CHierarchicalMHMap.h.

Member Data Documentation

◆ _init_CHierarchicalMHMap

mrpt::utils::CLASSINIT mrpt::hmtslam::CHierarchicalMHMap::_init_CHierarchicalMHMap
staticprotected

Definition at line 35 of file CHierarchicalMHMap.h.

◆ className

constexpr const char* mrpt::hmtslam::CHierarchicalMHMap::className = "CHierarchicalMHMap"
static

Definition at line 35 of file CHierarchicalMHMap.h.

◆ m_arcs

TArcList mrpt::hmtslam::CHierarchicalMapMHPartition::m_arcs
protectedinherited

Definition at line 47 of file CHierarchicalMapMHPartition.h.

◆ m_nodes

TNodeList mrpt::hmtslam::CHierarchicalMapMHPartition::m_nodes
protectedinherited

The internal list of nodes and arcs in the whole hierarchical model.

The objects must be deleted only in the CHierarchicalMap class, not in partitions only objects.

Definition at line 46 of file CHierarchicalMapMHPartition.h.

Referenced by mrpt::hmtslam::CHierarchicalMapMHPartition::begin(), and mrpt::hmtslam::CHierarchicalMapMHPartition::end().

◆ runtimeClassId

const mrpt::utils::TRuntimeClassId mrpt::hmtslam::CHierarchicalMHMap::runtimeClassId
staticprotected

Definition at line 35 of file CHierarchicalMHMap.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