9 #ifndef CONSTRAINED_POSE_NETWORK_IMPL_H 10 #define CONSTRAINED_POSE_NETWORK_IMPL_H 58 template <
class graph_t>
64 f <<
"VERTEX_SE2 " <<
id <<
" " <<
p.x() <<
" " <<
p.y() <<
" " <<
p.phi();
70 f <<
"VERTEX3 " <<
id <<
" " <<
p.x() <<
" " <<
p.y() <<
" " <<
p.z()<<
" " <<
p.roll()<<
" " <<
p.pitch()<<
" " <<
p.yaw();
77 f <<
"EDGE_SE2 " << edgeIDs.first <<
" " << edgeIDs.second <<
" " <<
86 f <<
"EDGE3 " << edgeIDs.first <<
" " << edgeIDs.second <<
" " <<
100 write_EDGE_line(edgeIDs,
p,f);
106 write_EDGE_line(edgeIDs,
p,f);
112 p.cov_inv.unit(3,1.0);
113 write_EDGE_line(edgeIDs,
p,f);
119 p.cov_inv.unit(6,1.0);
120 write_EDGE_line(edgeIDs,
p,f);
125 const graph_t*
g, std::ostream& f)
128 for (
const auto&
n :
g->nodes)
130 write_VERTEX_line(
n.first,
n.second, f);
132 const auto sAnnot =
n.second.retAnnotsAsString();
133 if (!sAnnot.empty()) f <<
" | " << sAnnot;
136 if (
n.first ==
g->root) f <<
"FIX " <<
n.first << endl;
140 for (
const auto& e : *
g)
141 if (e.first.first != e.first.second)
142 write_EDGE_line(e.first, e.second, f);
156 "Error opening file '%s' for writing", fil.c_str());
157 save_graph_of_poses_to_ostream(
g, f);
172 out <<
g->nodes <<
g->edges <<
g->root;
183 in >> sStoredClassName;
188 in >> stored_version;
191 switch (stored_version)
194 in >>
g->nodes >>
g->edges >>
g->root;
205 graph_t*
g, std::istream& f,
211 using CPOSE =
typename graph_t::constraint_t;
213 set<string> alreadyWarnedUnknowns;
222 const bool graph_is_3D = CPOSE::is_3D();
231 map<TNodeID, TNodeID> lstEquivs;
240 const string lin =
s.str();
243 if (!(
s >> key) || key.empty())
245 "Line %u: Can't read string for entry type in: '%s'",
246 lineNum, lin.c_str()));
252 if (!(
s >> id1 >> id2))
254 "Line %u: Can't read id1 & id2 in EQUIV line: '%s'",
255 lineNum, lin.c_str()));
256 lstEquivs[std::max(id1, id2)] =
std::min(id1, id2);
269 const string lin =
s.str();
285 if (!(
s >> key) || key.empty())
287 "Line %u: Can't read string for entry type in: '%s'",
288 lineNum, lin.c_str()));
295 if (!(
s >>
id >> p2D.
x >> p2D.
y >> p2D.
phi))
297 "Line %u: Error parsing VERTEX2 line: '%s'", lineNum,
301 if (
g->nodes.find(
id) !=
g->nodes.end())
303 "Line %u: Error, duplicated verted ID %u in line: " 305 lineNum, static_cast<unsigned int>(
id), lin.c_str()));
311 if (itEq != lstEquivs.end())
id = itEq->second;
315 if (
g->nodes.find(
id) ==
g->nodes.end())
318 CPOSE>::constraint_t::type_value;
324 else if (
strCmpI(key,
"VERTEX3"))
328 "Line %u: Try to load VERTEX3 into a 2D graph: " 330 lineNum, lin.c_str()));
337 if (!(
s >>
id >> p3D.
x >> p3D.
y >> p3D.
z >> p3D.
roll >>
340 "Line %u: Error parsing VERTEX3 line: '%s'", lineNum,
344 if (
g->nodes.find(
id) !=
g->nodes.end())
346 "Line %u: Error, duplicated verted ID %u in line: " 348 lineNum, static_cast<unsigned int>(
id), lin.c_str()));
354 if (itEq != lstEquivs.end())
id = itEq->second;
358 if (
g->nodes.find(
id) ==
g->nodes.end())
365 else if (
strCmpI(key,
"VERTEX_SE3:QUAT"))
369 "Line %u: Try to load VERTEX_SE3:QUAT into a 2D " 371 lineNum, lin.c_str()));
376 if (!(
s >>
id >> p3D.
x >> p3D.
y >> p3D.
z >> p3D.
qx >> p3D.
qy >>
379 "Line %u: Error parsing VERTEX_SE3:QUAT line: '%s'",
380 lineNum, lin.c_str()));
383 if (
g->nodes.find(
id) !=
g->nodes.end())
385 "Line %u: Error, duplicated verted ID %u in line: " 387 lineNum, static_cast<unsigned int>(
id), lin.c_str()));
393 if (itEq != lstEquivs.end())
id = itEq->second;
397 if (
g->nodes.find(
id) ==
g->nodes.end())
416 if (!(
s >> from_id >> to_id))
418 "Line %u: Error parsing EDGE2 line: '%s'", lineNum,
424 lstEquivs.find(to_id);
425 if (itEq != lstEquivs.end()) to_id = itEq->second;
429 lstEquivs.find(from_id);
430 if (itEq != lstEquivs.end()) from_id = itEq->second;
433 if (from_id != to_id)
438 if (!(
s >> Ap_mean.
x >> Ap_mean.
y >> Ap_mean.
phi >>
439 Ap_cov_inv(0, 0) >> Ap_cov_inv(0, 1) >>
440 Ap_cov_inv(0, 2) >> Ap_cov_inv(1, 1) >>
441 Ap_cov_inv(1, 2) >> Ap_cov_inv(2, 2)))
443 "Line %u: Error parsing EDGE2 line: '%s'", lineNum,
447 Ap_cov_inv(1, 0) = Ap_cov_inv(0, 1);
448 Ap_cov_inv(2, 0) = Ap_cov_inv(0, 2);
449 Ap_cov_inv(2, 1) = Ap_cov_inv(1, 2);
456 g->insertEdge(from_id, to_id, newEdge);
459 else if (
strCmpI(key,
"EDGE3"))
463 "Line %u: Try to load EDGE3 into a 2D graph: '%s'",
464 lineNum, lin.c_str()));
469 if (!(
s >> from_id >> to_id))
471 "Line %u: Error parsing EDGE3 line: '%s'", lineNum,
477 lstEquivs.find(to_id);
478 if (itEq != lstEquivs.end()) to_id = itEq->second;
482 lstEquivs.find(from_id);
483 if (itEq != lstEquivs.end()) from_id = itEq->second;
486 if (from_id != to_id)
493 if (!(
s >> Ap_mean.
x >> Ap_mean.
y >> Ap_mean.
z >>
496 "Line %u: Error parsing EDGE3 line: '%s'", lineNum,
501 if (!(
s >> Ap_cov_inv(0, 0) >> Ap_cov_inv(0, 1) >>
502 Ap_cov_inv(0, 2) >> Ap_cov_inv(0, 5) >>
503 Ap_cov_inv(0, 4) >> Ap_cov_inv(0, 3) >>
504 Ap_cov_inv(1, 1) >> Ap_cov_inv(1, 2) >>
505 Ap_cov_inv(1, 5) >> Ap_cov_inv(1, 4) >>
506 Ap_cov_inv(1, 3) >> Ap_cov_inv(2, 2) >>
507 Ap_cov_inv(2, 5) >> Ap_cov_inv(2, 4) >>
508 Ap_cov_inv(2, 3) >> Ap_cov_inv(5, 5) >>
509 Ap_cov_inv(5, 4) >> Ap_cov_inv(5, 3) >>
510 Ap_cov_inv(4, 4) >> Ap_cov_inv(4, 3) >>
514 Ap_cov_inv.unit(6, 1.0);
516 if (alreadyWarnedUnknowns.find(
"MISSING_3D") ==
517 alreadyWarnedUnknowns.end())
519 alreadyWarnedUnknowns.insert(
"MISSING_3D");
520 cerr <<
"[CNetworkOfPoses::loadFromTextFile] " 521 << fil <<
":" << lineNum
522 <<
": Warning: Information matrix missing, " 529 for (
size_t r = 1;
r < 6;
r++)
530 for (
size_t c = 0;
c <
r;
c++)
531 Ap_cov_inv(
r,
c) = Ap_cov_inv(
c,
r);
539 g->insertEdge(from_id, to_id, newEdge);
542 else if (
strCmpI(key,
"EDGE_SE3:QUAT"))
546 "Line %u: Try to load EDGE3 into a 2D graph: '%s'",
547 lineNum, lin.c_str()));
554 if (!(
s >> from_id >> to_id))
556 "Line %u: Error parsing EDGE_SE3:QUAT line: '%s'",
557 lineNum, lin.c_str()));
562 lstEquivs.find(to_id);
563 if (itEq != lstEquivs.end()) to_id = itEq->second;
567 lstEquivs.find(from_id);
568 if (itEq != lstEquivs.end()) from_id = itEq->second;
571 if (from_id != to_id)
576 if (!(
s >> Ap_mean.
x >> Ap_mean.
y >> Ap_mean.
z >>
577 Ap_mean.
qx >> Ap_mean.
qy >> Ap_mean.
qz >> Ap_mean.
qr))
579 "Line %u: Error parsing EDGE_SE3:QUAT line: " 581 lineNum, lin.c_str()));
585 if (!(
s >> Ap_cov_inv(0, 0) >> Ap_cov_inv(0, 1) >>
586 Ap_cov_inv(0, 2) >> Ap_cov_inv(0, 5) >>
587 Ap_cov_inv(0, 4) >> Ap_cov_inv(0, 3) >>
588 Ap_cov_inv(1, 1) >> Ap_cov_inv(1, 2) >>
589 Ap_cov_inv(1, 5) >> Ap_cov_inv(1, 4) >>
590 Ap_cov_inv(1, 3) >> Ap_cov_inv(2, 2) >>
591 Ap_cov_inv(2, 5) >> Ap_cov_inv(2, 4) >>
592 Ap_cov_inv(2, 3) >> Ap_cov_inv(5, 5) >>
593 Ap_cov_inv(5, 4) >> Ap_cov_inv(5, 3) >>
594 Ap_cov_inv(4, 4) >> Ap_cov_inv(4, 3) >>
598 Ap_cov_inv.unit(6, 1.0);
600 if (alreadyWarnedUnknowns.find(
"MISSING_3D") ==
601 alreadyWarnedUnknowns.end())
603 alreadyWarnedUnknowns.insert(
"MISSING_3D");
604 cerr <<
"[CNetworkOfPoses::loadFromTextFile] " 605 << fil <<
":" << lineNum
606 <<
": Warning: Information matrix missing, " 613 for (
size_t r = 1;
r < 6;
r++)
614 for (
size_t c = 0;
c <
r;
c++)
615 Ap_cov_inv(
r,
c) = Ap_cov_inv(
c,
r);
624 g->insertEdge(from_id, to_id, newEdge);
627 else if (
strCmpI(key,
"EQUIV"))
636 "Line %u: Can't read id in FIX line: '%s'",
637 lineNum, lin.c_str()));
642 if (alreadyWarnedUnknowns.find(key) ==
643 alreadyWarnedUnknowns.end())
645 alreadyWarnedUnknowns.insert(key);
646 cerr <<
"[CNetworkOfPoses::loadFromTextFile] " << fil <<
":" 647 << lineNum <<
": Warning: unknown entry type: " << key
658 std::ifstream f(fil);
661 "Error opening file '%s' for reading", fil.c_str());
662 load_graph_of_poses_from_text_stream(
g, f, fil);
679 typedef map<pair<TNodeID,TNodeID>, vector<TEdgeIterator> > TListAllEdges;
680 TListAllEdges lstAllEdges;
683 for (TEdgeIterator itEd=
g->edges.begin();itEd!=
g->edges.end();++itEd)
686 const pair<TNodeID,TNodeID> arc_id = make_pair(
std::min(itEd->first.first,itEd->first.second),std::max(itEd->first.first,itEd->first.second));
688 vector<TEdgeIterator> &lstEdges = lstAllEdges[arc_id];
690 lstEdges.push_back(itEd);
697 const size_t N = it->second.size();
698 for (
size_t i=1;i<N;i++)
699 g->edges.erase(it->second[i]);
701 if (N>=2) nRemoved+=N-1;
721 typedef typename graph_t::constraint_t constraint_t;
724 dijkstra_t dijkstra(*
g,
g->root);
728 typename dijkstra_t::tree_graph_t treeView;
729 dijkstra.getTreeGraph(treeView);
732 struct VisitorComputePoses :
public dijkstra_t::tree_graph_t::Visitor
736 VisitorComputePoses(graph_t *
g) : m_g(
g) { }
737 virtual void OnVisitNode(
const TNodeID parent_id,
const typename dijkstra_t::tree_graph_t::Visitor::tree_t::TEdgeInfo &edge_to_child,
const size_t depth_level)
MRPT_OVERRIDE 740 const TNodeID child_id = edge_to_child.id;
745 if ((!edge_to_child.reverse && !m_g->edges_store_inverse_poses) ||
746 (edge_to_child.reverse && m_g->edges_store_inverse_poses)
749 m_g->nodes[child_id].composeFrom(m_g->nodes[parent_id], edge_to_child.data->getPoseMean());
753 m_g->nodes[child_id].composeFrom(m_g->nodes[parent_id], - edge_to_child.data->getPoseMean());
762 bool empty_node_annots =
g->nodes.begin()->second.is_node_annots_empty;
763 map<const TNodeID, TNodeAnnotations*> nodeID_to_annots;
764 if (!empty_node_annots) {
766 poses_cit =
g->nodes.begin();
767 poses_cit !=
g->nodes.end();
770 nodeID_to_annots.insert(
772 poses_cit->first, poses_cit->second.getCopyOfAnnots()));
777 g->nodes[
g->root] =
typename constraint_t::type_value();
780 VisitorComputePoses myVisitor(
g);
781 treeView.visitBreadthFirst(treeView.root, myVisitor);
784 if (!empty_node_annots) {
786 poses_cit =
g->nodes.begin();
787 poses_cit !=
g->nodes.end();
791 bool res = poses_cit->second.setAnnots(*node_annots);
799 "Setting annotations for nodeID \"%lu\" was unsuccessful",
800 static_cast<unsigned long>(poses_cit->first)));
870 bool ignoreCovariances)
875 const TNodeID from_id = itEdge->first.first;
876 const TNodeID to_id = itEdge->first.second;
881 ASSERTMSG_(itPoseFrom!=
g->nodes.end(),
format(
"Node %u doesn't have a global pose in 'nodes'.", static_cast<unsigned int>(from_id)))
882 ASSERTMSG_(itPoseTo!=
g->nodes.end(),
format(
"Node %u doesn't have a global pose in 'nodes'.", static_cast<unsigned int>(to_id)))
885 typedef typename graph_t::constraint_t constraint_t;
887 const typename constraint_t::type_value &from_mean = itPoseFrom->second;
888 const typename constraint_t::type_value &to_mean = itPoseTo->second;
891 const constraint_t &edge_delta_pose = itEdge->second;
892 const typename constraint_t::type_value &edge_delta_pose_mean = edge_delta_pose.getPoseMean();
894 if (ignoreCovariances)
898 from_plus_delta.composeFrom(from_mean, edge_delta_pose_mean);
901 return auxEuclid2Dist(from_plus_delta,to_mean);
907 constraint_t from_plus_delta = edge_delta_pose;
908 from_plus_delta.changeCoordinatesReference(from_mean);
916 err[i] = from_plus_delta.getPoseMean()[i] - to_mean[i];
919 return auxMaha2Dist(err,from_plus_delta);
#define ASSERT_EQUAL_(__A, __B)
A directed graph with the argument of the template specifying the type of the annotations in the edge...
static double auxMaha2Dist(VEC &err, const CPosePDFGaussian &p)
double x() const
Common members of all points & poses classes.
Classes for serialization, sockets, ini-file manipulation, streams, list of properties-values, timewatch, extensions to STL.
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const CPosePDFGaussianInf &edge, std::ostream &f)
A template to obtain the type of its argument as a string at compile time.
Abstract class from which NodeAnnotations related classes can be implemented.
#define MRPT_OVERRIDE
C++11 "override" for virtuals:
bool getNextLine(std::string &out_str)
Reads from the file and return the next (non-comment) line, as a std::string.
double roll
Roll coordinate (rotation angle over X coordinate).
static double auxMaha2Dist(VEC &err, const mrpt::poses::CPose2D &p)
#define THROW_EXCEPTION(msg)
Abstract graph and tree data structures, plus generic graph algorithms.
#define THROW_EXCEPTION_FMT(_FORMAT_STRING,...)
mrpt::math::CMatrixDouble66 cov_inv
The inverse of the 6x6 covariance matrix.
double pitch() const
Get the PITCH angle (in radians)
double yaw() const
Get the YAW angle (in radians)
This file implements miscelaneous matrix and matrix/vector operations, and internal functions in mrpt...
MAT_C::Scalar multiply_HCHt_scalar(const VECTOR_H &H, const MAT_C &C)
r (a scalar) = H * C * H^t (with a vector H and a symmetric matrix C)
const Scalar * const_iterator
double yaw
Yaw coordinate (rotation angle over Z axis).
static double auxMaha2Dist(VEC &err, const CPosePDFGaussianInf &p)
static void read_graph_of_poses_from_binary_file(graph_t *g, mrpt::utils::CStream &in)
static double auxEuclid2Dist(const mrpt::poses::CPose2D &p1, const mrpt::poses::CPose2D &p2)
static double auxEuclid2Dist(const mrpt::poses::CPose3D &p1, const mrpt::poses::CPose3D &p2)
static void graph_of_poses_dijkstra_init(graph_t *g)
T square(const T x)
Inline function for the square of a number.
A directed graph of pose constraints, with edges being the relative poses between pairs of nodes iden...
void rewind()
Reset the read pointer to the beginning of the file.
static void copyFrom2D(CPose2D &p, const CPosePDFGaussianInf &pdf)
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const CPose3DPDFGaussian &edge, std::ostream &f)
This base class is used to provide a unified interface to files,memory buffers,..Please see the deriv...
void wrapToPiInPlace(T &a)
Modifies the given angle to translate it into the ]-pi,pi] range.
static void save_graph_of_poses_to_ostream(const graph_t *g, std::ostream &f)
This base provides a set of functions for maths stuff.
static void save_graph_of_poses_to_binary_file(const graph_t *g, mrpt::utils::CStream &out)
Declares a class that represents a Probability Density function (PDF) of a 2D pose ...
uint64_t TNodeID
The type for node IDs in graphs of different types.
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const CPosePDFGaussian &edge, std::ostream &f)
#define MRPT_UNUSED_PARAM(a)
Can be used to avoid "not used parameters" warnings from the compiler.
static void copyFrom2D(POSE_PDF &p, const CPosePDFGaussianInf &pdf)
#define MRPT_THROW_UNKNOWN_SERIALIZATION_VERSION(__V)
For use in CSerializable implementations.
static void copyFrom2D(CPose3D &p, const CPosePDFGaussianInf &pdf)
double z
Translation in x,y,z.
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
std::pair< TNodeID, TNodeID > TPairNodeIDs
A pair of node IDs.
static double auxMaha2Dist(VEC &err, const CPose3DPDFGaussian &p)
CPose3D mean
The mean value.
A class used to store a 3D pose as a translation (x,y,z) and a quaternion (qr,qx,qy,qz).
A class for parsing text files, returning each non-empty and non-comment line, along its line number...
std::string BASE_IMPEXP format(const char *fmt,...) MRPT_printf_format_check(1
A std::string version of C sprintf.
double qz
Unit quaternion part, qr,qx,qy,qz.
GLsizei const GLchar ** string
T wrapToPi(T a)
Modifies the given angle to translate it into the ]-pi,pi] range.
Classes for 2D/3D geometry representation, both of single values and probability density distribution...
double roll() const
Get the ROLL angle (in radians)
static void load_graph_of_poses_from_text_stream(graph_t *g, std::istream &f, const std::string &fil=std::string("(none)"))
double pitch
Pitch coordinate (rotation angle over Y axis).
Lightweight 3D pose (three spatial coordinates, plus a quaternion ).
static size_t graph_of_poses_collapse_dup_edges(graph_t *g)
static void save_graph_of_poses_to_text_file(const graph_t *g, const std::string &fil)
This is the global namespace for all Mobile Robot Programming Toolkit (MRPT) libraries.
A Probability Density function (PDF) of a 2D pose as a Gaussian with a mean and the inverse of the c...
GLdouble GLdouble GLdouble r
CPose2D mean
The mean value.
static void write_VERTEX_line(const TNodeID id, const mrpt::poses::CPose2D &p, std::ostream &f)
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).
This file implements matrix/vector text and binary serialization.
static double graph_edge_sqerror(const graph_t *g, const typename mrpt::graphs::CDirectedGraph< typename graph_t::constraint_t >::edges_map_t::const_iterator &itEdge, bool ignoreCovariances)
const double & phi() const
Get the phi angle of the 2D pose (in radians)
static void copyFrom3D(CPose3D &p, const CPose3DPDFGaussianInf &pdf)
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const mrpt::poses::CPose3D &edge, std::ostream &f)
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...
A partial specialization of CArrayNumeric for double numbers.
Declares a class that represents a Probability Density function (PDF) of a 3D pose ...
size_t getCurrentLineNumber() const
Return the line number of the last line returned with getNextLine.
static void load_graph_of_poses_from_text_file(graph_t *g, const std::string &fil)
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const mrpt::poses::CPose2D &edge, std::ostream &f)
global_poses_t nodes
The nodes (vertices) of the graph, with their estimated "global" (with respect to root) position...
static double auxMaha2Dist(VEC &err, const CPose3DPDFGaussianInf &p)
The Dijkstra algorithm for finding the shortest path between a given source node in a (weighted) dire...
static void write_EDGE_line(const TPairNodeIDs &edgeIDs, const CPose3DPDFGaussianInf &edge, std::ostream &f)
static void copyFrom3D(CPose2D &p, const CPose3DPDFGaussianInf &pdf)
static void copyFrom3D(POSE_PDF &p, const CPose3DPDFGaussianInf &pdf)
bool BASE_IMPEXP strCmpI(const std::string &s1, const std::string &s2)
Return true if the two strings are equal (case insensitive)
unsigned __int32 uint32_t
static void write_VERTEX_line(const TNodeID id, const mrpt::poses::CPose3D &p, std::ostream &f)
#define ASSERTMSG_(f, __ERROR_MSG)
double phi
Orientation (rads)
mrpt::math::CMatrixDouble33 cov_inv
The inverse of the 3x3 covariance matrix (the "information" matrix)
static double auxMaha2Dist(VEC &err, const mrpt::poses::CPose3D &p)