00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef CONSTRAINED_POSE_NETWORK_IMPL_H
00029 #define CONSTRAINED_POSE_NETWORK_IMPL_H
00030
00031 #include <mrpt/graphs/dijkstra.h>
00032 #include <mrpt/utils/CTextFileLinesParser.h>
00033
00034
00035 namespace mrpt
00036 {
00037 namespace graphs
00038 {
00039 namespace detail
00040 {
00041 using namespace std;
00042 using namespace mrpt;
00043 using namespace mrpt::utils;
00044 using namespace mrpt::poses;
00045 using namespace mrpt::graphs;
00046
00047 template <class POSE_PDF> struct TPosePDFHelper
00048 {
00049 static inline void copyFrom2D(POSE_PDF &p, const CPosePDFGaussianInf &pdf ) { p.copyFrom( pdf ); }
00050 static inline void copyFrom3D(POSE_PDF &p, const CPose3DPDFGaussianInf &pdf ) { p.copyFrom( pdf ); }
00051 };
00052 template <> struct TPosePDFHelper<CPose2D>
00053 {
00054 static inline void copyFrom2D(CPose2D &p, const CPosePDFGaussianInf &pdf ) { p = pdf.mean; }
00055 static inline void copyFrom3D(CPose2D &p, const CPose3DPDFGaussianInf &pdf ) { p = CPose2D(pdf.mean); }
00056 };
00057 template <> struct TPosePDFHelper<CPose3D>
00058 {
00059 static inline void copyFrom2D(CPose3D &p, const CPosePDFGaussianInf &pdf ) { p = pdf.mean; }
00060 static inline void copyFrom3D(CPose3D &p, const CPose3DPDFGaussianInf &pdf ) { p = pdf.mean; }
00061 };
00062
00063
00064 template <class graph_t>
00065 struct graph_ops
00066 {
00067 static void write_VERTEX_line(const TNodeID id, const CPose2D &p, std::ofstream &f)
00068 {
00069
00070 f << "VERTEX2 " << id << " " << p.x() << " " << p.y() << " " << p.phi() << endl;
00071 }
00072 static void write_VERTEX_line(const TNodeID id, const CPose3D &p, std::ofstream &f)
00073 {
00074
00075
00076 f << "VERTEX3 " << id << " " << p.x() << " " << p.y() << " " << p.z()<< " " << p.roll()<< " " << p.pitch()<< " " << p.yaw() << endl;
00077 }
00078
00079
00080 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPosePDFGaussianInf & edge, std::ofstream &f)
00081 {
00082
00083
00084 f << "EDGE2 " << edgeIDs.first << " " << edgeIDs.second << " " <<
00085 edge.mean.x()<<" "<<edge.mean.y()<<" "<<edge.mean.phi()<<" "<<
00086 edge.cov_inv(0,0)<<" "<<edge.cov_inv(0,1)<<" "<<edge.cov_inv(1,1)<<" "<<
00087 edge.cov_inv(2,2)<<" "<<edge.cov_inv(0,2)<<" "<<edge.cov_inv(1,2) << endl;
00088 }
00089 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPose3DPDFGaussianInf & edge, std::ofstream &f)
00090 {
00091
00092
00093
00094 f << "EDGE3 " << edgeIDs.first << " " << edgeIDs.second << " " <<
00095 edge.mean.x()<<" "<<edge.mean.y()<<" "<<edge.mean.z()<<" "<<
00096 edge.mean.roll()<<" "<<edge.mean.pitch()<<" "<<edge.mean.yaw()<<" "<<
00097 edge.cov_inv(0,0)<<" "<<edge.cov_inv(0,1)<<" "<<edge.cov_inv(0,2)<<" "<<edge.cov_inv(0,5)<<" "<<edge.cov_inv(0,4)<<" "<<edge.cov_inv(0,3)<<" "<<
00098 edge.cov_inv(1,1)<<" "<<edge.cov_inv(1,2)<<" "<<edge.cov_inv(1,5)<<" "<<edge.cov_inv(1,4)<<" "<<edge.cov_inv(1,3)<<" "<<
00099 edge.cov_inv(2,2)<<" "<<edge.cov_inv(2,5)<<" "<<edge.cov_inv(2,4)<<" "<<edge.cov_inv(2,3)<<" "<<
00100 edge.cov_inv(5,5)<<" "<<edge.cov_inv(5,4)<<" "<<edge.cov_inv(5,3)<<" "<<
00101 edge.cov_inv(4,4)<<" "<<edge.cov_inv(4,3)<<" "<<
00102 edge.cov_inv(3,3) << endl;
00103 }
00104 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPosePDFGaussian & edge, std::ofstream &f)
00105 {
00106 CPosePDFGaussianInf p;
00107 p.copyFrom(edge);
00108 write_EDGE_line(edgeIDs,p,f);
00109 }
00110 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPose3DPDFGaussian & edge, std::ofstream &f)
00111 {
00112 CPose3DPDFGaussianInf p;
00113 p.copyFrom(edge);
00114 write_EDGE_line(edgeIDs,p,f);
00115 }
00116 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPose2D & edge, std::ofstream &f)
00117 {
00118 CPosePDFGaussianInf p;
00119 p.mean = edge;
00120 p.cov_inv.unit(3,1.0);
00121 write_EDGE_line(edgeIDs,p,f);
00122 }
00123 static void write_EDGE_line( const TPairNodeIDs &edgeIDs,const CPose3D & edge, std::ofstream &f)
00124 {
00125 CPose3DPDFGaussianInf p;
00126 p.mean = edge;
00127 p.cov_inv.unit(6,1.0);
00128 write_EDGE_line(edgeIDs,p,f);
00129 }
00130
00131
00132
00133
00134
00135 static void save_graph_of_poses_from_text_file(const graph_t *g, const std::string &fil)
00136 {
00137 typedef typename graph_t::constraint_t CPOSE;
00138
00139 std::ofstream f;
00140 f.open(fil.c_str());
00141 if (!f.is_open())
00142 THROW_EXCEPTION_CUSTOM_MSG1("Error opening file '%s' for writing",fil.c_str());
00143
00144
00145 for (typename graph_t::global_poses_t::const_iterator itNod = g->nodes.begin();itNod!=g->nodes.end();++itNod)
00146 write_VERTEX_line(itNod->first, itNod->second, f);
00147
00148
00149 for (typename graph_t::const_iterator it=g->begin();it!=g->end();++it)
00150 if (it->first.first!=it->first.second)
00151 write_EDGE_line( it->first, it->second, f);
00152
00153 }
00154
00155
00156
00157
00158
00159 static void load_graph_of_poses_from_text_file(graph_t *g, const std::string &fil)
00160 {
00161 typedef typename graph_t::constraint_t CPOSE;
00162
00163 set<string> alreadyWarnedUnknowns;
00164
00165
00166 g->clear();
00167
00168
00169
00170 const bool graph_is_3D = CPOSE::is_3D();
00171
00172 CTextFileLinesParser filParser(fil);
00173
00174
00175
00176
00177
00178
00179 map<TNodeID,TNodeID> lstEquivs;
00180
00181
00182 istringstream s;
00183 while (filParser.getNextLine(s))
00184 {
00185 const unsigned int lineNum = filParser.getCurrentLineNumber();
00186 const string lin = s.str();
00187
00188 string key;
00189 if ( !(s >> key) || key.empty() )
00190 THROW_EXCEPTION(format("Line %u: Can't read string for entry type in: '%s'", lineNum, lin.c_str() ) );
00191
00192 if ( strCmpI(key,"EQUIV") )
00193 {
00194
00195 TNodeID id1,id2;
00196 if (!(s>> id1 >> id2))
00197 THROW_EXCEPTION(format("Line %u: Can't read id1 & id2 in EQUIV line: '%s'", lineNum, lin.c_str() ) );
00198 lstEquivs[std::max(id1,id2)] = std::min(id1,id2);
00199 }
00200 }
00201
00202
00203
00204
00205 filParser.rewind();
00206
00207
00208 while (filParser.getNextLine(s))
00209 {
00210 const unsigned int lineNum = filParser.getCurrentLineNumber();
00211 const string lin = s.str();
00212
00213
00214
00215
00216
00217
00218
00219 string key;
00220 if ( !(s >> key) || key.empty() )
00221 THROW_EXCEPTION(format("Line %u: Can't read string for entry type in: '%s'", lineNum, lin.c_str() ) );
00222
00223 if ( strCmpI(key,"VERTEX2") || strCmpI(key,"VERTEX") )
00224 {
00225 TNodeID id;
00226 TPose2D p2D;
00227 if (!(s>> id >> p2D.x >> p2D.y >> p2D.phi))
00228 THROW_EXCEPTION(format("Line %u: Error parsing VERTEX2 line: '%s'", lineNum, lin.c_str() ) );
00229
00230
00231 if (g->nodes.find(id)!=g->nodes.end())
00232 THROW_EXCEPTION(format("Line %u: Error, duplicated verted ID %u in line: '%s'", lineNum, static_cast<unsigned int>(id), lin.c_str() ) );
00233
00234
00235 {
00236 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(id);
00237 if (itEq!=lstEquivs.end()) id = itEq->second;
00238 }
00239
00240
00241 if (g->nodes.find(id)==g->nodes.end())
00242 {
00243 typename CNetworkOfPoses<CPOSE>::constraint_t::type_value & newNode = g->nodes[id];
00244 newNode = CPose2D(p2D);
00245 }
00246 }
00247 else if ( strCmpI(key,"VERTEX3") )
00248 {
00249 if (!graph_is_3D)
00250 THROW_EXCEPTION(format("Line %u: Try to load VERTEX3 into a 2D graph: '%s'", lineNum, lin.c_str() ) );
00251
00252
00253
00254 TNodeID id;
00255 TPose3D p3D;
00256
00257 if (!(s>> id >> p3D.x >> p3D.y >> p3D.z >> p3D.roll >> p3D.pitch >> p3D.yaw ))
00258 THROW_EXCEPTION(format("Line %u: Error parsing VERTEX3 line: '%s'", lineNum, lin.c_str() ) );
00259
00260
00261 if (g->nodes.find(id)!=g->nodes.end())
00262 THROW_EXCEPTION(format("Line %u: Error, duplicated verted ID %u in line: '%s'", lineNum, static_cast<unsigned int>(id), lin.c_str() ) );
00263
00264
00265 {
00266 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(id);
00267 if (itEq!=lstEquivs.end()) id = itEq->second;
00268 }
00269
00270
00271 if (g->nodes.find(id)==g->nodes.end())
00272 {
00273 g->nodes[id] = typename CNetworkOfPoses<CPOSE>::constraint_t::type_value( CPose3D(p3D) );
00274 }
00275 }
00276 else if ( strCmpI(key,"EDGE2") || strCmpI(key,"EDGE") )
00277 {
00278
00279
00280
00281
00282
00283
00284
00285 TNodeID to_id, from_id;
00286 if (!(s>> from_id >> to_id ))
00287 THROW_EXCEPTION(format("Line %u: Error parsing EDGE2 line: '%s'", lineNum, lin.c_str() ) );
00288
00289
00290 {
00291 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(to_id);
00292 if (itEq!=lstEquivs.end()) to_id = itEq->second;
00293 }
00294 {
00295 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(from_id);
00296 if (itEq!=lstEquivs.end()) from_id = itEq->second;
00297 }
00298
00299 if (from_id!=to_id)
00300 {
00301 TPose2D Ap_mean;
00302 CMatrixDouble33 Ap_cov_inv;
00303 if (!(s>>
00304 Ap_mean.x >> Ap_mean.y >> Ap_mean.phi >>
00305 Ap_cov_inv(0,0) >> Ap_cov_inv(0,1) >> Ap_cov_inv(1,1) >>
00306 Ap_cov_inv(2,2) >> Ap_cov_inv(0,2) >> Ap_cov_inv(1,2) ))
00307 THROW_EXCEPTION(format("Line %u: Error parsing EDGE2 line: '%s'", lineNum, lin.c_str() ) );
00308
00309
00310 Ap_cov_inv(1,0) = Ap_cov_inv(0,1);
00311 Ap_cov_inv(2,0) = Ap_cov_inv(0,2);
00312 Ap_cov_inv(2,1) = Ap_cov_inv(1,2);
00313
00314
00315 typename CNetworkOfPoses<CPOSE>::edge_t newEdge;
00316 TPosePDFHelper<CPOSE>::copyFrom2D(newEdge, CPosePDFGaussianInf( CPose2D(Ap_mean), Ap_cov_inv ) );
00317 g->insertEdge(from_id, to_id, newEdge);
00318 }
00319 }
00320 else if ( strCmpI(key,"EDGE3") )
00321 {
00322 if (!graph_is_3D)
00323 THROW_EXCEPTION(format("Line %u: Try to load EDGE3 into a 2D graph: '%s'", lineNum, lin.c_str() ) );
00324
00325
00326 TNodeID to_id, from_id;
00327 if (!(s>> from_id >> to_id ))
00328 THROW_EXCEPTION(format("Line %u: Error parsing EDGE3 line: '%s'", lineNum, lin.c_str() ) );
00329
00330
00331 {
00332 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(to_id);
00333 if (itEq!=lstEquivs.end()) to_id = itEq->second;
00334 }
00335 {
00336 const map<TNodeID,TNodeID>::const_iterator itEq = lstEquivs.find(from_id);
00337 if (itEq!=lstEquivs.end()) from_id = itEq->second;
00338 }
00339
00340 if (from_id!=to_id)
00341 {
00342 TPose3D Ap_mean;
00343 CMatrixDouble66 Ap_cov_inv;
00344
00345 if (!(s>> Ap_mean.x >> Ap_mean.y >> Ap_mean.z >> Ap_mean.roll >> Ap_mean.pitch >> Ap_mean.yaw ))
00346 THROW_EXCEPTION(format("Line %u: Error parsing EDGE3 line: '%s'", lineNum, lin.c_str() ) );
00347
00348
00349 if (!(s>>
00350 Ap_cov_inv(0,0) >> Ap_cov_inv(0,1) >> Ap_cov_inv(0,2) >> Ap_cov_inv(0,5) >> Ap_cov_inv(0,4) >> Ap_cov_inv(0,3) >>
00351 Ap_cov_inv(1,1) >> Ap_cov_inv(1,2) >> Ap_cov_inv(1,5) >> Ap_cov_inv(1,4) >> Ap_cov_inv(1,3) >>
00352 Ap_cov_inv(2,2) >> Ap_cov_inv(2,5) >> Ap_cov_inv(2,4) >> Ap_cov_inv(2,3) >>
00353 Ap_cov_inv(5,5) >> Ap_cov_inv(5,4) >> Ap_cov_inv(5,3) >>
00354 Ap_cov_inv(4,4) >> Ap_cov_inv(4,3) >>
00355 Ap_cov_inv(3,3) ))
00356 {
00357
00358 Ap_cov_inv.unit(6,1.0);
00359
00360 if (alreadyWarnedUnknowns.find("MISSING_3D")==alreadyWarnedUnknowns.end())
00361 {
00362 alreadyWarnedUnknowns.insert("MISSING_3D");
00363 cerr << "[CNetworkOfPoses::loadFromTextFile] " << fil << ":" << lineNum << ": Warning: Information matrix missing, assuming unity.\n";
00364 }
00365 }
00366 else
00367 {
00368
00369 for (size_t r=1;r<6;r++)
00370 for (size_t c=0;c<r;c++)
00371 Ap_cov_inv(r,c) = Ap_cov_inv(c,r);
00372 }
00373
00374
00375 typename CNetworkOfPoses<CPOSE>::edge_t newEdge;
00376 TPosePDFHelper<CPOSE>::copyFrom3D(newEdge, CPose3DPDFGaussianInf( CPose3D(Ap_mean), Ap_cov_inv ) );
00377 g->insertEdge(from_id, to_id, newEdge);
00378 }
00379 }
00380 else if ( strCmpI(key,"EQUIV") )
00381 {
00382
00383 }
00384 else
00385 {
00386 if (alreadyWarnedUnknowns.find(key)==alreadyWarnedUnknowns.end())
00387 {
00388 alreadyWarnedUnknowns.insert(key);
00389 cerr << "[CNetworkOfPoses::loadFromTextFile] " << fil << ":" << lineNum << ": Warning: unknown entry type: " << key << endl;
00390 }
00391 }
00392 }
00393
00394 }
00395
00396
00397
00398
00399
00400
00401
00402
00403
00404 static size_t graph_of_poses_collapse_dup_edges(graph_t *g)
00405 {
00406 MRPT_START
00407 typedef typename graph_t::edges_map_t::iterator TEdgeIterator;
00408
00409
00410
00411 typedef map<pair<TNodeID,TNodeID>, vector<TEdgeIterator> > TListAllEdges;
00412 TListAllEdges lstAllEdges;
00413
00414
00415 for (TEdgeIterator itEd=g->edges.begin();itEd!=g->edges.end();++itEd)
00416 {
00417
00418 const pair<TNodeID,TNodeID> arc_id = make_pair( std::min(itEd->first.first,itEd->first.second),std::max(itEd->first.first,itEd->first.second) );
00419
00420 vector<TEdgeIterator> &lstEdges = lstAllEdges[arc_id];
00421
00422 lstEdges.push_back(itEd);
00423 }
00424
00425
00426 size_t nRemoved = 0;
00427 for (typename TListAllEdges::const_iterator it=lstAllEdges.begin();it!=lstAllEdges.end();++it)
00428 {
00429 const size_t N = it->second.size();
00430 for (size_t i=1;i<N;i++)
00431 g->edges.erase( it->second[i] );
00432
00433 if (N>=2) nRemoved+=N-1;
00434 }
00435
00436 return nRemoved;
00437 MRPT_END
00438 }
00439
00440
00441
00442
00443
00444
00445
00446 static void graph_of_poses_dijkstra_init(graph_t *g)
00447 {
00448 MRPT_START
00449
00450
00451 typedef CDijkstra<graph_t,typename graph_t::maps_implementation_t> dijkstra_t;
00452 typedef typename graph_t::constraint_t constraint_t;
00453
00454 dijkstra_t dijkstra(*g, g->root);
00455
00456
00457
00458 typename dijkstra_t::tree_graph_t treeView;
00459 dijkstra.getTreeGraph(treeView);
00460
00461
00462 struct VisitorComputePoses : public dijkstra_t::tree_graph_t::Visitor
00463 {
00464 graph_t * m_g;
00465
00466 VisitorComputePoses(graph_t *g) : m_g(g) { }
00467 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 )
00468 {
00469 const TNodeID child_id = edge_to_child.id;
00470
00471
00472
00473 if ( (!edge_to_child.reverse && !m_g->edges_store_inverse_poses) ||
00474 ( edge_to_child.reverse && m_g->edges_store_inverse_poses)
00475 )
00476 {
00477 m_g->nodes[child_id].composeFrom( m_g->nodes[parent_id], edge_to_child.data->getPoseMean() );
00478 }
00479 else
00480 {
00481 m_g->nodes[child_id].composeFrom( m_g->nodes[parent_id], - edge_to_child.data->getPoseMean() );
00482 }
00483 }
00484 };
00485
00486
00487 g->nodes.clear();
00488 g->nodes[g->root] = typename constraint_t::type_value();
00489
00490
00491 VisitorComputePoses myVisitor(g);
00492 treeView.visitBreadthFirst(treeView.root, myVisitor);
00493
00494 MRPT_END
00495 }
00496
00497
00498
00499 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPosePDFGaussianInf &p) {
00500 math::wrapToPiInPlace(err[2]);
00501 return mrpt::math::multiply_HCHt_scalar(err,p.cov_inv);
00502 }
00503 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPose3DPDFGaussianInf &p) {
00504 math::wrapToPiInPlace(err[3]);
00505 math::wrapToPiInPlace(err[4]);
00506 math::wrapToPiInPlace(err[5]);
00507 return mrpt::math::multiply_HCHt_scalar(err,p.cov_inv);
00508 }
00509 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPosePDFGaussian &p) {
00510 math::wrapToPiInPlace(err[2]);
00511 CMatrixDouble33 COV_INV(UNINITIALIZED_MATRIX);
00512 p.cov.inv(COV_INV);
00513 return mrpt::math::multiply_HCHt_scalar(err,COV_INV);
00514 }
00515 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPose3DPDFGaussian &p) {
00516 math::wrapToPiInPlace(err[3]);
00517 math::wrapToPiInPlace(err[4]);
00518 math::wrapToPiInPlace(err[5]);
00519 CMatrixDouble66 COV_INV(UNINITIALIZED_MATRIX);
00520 p.cov.inv(COV_INV);
00521 return mrpt::math::multiply_HCHt_scalar(err,COV_INV);
00522 }
00523
00524 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPose2D &p) {
00525 math::wrapToPiInPlace(err[2]);
00526 return square(err[0])+square(err[1])+square(err[2]);
00527 }
00528 template <class VEC> static inline double auxMaha2Dist(VEC &err,const CPose3D &p) {
00529 math::wrapToPiInPlace(err[3]);
00530 math::wrapToPiInPlace(err[4]);
00531 math::wrapToPiInPlace(err[5]);
00532 return square(err[0])+square(err[1])+square(err[2])+square(err[3])+square(err[4])+square(err[5]);
00533 }
00534
00535
00536 static inline double auxEuclid2Dist(const CPose2D &p1,const CPose2D &p2) {
00537 return
00538 square(p1.x()-p2.x())+
00539 square(p1.y()-p2.y())+
00540 square( mrpt::math::wrapToPi(p1.phi()-p2.phi() ) );
00541 }
00542 static inline double auxEuclid2Dist(const CPose3D &p1,const CPose3D &p2) {
00543 return
00544 square(p1.x()-p2.x())+
00545 square(p1.y()-p2.y())+
00546 square(p1.z()-p2.z())+
00547 square( mrpt::math::wrapToPi(p1.yaw()-p2.yaw() ) )+
00548 square( mrpt::math::wrapToPi(p1.pitch()-p2.pitch() ) )+
00549 square( mrpt::math::wrapToPi(p1.roll()-p2.roll() ) );
00550 }
00551
00552
00553
00554
00555
00556
00557 static double graph_edge_sqerror(
00558 const graph_t *g,
00559 const typename mrpt::graphs::CDirectedGraph<typename graph_t::constraint_t>::edges_map_t::const_iterator &itEdge,
00560 bool ignoreCovariances )
00561 {
00562 MRPT_START
00563
00564
00565 const TNodeID from_id = itEdge->first.first;
00566 const TNodeID to_id = itEdge->first.second;
00567
00568
00569 typename graph_t::global_poses_t::const_iterator itPoseFrom = g->nodes.find(from_id);
00570 typename graph_t::global_poses_t::const_iterator itPoseTo = g->nodes.find(to_id);
00571 ASSERTMSG_(itPoseFrom!=g->nodes.end(), format("Node %u doesn't have a global pose in 'nodes'.", static_cast<unsigned int>(from_id)))
00572 ASSERTMSG_(itPoseTo!=g->nodes.end(), format("Node %u doesn't have a global pose in 'nodes'.", static_cast<unsigned int>(to_id)))
00573
00574
00575 typedef typename graph_t::constraint_t constraint_t;
00576
00577 const typename constraint_t::type_value &from_mean = itPoseFrom->second;
00578 const typename constraint_t::type_value &to_mean = itPoseTo->second;
00579
00580
00581 const constraint_t &edge_delta_pose = itEdge->second;
00582 const typename constraint_t::type_value &edge_delta_pose_mean = edge_delta_pose.getPoseMean();
00583
00584 if (ignoreCovariances)
00585 {
00586
00587 typename constraint_t::type_value from_plus_delta(UNINITIALIZED_POSE);
00588 from_plus_delta.composeFrom(from_mean, edge_delta_pose_mean);
00589
00590
00591 return auxEuclid2Dist(from_plus_delta,to_mean);
00592 }
00593 else
00594 {
00595
00596
00597 constraint_t from_plus_delta = edge_delta_pose;
00598 from_plus_delta.changeCoordinatesReference(from_mean);
00599
00600
00601
00602
00603
00604 CArrayDouble<constraint_t::type_value::static_size> err;
00605 for (size_t i=0;i<constraint_t::type_value::static_size;i++)
00606 err[i] = from_plus_delta.getPoseMean()[i] - to_mean[i];
00607
00608
00609 return auxMaha2Dist(err,from_plus_delta);
00610 }
00611 MRPT_END
00612 }
00613
00614 };
00615
00616 }
00617 }
00618 }
00619
00620 #endif