40 size_t CHierarchicalMapMHPartition::nodeCount()
const {
return m_nodes.size(); }
44 size_t CHierarchicalMapMHPartition::arcCount()
const {
return m_arcs.size(); }
85 if (it->second->m_hypotheses.has(hypothesisID))
86 if (!
os::_strcmpi(it->second->m_label.c_str(), label.c_str()))
105 if (it->second->m_hypotheses.has(hypothesisID))
106 if (!
os::_strcmpi(it->second->m_label.c_str(), label.c_str()))
123 return (m_nodes.begin())->second;
129 void CHierarchicalMapMHPartition::saveAreasDiagramForMATLAB(
308 void CHierarchicalMapMHPartition::saveAreasDiagramWithEllipsedForMATLAB(
310 const THypothesisID& hypothesisID,
float uncertaintyExagerationFactor,
311 bool drawArcs,
unsigned int numberOfIterationsForOptimalGlobalPoses)
const 487 void CHierarchicalMapMHPartition::saveGlobalMapForMATLAB(
735 void CHierarchicalMapMHPartition::findPathBetweenNodes(
760 map<CHMHMapNode::TNodeID, TDistance> d;
761 map<CHMHMapNode::TNodeID, TPrevious> previous;
762 map<CHMHMapNode::TNodeID, CHMHMapArc::Ptr> previous_arcs;
763 map<CHMHMapNode::TNodeID, bool> visited;
765 unsigned visitedCount = 0;
768 m_nodes.find(
source) != m_nodes.end(),
769 format(
"Source node %u not found in the H-Map", (
unsigned int)
source));
771 m_nodes.find(target) != m_nodes.end(),
772 format(
"Target node %u not found in the H-Map", (
unsigned int)target));
774 ASSERT_(m_nodes.find(
source)->second->m_hypotheses.has(hypothesisID));
775 ASSERT_(m_nodes.find(target)->second->m_hypotheses.has(hypothesisID));
792 unsigned min_d = std::numeric_limits<unsigned>::max();
799 if (i->second->m_hypotheses.has(hypothesisID))
801 if (d[i->first].dist < min_d && !visited[i->first])
804 min_d = d[u->first].dist;
811 visited[u->first] =
true;
817 nodeU->getArcs(arcs, hypothesisID);
823 if ((*i)->getNodeFrom() != nodeU->getID())
824 vID = (*i)->getNodeFrom();
826 vID = (*i)->getNodeTo();
830 if ((*i)->getNodeFrom() != nodeU->getID())
833 vID = (*i)->getNodeTo();
836 if ((min_d + 1) < d[vID].dist)
838 d[vID].dist = min_d + 1;
839 previous[vID].id = u->first;
840 previous_arcs[vID] = *i;
843 }
while (u->first != target && visitedCount < m_nodes.size());
848 if (u->first == target)
854 ret.push_front(previous_arcs[nod]);
855 nod = previous[nod].id;
865 void CHierarchicalMapMHPartition::computeCoordinatesTransformationBetweenNodes(
868 unsigned int particlesCount,
float additionalNoiseXYratio,
869 float additionalNoisePhiRad)
const 875 const TPose3D nullPose(0, 0, 0, 0, 0, 0);
880 std::vector<TPose3DList> listSamples;
882 TPose3DList dummyList;
886 findPathBetweenNodes(nodeFrom, nodeTo, hypothesisID, arcsPath);
888 pathLength = arcsPath.size();
895 dummyList.resize(particlesCount);
896 listSamples.resize(pathLength, dummyList);
897 for (arcsIt = arcsPath.begin(), lstIt = listSamples.begin();
898 arcsIt != arcsPath.end(); lstIt++, arcsIt++)
901 bool reversedArc = (*arcsIt)->getNodeTo() == lastNode;
903 reversedArc ? (*arcsIt)->getNodeFrom() : (*arcsIt)->getNodeTo();
907 TPoseID curNodeRefPoseID, nextNodeRefPoseID;
908 getNodeByID((*arcsIt)->getNodeFrom())
909 ->m_annotations.getElemental(
912 getNodeByID((*arcsIt)->getNodeTo())
913 ->m_annotations.getElemental(
917 TPoseID srcRefPoseID, trgRefPoseID;
918 (*arcsIt)->m_annotations.getElemental(
920 (*arcsIt)->m_annotations.getElemental(
923 ASSERT_(curNodeRefPoseID == srcRefPoseID);
924 ASSERT_(nextNodeRefPoseID == trgRefPoseID);
932 pdf.
copyFrom(*std::dynamic_pointer_cast<CPose3DPDF>(anotation));
941 for (poseIt = lstIt->begin(), samplIt =
samples.begin();
942 poseIt != lstIt->end(); poseIt++, samplIt++)
945 poseIt->setFromValues(
947 additionalNoiseXYratio *
950 additionalNoiseXYratio *
954 additionalNoisePhiRad *
956 (*samplIt)[4], (*samplIt)[5]);
967 for (
unsigned int i = 0; i < particlesCount; i++)
971 for (
unsigned int j = 0; j < pathLength; j++)
974 sample = sample + listSamples[j][i];
976 sample = listSamples[j][i];
985 cout <<
"[computeCoordinatesTransformationBetweenNodes] Nodes: " << nodeFrom <<
" - " << nodeTo <<
": " << auxPDF;
994 float CHierarchicalMapMHPartition::computeMatchProbabilityBetweenNodes(
997 const THypothesisID& hypothesisID,
unsigned int monteCarloSamplesPose)
1013 void CHierarchicalMapMHPartition::findArcsBetweenNodes(
1025 node1->getArcs(lstArcs);
1026 for (itArc = lstArcs.begin(); itArc != lstArcs.end(); itArc++)
1028 if ((*itArc)->m_hypotheses.has(hypothesisID))
1029 if ((*itArc)->m_nodeFrom == node2id ||
1030 (*itArc)->m_nodeTo == node2id)
1032 ret.push_back(*itArc);
1042 void CHierarchicalMapMHPartition::findArcsOfTypeBetweenNodes(
1055 node1->getArcs(lstArcs);
1056 for (itArc = lstArcs.begin(); itArc != lstArcs.end(); itArc++)
1058 if ((*itArc)->m_hypotheses.has(hypothesisID))
1059 if ((*itArc)->m_nodeFrom == node2id ||
1060 (*itArc)->m_nodeTo == node2id)
1062 if ((*itArc)->m_arcType == arcType) ret.push_back(*itArc);
1072 bool CHierarchicalMapMHPartition::areNodesNeightbour(
1074 const THypothesisID& hypothesisID,
const char* requiredAnnotation)
const 1083 node1->getArcs(lstArcs);
1084 for (itArc = lstArcs.begin(); itArc != lstArcs.end(); itArc++)
1086 if ((*itArc)->m_hypotheses.has(hypothesisID))
1087 if ((*itArc)->m_nodeFrom == node2id ||
1088 (*itArc)->m_nodeTo == node2id)
1090 if (!requiredAnnotation)
1092 else if ((*itArc)->m_annotations.get(
1093 requiredAnnotation, hypothesisID))
1107 void CHierarchicalMapMHPartition::getAs3DScene(
1110 const unsigned int& numberOfIterationsForOptimalGlobalPoses,
1111 const bool& showRobotPoseIDs)
const 1119 mrpt::make_aligned_shared<mrpt::opengl::CGridPlaneXY>(
1120 -500, 500, -500, 500, 0, 5);
1121 obj->setColor(0.3, 0.3, 0.3);
1125 using TMapID2PosePDF = std::map<
1127 std::less<CHMHMapNode::TNodeID>,
1128 Eigen::aligned_allocator<
1129 std::pair<const CHMHMapNode::TNodeID, CPose3DPDFGaussian>>>;
1130 TMapID2PosePDF nodesPoses;
1133 using TMapID2Pose2D = std::map<
1135 Eigen::aligned_allocator<
1136 std::pair<const CHMHMapNode::TNodeID, CPose2D>>>;
1142 computeGloballyConsistentNodeCoordinates(
1143 nodesPoses, idReferenceNode, hypothesisID,
1144 numberOfIterationsForOptimalGlobalPoses);
1147 for (it = nodesPoses.begin(); it != nodesPoses.end(); it++)
1156 if (posesGraph && posesGraph->size())
1162 it != posesGraph->end(); ++it)
1165 meanSFs *= 1.0f / (posesGraph->size());
1168 meanPose = meanPose +
CPose2D(meanSFs);
1175 nodesMeanPoses[it->first] = meanPose;
1182 for (it = nodesPoses.begin(); it != nodesPoses.end(); it++)
1184 const CPose3D& pose = it->second.mean;
1193 mrpt::make_aligned_shared<mrpt::opengl::CSetOfObjects>();
1194 metricMap->getAs3DObject(objTex);
1195 objTex->setPose(pose);
1200 float nodes_height = 10.0f;
1201 float nodes_radius = 1.0f;
1205 for (it = nodesPoses.begin(), it2 = nodesMeanPoses.begin();
1206 it != nodesPoses.end(); it++, it2++)
1209 const CPose3D& pose = it->second.mean;
1214 mrpt::make_aligned_shared<mrpt::opengl::CSphere>();
1216 objSphere->setName(node->m_label);
1217 objSphere->setColor(0, 0, 1);
1218 objSphere->setLocation(
1219 meanPose.
x(), meanPose.
y(), meanPose.z() + nodes_height);
1220 objSphere->setRadius(nodes_radius);
1221 objSphere->setNumberDivsLongitude(16);
1222 objSphere->setNumberDivsLatitude(16);
1224 objSphere->enableRadiusIndependentOfEyeDistance();
1226 outScene.
insert(objSphere);
1230 mrpt::make_aligned_shared<mrpt::opengl::CText>();
1232 objText->setString(
format(
"%li", (
long int)node->getID()));
1234 objText->setColor(1, 0, 0);
1235 objText->setLocation(
1236 meanPose.
x(), meanPose.
y(), meanPose.z() + nodes_height);
1238 outScene.
insert(objText);
1250 it != posesGraph->end(); ++it)
1253 it->second.pdf.getMean(SF_pose);
1255 CPose3D auxPose(pose + SF_pose);
1258 mrpt::make_aligned_shared<mrpt::opengl::CDisk>();
1260 glObj->setColor(1, 0, 0);
1262 glObj->setPose(auxPose);
1265 glObj->setDiskRadius(0.05f);
1266 glObj->setSlicesCount(20);
1267 glObj->setLoopsCount(10);
1269 if (showRobotPoseIDs)
1271 glObj->setName(
format(
"%i", (
int)it->first));
1272 glObj->enableShowName();
1279 mrpt::make_aligned_shared<mrpt::opengl::CSimpleLine>();
1281 objLine->setColor(1, 0, 0, 0.2);
1282 objLine->setLineWidth(1.5);
1284 objLine->setLineCoords(
1285 meanPose.
x(), meanPose.
y(), nodes_height, auxPose.
x(),
1288 outScene.
insert(objLine);
1295 node->getArcs(arcs, hypothesisID);
1300 if (arc->getNodeFrom() == node->getID())
1302 CPose3D poseTo(nodesMeanPoses.find(arc->getNodeTo())->second);
1306 mrpt::make_aligned_shared<mrpt::opengl::CSimpleLine>();
1308 objLine->setColor(0, 1, 0, 0.5);
1309 objLine->setLineWidth(5);
1311 objLine->setLineCoords(
1312 meanPose.
x(), meanPose.
y(), meanPose.z() + nodes_height,
1313 poseTo.
x(), poseTo.
y(), poseTo.z() + nodes_height);
1315 outScene.
insert(objLine);
1326 void CHierarchicalMapMHPartition::computeGloballyConsistentNodeCoordinates(
1329 std::less<CHMHMapNode::TNodeID>,
1330 Eigen::aligned_allocator<std::pair<
1334 const unsigned int& numberOfIterations)
const 1340 if (m_arcs.empty())
return;
1347 it_arc != m_arcs.end(); ++it_arc)
1349 if (!(*it_arc)->m_hypotheses.has(hypothesisID))
continue;
1356 if (!anotation)
continue;
1360 *std::dynamic_pointer_cast<CPose3DPDF>(anotation));
1366 pose_graph.
root = idReferenceNode;
1372 graphslam_params[
"max_iterations"] = numberOfIterations;
1375 pose_graph, out_info,
1381 pose_graph.
nodes.begin();
1382 it_node != pose_graph.
nodes.end(); ++it_node)
1388 new_pose.
mean = it_node->second;
1389 new_pose.
cov.setIdentity();
1393 #if __computeGloballyConsistentNodeCoordinates__VERBOSE 1396 it != nodePoses.end(); ++it)
1397 cout << it->first <<
": " << it->second.mean << endl;
1407 void CHierarchicalMapMHPartition::dumpAsText(std::vector<std::string>& st)
const 1410 st.push_back(
"LIST OF NODES");
1411 st.push_back(
"================");
1418 "NODE ID: %i\t LABEL:%s\tARCS: ", (
int)it->second->getID(),
1419 it->second->m_label.c_str());
1421 it->second->getArcs(arcs);
1424 "%i-%i, ", (
int)(*a)->getNodeFrom(), (int)(*a)->getNodeTo());
1429 it->second->m_annotations.begin();
1430 ann != it->second->m_annotations.end(); ++ann)
1433 " [HYPO ID #%02i] Annotation '%s' Class: ", (
int)ann->ID,
1436 s +=
string(ann->value->GetRuntimeClass()->className);
1445 it->second->m_annotations.getElemental(
1447 st.push_back(
format(
" VALUE: %i", (
int)refID));
1457 " CRobotPosesGraph has %i poses:",
1458 (
int)posesGraph->size()));
1461 p != posesGraph->end(); ++
p)
1466 " Pose %i \t (%.03f,%.03f,%.03fdeg)",
1467 (
int)
p->first, pdfMean.
x(), pdfMean.
y(),
1478 st.push_back(
"LIST OF ARCS");
1479 st.push_back(
"================");
1485 "ARC: %i -> %i\n", (
int)(*it)->getNodeFrom(),
1486 (int)(*it)->getNodeTo());
1488 s +=
string(
" Arc type: ") + (*it)->m_arcType;
1493 (*it)->m_annotations.begin();
1494 ann != (*it)->m_annotations.end(); ++ann)
1497 " [HYPO ID #%02i] Annotation '%s' Class: ", (
int)ann->ID,
1500 s +=
string(ann->value->GetRuntimeClass()->className);
1509 (*it)->m_annotations.getElemental(
1511 st.push_back(
format(
" VALUE: %i", (
int)refID));
1516 (*it)->m_annotations.getElemental(
1518 st.push_back(
format(
" VALUE: %i", (
int)refID));
1528 *std::dynamic_pointer_cast<CPose3DPDF>(o));
1531 " VALUE: (%f,%f,%f , %fdeg,%fdeg,%fdeg)",
1532 relativePoseAcordToArc.
mean.
x(),
1533 relativePoseAcordToArc.
mean.
y(),
1534 relativePoseAcordToArc.
mean.z(),
1551 bool& isInverted)
const 1556 findArcsOfTypeBetweenNodes(
1557 node1id, node2id, hypothesisID, arcType, lstArcs);
1561 if ((*a)->getNodeFrom() == node1id)
1582 double CHierarchicalMapMHPartition::computeOverlapProbabilityBetweenNodes(
1584 const THypothesisID& hypothesisID,
const size_t& monteCarloSamples,
1585 const float margin_to_substract)
const 1595 computeCoordinatesTransformationBetweenNodes(
1596 nodeFrom, nodeTo, posePDF, hypothesisID, monteCarloSamples);
1601 float r1_x_min, r1_x_max, r1_y_min, r1_y_max, r2_x_min, r2_x_max, r2_y_min,
1608 ASSERT_(hMap1->m_gridMaps.size() > 0);
1610 r1_x_min = hMap1->m_gridMaps[0]->getXMin();
1611 r1_x_max = hMap1->m_gridMaps[0]->getXMax();
1612 r1_y_min = hMap1->m_gridMaps[0]->getYMin();
1613 r1_y_max = hMap1->m_gridMaps[0]->getYMax();
1615 if (r1_x_max - r1_x_min > 2 * margin_to_substract)
1617 r1_x_max -= margin_to_substract;
1618 r1_x_min += margin_to_substract;
1620 if (r1_y_max - r1_y_min > 2 * margin_to_substract)
1622 r1_y_max -= margin_to_substract;
1623 r1_y_min += margin_to_substract;
1630 ASSERT_(hMap2->m_gridMaps.size() > 0);
1632 r2_x_min = hMap2->m_gridMaps[0]->getXMin();
1633 r2_x_max = hMap2->m_gridMaps[0]->getXMax();
1634 r2_y_min = hMap2->m_gridMaps[0]->getYMin();
1635 r2_y_max = hMap2->m_gridMaps[0]->getYMax();
1637 if (r2_x_max - r2_x_min > 2 * margin_to_substract)
1639 r2_x_max -= margin_to_substract;
1640 r2_x_min += margin_to_substract;
1642 if (r2_y_max - r2_y_min > 2 * margin_to_substract)
1644 r2_y_max -= margin_to_substract;
1645 r2_y_min += margin_to_substract;
1649 for (i = 0; i < monteCarloSamples; i++)
1652 r1_x_min, r1_x_max, r1_y_min, r1_y_max, r2_x_min, r2_x_max,
1660 return static_cast<double>(hits) / monteCarloSamples;
A namespace of pseudo-random numbers generators of diferent distributions.
double x() const
Common members of all points & poses classes.
void optimize_graph_spa_levmarq(GRAPH_T &graph, TResultInfoSpaLevMarq &out_info, const std::set< mrpt::graphs::TNodeID > *in_nodes_to_optimize=nullptr, const mrpt::system::TParametersDouble &extra_params=mrpt::system::TParametersDouble(), typename graphslam_traits< GRAPH_T >::TFunctorFeedback functor_feedback=typename graphslam_traits< GRAPH_T >::TFunctorFeedback())
Optimize a graph of pose constraints using the Sparse Pose Adjustment (SPA) sparse representation and...
bool RectanglesIntersection(const double &R1_x_min, const double &R1_x_max, const double &R1_y_min, const double &R1_y_max, const double &R2_x_min, const double &R2_x_max, const double &R2_y_min, const double &R2_y_max, const double &R2_pose_x, const double &R2_pose_y, const double &R2_pose_phi)
Returns whether two rotated rectangles intersect.
CPose3D mean
The mean value.
void dijkstra_nodes_estimate()
Spanning tree computation of a simple estimation of the global coordinates of each node just from the...
#define THROW_EXCEPTION(msg)
void copyFrom(const CPose3DPDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
mrpt::graphs::TNodeID TNodeID
The type of the IDs of nodes.
CParticleList m_particles
The array of particles.
double normalizeWeights(double *out_max_log_w=nullptr) override
Normalize the (logarithmic) weights, such as the maximum weight is zero.
mrpt::graphs::TNodeID root
The ID of the node that is the origin of coordinates, used as reference by all coordinates in nodes...
Classes related to the implementation of Hybrid Metric Topological (HMT) SLAM.
This file implements several operations that operate element-wise on individual or pairs of container...
Declares a class that represents a Probability Density function (PDF) of a 3D(6D) pose ...
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
double pitch() const
Get the PITCH angle (in radians)
double yaw() const
Get the YAW angle (in radians)
std::vector< T, mrpt::aligned_allocator_cpp11< T > > aligned_std_vector
GLsizei GLsizei GLuint * obj
const TDistance & operator=(const unsigned &D)
A directed graph of pose constraints, with edges being the relative poses between pairs of nodes iden...
#define ASSERT_(f)
Defines an assertion mechanism.
void getMean(CPose3D &mean_pose) const override
Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF), computed as a weighted average over all m_particles.
This base provides a set of functions for maths stuff.
std::vector< TPropertyValueIDTriplet >::const_iterator const_iterator
void addComponents(const CPose3D &p)
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" ...
Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class stores a set of r...
#define ASSERTMSG_(f, __ERROR_MSG)
Defines an assertion mechanism.
void clear(bool createMainViewport=true)
Clear the list of objects and viewports in the scene, deleting objects' memory, and leaving just the ...
void drawManySamples(size_t N, std::vector< mrpt::math::CVectorDouble > &outSamples) const override
Draws a number of samples from the distribution, and saves as a list of 1x6 vectors, where each row contains a (x,y,phi) datum.
void copyFrom(const CPose3DPDF &o) override
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
#define NODE_ANNOTATION_METRIC_MAPS
GLsizei const GLchar ** string
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
mrpt::math::CMatrixDouble66 cov
The 6x6 covariance matrix.
int64_t THypothesisID
An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
#define ARC_ANNOTATION_DELTA_SRC_POSEID
A class used to store a 2D pose, including the 2D coordinate point and a heading (phi) angle...
A class used to store a 3D pose (a 3D translation + a rotation in 3D).
TDistance(const unsigned &D)
Output information for mrpt::graphslam::optimize_graph_spa_levmarq()
Lightweight 3D pose (three spatial coordinates, plus three angular coordinates).
Declares a class that represents a Probability Density function (PDF) of a 3D pose as a Gaussian des...
The namespace for 3D scene representation and rendering.
This class allows the user to create, load, save, and render 3D scenes using OpenGL primitives...
GLsizei GLsizei GLchar * source
typename edges_map_t::const_iterator const_iterator
#define NODE_ANNOTATION_REF_POSEID
uint64_t TNodeID
A generic numeric type for unique IDs of nodes or entities.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
void normalizeAngles()
Rebuild the internal matrix & update the yaw/pitch/roll angles within the ]-PI,PI] range (Must be cal...
global_poses_t nodes
The nodes (vertices) of the graph, with their estimated "global" (with respect to root) position...
GLenum GLsizei GLenum format
void resetDeterministic(const mrpt::math::TPose3D &location, size_t particlesCount=0)
Reset the PDF to a single point: All m_particles will be set exactly to the supplied pose...
void insertEdgeAtEnd(TNodeID from_nodeID, TNodeID to_nodeID, const edge_t &edge_value)
Insert an edge (from -> to) with the given edge value (more efficient version to be called if you kno...
This class stores any customizable set of metric maps.
#define NODE_ANNOTATION_POSES_GRAPH
CRandomGenerator & getRandomGenerator()
A static instance of a CRandomGenerator class, for use in single-thread applications.
void insert(const CRenderizable::Ptr &newObject, const std::string &viewportName=std::string("main"))
Insert a new object into the scene, in the given viewport (by default, into the "main" viewport)...
#define ARC_ANNOTATION_DELTA_TRG_POSEID
GLubyte GLubyte GLubyte a
const Scalar * const_iterator
A class for storing a sequence of arcs (a path).
#define ARC_ANNOTATION_DELTA
Declares a class that represents a Probability Density function (PDF) of a 3D pose.
#define MRPT_UNUSED_PARAM(a)
Determines whether this is an X86 or AMD64 platform.
int _strcmpi(const char *str1, const char *str2) noexcept
An OS-independent version of strcmpi.