41 size_t CHierarchicalMapMHPartition::nodeCount()
const 43 return m_nodes.size();
49 size_t CHierarchicalMapMHPartition::arcCount()
const 64 return it==m_nodes.end() ? CHMHMapNodePtr() : it->second;
77 return it==m_nodes.end() ? CHMHMapNodePtr() : it->second;
91 if ( it->second->m_hypotheses.has(hypothesisID) )
92 if ( !
os::_strcmpi( it->second->m_label.c_str(), label.c_str() ) )
96 return CHMHMapNodePtr();
103 const CHMHMapNodePtr CHierarchicalMapMHPartition::getNodeByLabel(
const std::string &label,
const THypothesisID &hypothesisID)
const 109 if ( it->second->m_hypotheses.has(hypothesisID) )
110 if ( !
os::_strcmpi( it->second->m_label.c_str(), label.c_str() ) )
114 return CHMHMapNodePtr();
122 CHMHMapNodePtr CHierarchicalMapMHPartition::getFirstNode()
125 return CHMHMapNodePtr();
126 else return (m_nodes.begin())->second;
132 void CHierarchicalMapMHPartition::saveAreasDiagramForMATLAB(
305 void CHierarchicalMapMHPartition::saveAreasDiagramWithEllipsedForMATLAB(
309 float uncertaintyExagerationFactor,
311 unsigned int numberOfIterationsForOptimalGlobalPoses
479 void CHierarchicalMapMHPartition::saveGlobalMapForMATLAB(
703 const TDistance & operator =(
const unsigned &D) { dist = D;
return *
this;}
721 void CHierarchicalMapMHPartition::findPathBetweenNodes(
726 bool direction)
const 748 map<CHMHMapNode::TNodeID,TDistance> d;
749 map<CHMHMapNode::TNodeID,TPrevious> previous;
750 map<CHMHMapNode::TNodeID, CHMHMapArcPtr> previous_arcs;
751 map<CHMHMapNode::TNodeID, bool> visited;
753 unsigned visitedCount = 0;
756 ASSERTMSG_( m_nodes.find(target)!=m_nodes.end(),
format(
"Target node %u not found in the H-Map",(
unsigned int)target) );
758 ASSERT_( m_nodes.find(
source)->second->m_hypotheses.has(hypothesisID) );
759 ASSERT_( m_nodes.find(target)->second->m_hypotheses.has(hypothesisID) );
776 unsigned min_d = std::numeric_limits<unsigned>::max();
782 if (i->second->m_hypotheses.has(hypothesisID))
784 if (d[i->first].dist < min_d && !visited[i->first])
787 min_d = d[u->first].dist;
794 visited[u->first] =
true;
798 const CHMHMapNodePtr nodeU = getNodeByID(u->first);
800 nodeU->getArcs( arcs, hypothesisID );
806 if ( (*i)->getNodeFrom() != nodeU->getID() )
807 vID = (*i)->getNodeFrom();
808 else vID = (*i)->getNodeTo();
812 if ( (*i)->getNodeFrom() != nodeU->getID() )
814 else vID = (*i)->getNodeTo();
817 if ( (min_d+1) < d[vID].dist)
819 d[vID].dist = min_d+1;
820 previous[vID].id = u->first;
821 previous_arcs[vID] = *i;
824 }
while ( u->first !=target && visitedCount<m_nodes.size() );
829 if (u->first==target)
835 ret.push_front( previous_arcs[nod] );
836 nod = previous[nod].id;
846 void CHierarchicalMapMHPartition::computeCoordinatesTransformationBetweenNodes(
851 unsigned int particlesCount,
852 float additionalNoiseXYratio,
853 float additionalNoisePhiRad )
const 859 static const CPose3D nullPose(0,0,0);
864 std::vector<TPose3DList> listSamples;
866 TPose3DList dummyList;
870 findPathBetweenNodes( nodeFrom, nodeTo, hypothesisID, arcsPath );
872 pathLength = arcsPath.size();
879 dummyList.resize( particlesCount );
880 listSamples.resize( pathLength, dummyList );
881 for (arcsIt=arcsPath.begin(),lstIt=listSamples.begin();arcsIt!=arcsPath.end();lstIt++,arcsIt++)
884 bool reversedArc = (*arcsIt)->getNodeTo() == lastNode;
885 nextNode = reversedArc ? (*arcsIt)->getNodeFrom() : (*arcsIt)->getNodeTo();
889 TPoseID curNodeRefPoseID, nextNodeRefPoseID;
890 getNodeByID((*arcsIt)->getNodeFrom())->m_annotations.getElemental(
NODE_ANNOTATION_REF_POSEID, curNodeRefPoseID, hypothesisID,
true);
891 getNodeByID((*arcsIt)->getNodeTo())->m_annotations.getElemental(
NODE_ANNOTATION_REF_POSEID, nextNodeRefPoseID, hypothesisID,
true);
893 TPoseID srcRefPoseID, trgRefPoseID;
897 ASSERT_( curNodeRefPoseID == srcRefPoseID );
898 ASSERT_( nextNodeRefPoseID == trgRefPoseID);
902 CSerializablePtr anotation = (*arcsIt)->m_annotations.get(
ARC_ANNOTATION_DELTA, hypothesisID );
906 pdf.
copyFrom(*CPose3DPDFPtr(anotation));
915 for (poseIt=lstIt->begin(),samplIt=
samples.begin();poseIt!=lstIt->end();poseIt++,samplIt++)
918 poseIt->setFromValues(
928 if (reversedArc) *poseIt = nullPose - *poseIt;
936 for (
unsigned int i=0;i<particlesCount;i++)
940 for (
unsigned int j=0;j<pathLength;j++)
943 sample = sample + listSamples[j][i];
944 else sample = listSamples[j][i];
953 cout <<
"[computeCoordinatesTransformationBetweenNodes] Nodes: " << nodeFrom <<
" - " << nodeTo <<
": " << auxPDF;
963 float CHierarchicalMapMHPartition::computeMatchProbabilityBetweenNodes(
969 unsigned int monteCarloSamplesPose )
985 void CHierarchicalMapMHPartition::findArcsBetweenNodes(
994 const CHMHMapNodePtr node1 = getNodeByID( node1id );
999 node1->getArcs( lstArcs );
1000 for (itArc=lstArcs.begin();itArc!=lstArcs.end();itArc++)
1002 if ((*itArc)->m_hypotheses.has(hypothesisID))
1003 if ( (*itArc)->m_nodeFrom == node2id ||
1004 (*itArc)->m_nodeTo == node2id)
1006 ret.push_back( *itArc );
1016 void CHierarchicalMapMHPartition::findArcsOfTypeBetweenNodes(
1026 const CHMHMapNodePtr node1 = getNodeByID( node1id );
1031 node1->getArcs( lstArcs );
1032 for (itArc=lstArcs.begin();itArc!=lstArcs.end();itArc++)
1034 if ((*itArc)->m_hypotheses.has(hypothesisID))
1035 if ( (*itArc)->m_nodeFrom == node2id ||
1036 (*itArc)->m_nodeTo == node2id)
1038 if ((*itArc)->m_arcType.isType(arcType) )
1039 ret.push_back( *itArc );
1050 bool CHierarchicalMapMHPartition::areNodesNeightbour(
1054 const char *requiredAnnotation )
const 1058 const CHMHMapNodePtr node1 = getNodeByID( node1id );
1063 node1->getArcs( lstArcs );
1064 for (itArc=lstArcs.begin();itArc!=lstArcs.end();itArc++)
1066 if ((*itArc)->m_hypotheses.has(hypothesisID))
1067 if ( (*itArc)->m_nodeFrom == node2id ||
1068 (*itArc)->m_nodeTo == node2id)
1070 if (!requiredAnnotation)
1073 if ( (*itArc)->m_annotations.get(requiredAnnotation, hypothesisID) )
1088 void CHierarchicalMapMHPartition::getAs3DScene(
1092 const unsigned int &numberOfIterationsForOptimalGlobalPoses,
1093 const bool &showRobotPoseIDs
1102 obj->setColor(0.3,0.3,0.3);
1107 TMapID2PosePDF nodesPoses;
1111 TMapID2Pose2D nodesMeanPoses;
1115 computeGloballyConsistentNodeCoordinates( nodesPoses, idReferenceNode, hypothesisID, numberOfIterationsForOptimalGlobalPoses);
1118 for (it=nodesPoses.begin();it!=nodesPoses.end();it++)
1121 const CHMHMapNodePtr node = getNodeByID( it->first );
1125 if (posesGraph && posesGraph->size())
1133 meanSFs *= 1.0f/(posesGraph->size());
1136 meanPose = meanPose +
CPose2D(meanSFs);
1143 nodesMeanPoses[it->first] = meanPose;
1150 for (it = nodesPoses.begin();it!=nodesPoses.end();it++)
1152 const CPose3D &pose = it->second.mean;
1153 const CHMHMapNodePtr node = getNodeByID( it->first );
1159 metricMap->getAs3DObject( objTex );
1160 objTex->setPose( pose );
1161 outScene.
insert( objTex );
1166 float nodes_height = 10.0f;
1167 float nodes_radius = 1.0f;
1171 for (it = nodesPoses.begin(),it2=nodesMeanPoses.begin();it!=nodesPoses.end();it++,it2++)
1173 const CHMHMapNodePtr node = getNodeByID( it->first );
1174 const CPose3D &pose = it->second.mean ;
1180 objSphere->setName( node->m_label );
1181 objSphere->setColor(0,0,1);
1182 objSphere->setLocation(meanPose.
x(), meanPose.
y(), meanPose.z() + nodes_height);
1183 objSphere->setRadius( nodes_radius );
1184 objSphere->setNumberDivsLongitude(16);
1185 objSphere->setNumberDivsLatitude(16);
1187 objSphere->enableRadiusIndependentOfEyeDistance();
1189 outScene.
insert( objSphere );
1194 objText->setString(
format(
"%li",(
long int)node->getID()) );
1196 objText->setColor(1,0,0);
1197 objText->setLocation(meanPose.
x(), meanPose.
y(), meanPose.z() + nodes_height);
1199 outScene.
insert( objText );
1211 it->second.pdf.getMean(SF_pose);
1213 CPose3D auxPose( pose + SF_pose );
1217 glObj->setColor(1,0,0);
1219 glObj->setPose( auxPose );
1222 glObj->setDiskRadius(0.05f);
1223 glObj->setSlicesCount(20);
1224 glObj->setLoopsCount(10);
1226 if (showRobotPoseIDs)
1228 glObj->setName(
format(
"%i",(
int)it->first ) );
1229 glObj->enableShowName();
1232 outScene.
insert( glObj );
1237 objLine->setColor(1,0,0, 0.2);
1238 objLine->setLineWidth(1.5);
1240 objLine->setLineCoords(meanPose.
x(),meanPose.
y(),nodes_height,auxPose.
x(), auxPose.
y(),0);
1242 outScene.
insert( objLine );
1250 node->getArcs( arcs, hypothesisID );
1253 CHMHMapArcPtr arc = *
a;
1255 if (arc->getNodeFrom()==node->getID())
1257 CPose3D poseTo( nodesMeanPoses.find(arc->getNodeTo())->second );
1262 objLine->setColor(0,1,0, 0.5);
1263 objLine->setLineWidth(5);
1265 objLine->setLineCoords(meanPose.
x(),meanPose.
y(),meanPose.z()+nodes_height,poseTo.
x(), poseTo.
y(),poseTo.z() + nodes_height);
1267 outScene.
insert( objLine );
1281 void CHierarchicalMapMHPartition::computeGloballyConsistentNodeCoordinates(
1285 const unsigned int &numberOfIterations)
const 1300 if (!(*it_arc)->m_hypotheses.has(hypothesisID))
continue;
1305 CSerializablePtr anotation = (*it_arc)->m_annotations.get(
ARC_ANNOTATION_DELTA, hypothesisID );
1306 if (!anotation)
continue;
1309 edge_rel_pose_pdf.
copyFrom(*CPose3DPDFPtr(anotation));
1315 pose_graph.
root = idReferenceNode;
1321 graphslam_params[
"max_iterations"] = numberOfIterations;
1337 new_pose.
mean = it_node->second;
1338 new_pose.
cov.setIdentity();
1341 #if __computeGloballyConsistentNodeCoordinates__VERBOSE 1343 cout << it->first <<
": " << it->second.mean << endl;
1357 st <<
"LIST OF NODES";
1358 st <<
"================";
1363 s +=
format(
"NODE ID: %i\t LABEL:%s\tARCS: ", (
int)it->second->getID(), it->second->m_label.c_str() );
1365 it->second->getArcs(arcs);
1367 s +=
format(
"%i-%i, ", (
int)(*a)->getNodeFrom(), (int)(*a)->getNodeTo() );
1373 s=
format(
" [HYPO ID #%02i] Annotation '%s' Class: ", (
int)ann->ID, ann->name.c_str() );
1375 s+=
string(ann->value->GetRuntimeClass()->className);
1384 st <<
format(
" VALUE: %i",(
int)refID);
1391 st <<
format(
" CRobotPosesGraph has %i poses:",(
int)posesGraph->size());
1397 st <<
format(
" Pose %i \t (%.03f,%.03f,%.03fdeg)",
1413 st <<
"LIST OF ARCS";
1414 st <<
"================";
1419 s +=
format(
"ARC: %i -> %i\n", (
int)(*it)->getNodeFrom(), (int)(*it)->getNodeTo() );
1421 s+=
string(
" Arc type: ")+(*it)->m_arcType.getType();
1427 s=
format(
" [HYPO ID #%02i] Annotation '%s' Class: ", (
int)ann->ID, ann->name.c_str() );
1429 s+=
string(ann->value->GetRuntimeClass()->className);
1438 st <<
format(
" VALUE: %i",(
int)refID);
1444 st <<
format(
" VALUE: %i",(
int)refID);
1452 relativePoseAcordToArc.
copyFrom(*CPose3DPDFPtr(o));
1454 st <<
format(
" VALUE: (%f,%f,%f , %fdeg,%fdeg,%fdeg)",
1455 relativePoseAcordToArc.
mean.
x(),
1456 relativePoseAcordToArc.
mean.
y(),
1457 relativePoseAcordToArc.
mean.z(),
1474 CHMHMapArcPtr CHierarchicalMapMHPartition::findArcOfTypeBetweenNodes(
1479 bool &isInverted )
const 1484 findArcsOfTypeBetweenNodes( node1id, node2id, hypothesisID, arcType, lstArcs);
1488 if ( (*a)->getNodeFrom() == node1id )
1502 return CHMHMapArcPtr();
1509 double CHierarchicalMapMHPartition::computeOverlapProbabilityBetweenNodes(
1513 const size_t &monteCarloSamples,
1514 const float margin_to_substract
1521 const CHMHMapNodePtr from = getNodeByID( nodeFrom );
1522 const CHMHMapNodePtr to = getNodeByID( nodeTo );
1525 computeCoordinatesTransformationBetweenNodes(
1535 float r1_x_min, r1_x_max, r1_y_min, r1_y_max,r2_x_min, r2_x_max, r2_y_min, r2_y_max;
1540 ASSERT_(hMap1->m_gridMaps.size()>0);
1542 r1_x_min = hMap1->m_gridMaps[0]->getXMin();
1543 r1_x_max = hMap1->m_gridMaps[0]->getXMax();
1544 r1_y_min = hMap1->m_gridMaps[0]->getYMin();
1545 r1_y_max = hMap1->m_gridMaps[0]->getYMax();
1547 if (r1_x_max-r1_x_min>2*margin_to_substract)
1549 r1_x_max -= margin_to_substract;
1550 r1_x_min += margin_to_substract;
1552 if (r1_y_max-r1_y_min>2*margin_to_substract)
1554 r1_y_max -= margin_to_substract;
1555 r1_y_min += margin_to_substract;
1562 ASSERT_(hMap2->m_gridMaps.size()>0);
1564 r2_x_min = hMap2->m_gridMaps[0]->getXMin();
1565 r2_x_max = hMap2->m_gridMaps[0]->getXMax();
1566 r2_y_min = hMap2->m_gridMaps[0]->getYMin();
1567 r2_y_max = hMap2->m_gridMaps[0]->getYMax();
1569 if (r2_x_max-r2_x_min>2*margin_to_substract)
1571 r2_x_max -= margin_to_substract;
1572 r2_x_min += margin_to_substract;
1574 if (r2_y_max-r2_y_min>2*margin_to_substract)
1576 r2_y_max -= margin_to_substract;
1577 r2_y_min += margin_to_substract;
1581 for (i=0;i<monteCarloSamples;i++)
1584 r2_x_min, r2_x_max, r2_y_min, r2_y_max,
1593 return static_cast<double>(hits) / monteCarloSamples;
A namespace of pseudo-random numbers genrators of diferent distributions.
void optimize_graph_spa_levmarq(GRAPH_T &graph, TResultInfoSpaLevMarq &out_info, const std::set< mrpt::utils::TNodeID > *in_nodes_to_optimize=NULL, const mrpt::utils::TParametersDouble &extra_params=mrpt::utils::TParametersDouble(), typename graphslam_traits< GRAPH_T >::TFunctorFeedback functor_feedback=NULL)
Optimize a graph of pose constraints using the Sparse Pose Adjustment (SPA) sparse representation and...
double x() const
Common members of all points & poses classes.
bool BASE_IMPEXP 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.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
CPose3D mean
The mean value.
void getMean(CPose3D &mean_pose) const MRPT_OVERRIDE
Returns an estimate of the pose, (the mean, or mathematical expectation of the PDF), computed as a weighted average over all m_particles.
void dijkstra_nodes_estimate()
Spanning tree computation of a simple estimation of the global coordinates of each node just from the...
std::vector< TPropertyValueIDTriplet >::const_iterator const_iterator
This namespace provides a OS-independent interface to many useful functions: filenames manipulation...
void copyFrom(const CPose3DPDF &o) MRPT_OVERRIDE
Copy operator, translating if necesary (for example, between particles and gaussian representations) ...
Classes related to the implementation of Hybrid Metric Topological (HMT) SLAM.
void drawManySamples(size_t N, std::vector< mrpt::math::CVectorDouble > &outSamples) const MRPT_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.
#define THROW_EXCEPTION(msg)
BASE_IMPEXP CRandomGenerator randomGenerator
A static instance of a CRandomGenerator class, for use in single-thread applications.
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 ...
double pitch() const
Get the PITCH angle (in radians)
double yaw() const
Get the YAW angle (in radians)
const Scalar * const_iterator
uint64_t TPoseID
An integer number uniquely identifying each robot pose stored in HMT-SLAM.
GLsizei GLsizei GLuint * obj
static CSpherePtr Create()
double drawGaussian1D_normalized(double *likelihood=NULL)
Generate a normalized (mean=0, std=1) normally distributed sample.
A directed graph of pose constraints, with edges being the relative poses between pairs of nodes iden...
int64_t THypothesisID
An integer number uniquely identifying each of the concurrent hypotheses for the robot topological pa...
A class for storing a list of text lines.
CParticleList m_particles
The array of particles.
This base provides a set of functions for maths stuff.
void insert(const CRenderizablePtr &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 MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
mrpt::maps::CMultiMetricMapPtr CMultiMetricMapPtr
Backward compatible typedef.
void addComponents(const CPose3D &p)
Scalar sum of all 6 components: This is diferent from poses composition, which is implemented as "+" ...
void clear()
Clear the whole list.
Auxiliary class used in mrpt::slam::CLocalMetricHypothesis for HMT-SLAM; this class stores a set of r...
void clear(bool createMainViewport=true)
Clear the list of objects and viewports in the scene, deleting objects' memory, and leaving just the ...
void copyFrom(const CPose3DPDF &o) MRPT_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.
static CGridPlaneXYPtr Create()
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).
void resetDeterministic(const CPose3D &location, size_t particlesCount=0)
Reset the PDF to a single point: All m_particles will be set exactly to the supplied pose...
double normalizeWeights(double *out_max_log_w=NULL) MRPT_OVERRIDE
Normalize the (logarithmic) weights, such as the maximum weight is zero.
int BASE_IMPEXP _strcmpi(const char *str1, const char *str2) MRPT_NO_THROWS
An OS-independent version of strcmpi.
TDistance(const unsigned &D)
static CSimpleLinePtr Create()
Output information for mrpt::graphslam::optimize_graph_spa_levmarq()
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
#define NODE_ANNOTATION_REF_POSEID
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
mrpt::utils::TNodeID root
The ID of the node that is the origin of coordinates, used as reference by all coordinates in nodes...
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
#define ASSERTMSG_(f, __ERROR_MSG)
#define ARC_ANNOTATION_DELTA_TRG_POSEID
GLubyte GLubyte GLubyte a
A class for storing a sequence of arcs (a path).
std::vector< TYPE1, Eigen::aligned_allocator< TYPE1 > > vector_t
#define ARC_ANNOTATION_DELTA
edges_map_t::const_iterator const_iterator
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.
static CSetOfObjectsPtr Create()