Go to the documentation of this file.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 
00029 
00030 
00031 
00032 
00033 
00034 
00035 
00036 
00043 #include "posegraph2.hh"
00044 #include <fstream>
00045 #include <sstream>
00046 #include <string>
00047 
00048 using namespace std;
00049 
00050 namespace AISNavigation {
00051 
00052 
00053 typedef unsigned int uint;
00054 #define LINESIZE 81920
00055 
00056 
00057 #define DEBUG(i) \
00058         if (verboseLevel>i) cerr
00059 
00060 
00061 bool TreePoseGraph2::load(const char* filename, bool overrideCovariances){
00062   clear();
00063   ifstream is(filename);
00064   if (!is)
00065     return false;
00066 
00067   while(is){
00068     char buf[LINESIZE];
00069     is.getline(buf,LINESIZE);
00070     istringstream ls(buf);
00071     string tag;
00072     ls >> tag;
00073 
00074     if (tag=="VERTEX" || tag=="VERTEX2"){
00075       int id;
00076       Pose p;
00077       ls >> id >> p.x() >> p.y() >> p.theta(); 
00078       if (addVertex(id,p))
00079         DEBUG(2) << "V " << id << endl;
00080       
00081     }
00082 
00083     if (tag=="EDGE" || tag=="EDGE2"){
00084       int id1, id2;
00085       Pose p;
00086       InformationMatrix m;
00087       ls >> id1 >> id2 >> p.x() >> p.y() >> p.theta();
00088       if (overrideCovariances){
00089         m.values[0][0]=1;  m.values[1][1]=1; m.values[2][2]=1;
00090         m.values[0][1]=0;  m.values[0][2]=0; m.values[1][2]=0;
00091       } else {
00092         ls >> m.values[0][0] >> m.values[0][1] >> m.values [1][1]
00093            >> m.values[2][2] >> m.values[0][2] >> m.values [1][2];
00094       }
00095       m.values[1][0]=m.values[0][1];
00096       m.values[2][0]=m.values[0][2];
00097       m.values[2][1]=m.values[1][2];
00098       TreePoseGraph2::Vertex* v1=vertex(id1);
00099       TreePoseGraph2::Vertex* v2=vertex(id2);
00100       Transformation t(p);
00101       if (addEdge(v1, v2,t ,m))
00102          DEBUG(2) << "E " << id1 << " " << id2 <<  endl;
00103     }
00104   }
00105   return true;
00106 }
00107 
00108 bool TreePoseGraph2::loadEquivalences(const char* filename){
00109   ifstream is(filename);
00110   if (!is)
00111     return false;
00112   EdgeList suppressed;
00113   uint equivCount=0;
00114   while (is){
00115     char buf[LINESIZE];
00116     is.getline(buf, LINESIZE);
00117     istringstream ls(buf);
00118     string tag;
00119     ls >> tag;
00120     if (tag=="EQUIV"){
00121       int id1, id2;
00122       ls >> id1 >> id2;
00123       Edge* e=edge(id1,id2);
00124       if (!e)
00125         e=edge(id2,id1);
00126       if (e){
00127         suppressed.push_back(e);
00128         equivCount++;
00129       }
00130     }
00131   }
00132   for (EdgeList::iterator it=suppressed.begin(); it!=suppressed.end(); it++){
00133     Edge* e=*it;
00134     if (e->v1->id > e->v2->id)
00135       revertEdge(e);
00136     collapseEdge(e);
00137   }
00138   for (TreePoseGraph2::VertexMap::iterator it=vertices.begin(); it!=vertices.end(); it++){
00139     Vertex* v=it->second;
00140     v->edges.clear();
00141   }
00142   for (TreePoseGraph2::EdgeMap::iterator it=edges.begin(); it!=edges.end(); it++){
00143     TreePoseGraph2::Edge * e=it->second;
00144     e->v1->edges.push_back(e);
00145     e->v2->edges.push_back(e);
00146   }
00147   return true;
00148 }
00149 
00150 bool TreePoseGraph2::saveGnuplot(const char* filename){
00151   ofstream os(filename);
00152   if (!os)
00153     return false;
00154 
00155   for (TreePoseGraph2::EdgeMap::const_iterator it=edges.begin(); it!=edges.end(); it++){
00156     const TreePoseGraph2::Edge * e=it->second;
00157     const Vertex* v1=e->v1;
00158     const Vertex* v2=e->v2;
00159     
00160     os << v1->pose.x() << " " << v1->pose.y() << " " << v1->pose.theta() << endl;
00161     os << v2->pose.x() << " " << v2->pose.y() << " " << v2->pose.theta() << endl;
00162     os << endl;
00163   }
00164   return true;
00165 
00166 }
00167 
00168 bool TreePoseGraph2::save(const char* filename){
00169   ofstream os(filename);
00170   if (!os)
00171     return false;
00172   
00173   for (TreePoseGraph2::VertexMap::const_iterator it=vertices.begin(); it!=vertices.end(); it++){
00174     const TreePoseGraph2::Vertex* v=it->second;
00175     os << "VERTEX " 
00176        << v->id << " " 
00177        << v->pose.x() << " " 
00178        << v->pose.y() << " " 
00179        << v->pose.theta()<< endl; 
00180   }
00181   for (TreePoseGraph2::EdgeMap::const_iterator it=edges.begin(); it!=edges.end(); it++){
00182     const TreePoseGraph2::Edge * e=it->second;
00183     os << "EDGE " << e->v1->id << " " << e->v2->id << " ";
00184     Pose p=e->transformation.toPoseType();
00185     os << p.x() << " " << p.y() << " " << p.theta() << " ";
00186     os << e->informationMatrix.values[0][0] << " "
00187        << e->informationMatrix.values[0][1] << " "
00188        << e->informationMatrix.values[1][1] << " "
00189        << e->informationMatrix.values[2][2] << " "
00190        << e->informationMatrix.values[0][2] << " "
00191        << e->informationMatrix.values[1][2] << endl;
00192     }
00193   return true;
00194 }
00195 
00198 struct IdPrinter{
00199   IdPrinter(std::ostream& _os):os(_os){}
00200   std::ostream& os;
00201   void perform(TreePoseGraph2::Vertex* v){
00202     std::cout << "(" << v->id << "," << v->level << ")" << endl;
00203   }
00204 };
00205 
00206 void TreePoseGraph2::printDepth( std::ostream& os ){
00207   IdPrinter ip(os);
00208   treeDepthVisit(ip, root);
00209 }
00210 
00211 void TreePoseGraph2::printWidth( std::ostream& os ){
00212   IdPrinter ip(os);
00213   treeBreadthVisit(ip);
00214 }
00215 
00219 struct PosePropagator{
00220   void perform(TreePoseGraph2::Vertex* v){
00221     if (!v->parent)
00222       return;
00223     TreePoseGraph2::Transformation tParent(v->parent->pose);
00224     TreePoseGraph2::Transformation tNode=tParent*v->parentEdge->transformation;
00225 
00226     
00227     
00228     
00229     
00230     
00231     
00232     
00233 
00234     assert(v->parentEdge->v1==v->parent);
00235     assert(v->parentEdge->v2==v);
00236     v->pose=tNode.toPoseType();
00237   }
00238 };
00239 
00240 void TreePoseGraph2::initializeOnTree(){
00241   PosePropagator pp;
00242   treeDepthVisit(pp, root);
00243 }
00244 
00245 
00246 void TreePoseGraph2::printEdgesStat(std::ostream& os){
00247   for (TreePoseGraph2::EdgeMap::const_iterator it=edges.begin(); it!=edges.end(); it++){
00248     const TreePoseGraph2::Edge * e=it->second;
00249     os << "EDGE " << e->v1->id << " " << e->v2->id << " ";
00250     Pose p=e->transformation.toPoseType();
00251     os << p.x() << " " << p.y() << " " << p.theta() << " ";
00252     os << e->informationMatrix.values[0][0] << " "
00253        << e->informationMatrix.values[0][1] << " "
00254        << e->informationMatrix.values[1][1] << " "
00255        << e->informationMatrix.values[2][2] << " "
00256        << e->informationMatrix.values[0][2] << " "
00257        << e->informationMatrix.values[1][2] << endl;
00258     os << "   top=" << e->top->id << " length=" << e->length << endl;
00259   }
00260 }
00261 
00262 void TreePoseGraph2::revertEdgeInfo(Edge* e){
00263   Transformation it=e->transformation.inv();
00264   InformationMatrix R;
00265   R.values[0][0]=e->transformation.rotationMatrix[0][0];
00266   R.values[0][1]=e->transformation.rotationMatrix[0][1];
00267   R.values[0][2]=0;
00268 
00269   R.values[1][0]=e->transformation.rotationMatrix[1][0];
00270   R.values[1][1]=e->transformation.rotationMatrix[1][1];
00271   R.values[1][2]=0;
00272 
00273   R.values[2][0]=0;
00274   R.values[2][1]=0;
00275   R.values[2][2]=1;
00276 
00277   InformationMatrix IM=R.transpose()*e->informationMatrix*R;
00278 
00279 
00280   
00281  
00282   
00283 
00284   
00285   
00286 
00287   e->transformation=it;
00288   e->informationMatrix=IM;
00289 };
00290 
00291 void TreePoseGraph2::initializeFromParentEdge(Vertex* v){
00292   Transformation tp=Transformation(v->parent->pose)*v->parentEdge->transformation;
00293   v->transformation=tp;
00294   v->pose=tp.toPoseType();
00295   v->parameters=v->pose;
00296   v->parameters.x()-=v->parent->pose.x();
00297   v->parameters.y()-=v->parent->pose.y();
00298   v->parameters.theta()-=v->parent->pose.theta();
00299   v->parameters.theta()=atan2(sin(v->parameters.theta()), cos(v->parameters.theta()));
00300 }
00301 
00302 void TreePoseGraph2::collapseEdge(Edge* e){
00303   EdgeMap::iterator ie_it=edges.find(e);
00304   if (ie_it==edges.end())
00305     return;
00306   
00307   
00308   assert(vertices.find(e->v1->id)!=vertices.end());
00309   assert(vertices.find(e->v2->id)!=vertices.end());
00310 
00311   Vertex* v1=e->v1;
00312   Vertex* v2=e->v2;
00313   
00314   
00315   
00316   for (EdgeList::iterator it=v2->edges.begin(); it!=v2->edges.end(); it++){
00317     if ( (*it)->v1!=v2 )
00318       revertEdge(*it);
00319   }
00320 
00321  
00322   for (EdgeList::iterator it=v1->edges.begin(); it!=v1->edges.end(); it++){
00323     if ( (*it)->v1!=v1 )
00324       revertEdge(*it);
00325   }
00326 
00327   assert(e->v1==v1);
00328 
00329   InformationMatrix I12=e->informationMatrix;
00330   CovarianceMatrix  C12=I12.inv();
00331   Transformation    T12=e->transformation;
00332   
00333 
00334   
00335 
00336   
00337   for (EdgeList::iterator it2=v2->edges.begin(); it2!=v2->edges.end(); it2++){
00338     Edge* e2=*it2;
00339     if (e2->v1==v2){ 
00340       
00341       
00342       InformationMatrix I2x=e2->informationMatrix;
00343       CovarianceMatrix  C2x=I2x.inv();
00344       
00345       
00346       
00347       
00348       
00349       
00350       
00351       
00352       
00353       
00354       
00355       
00356       
00357       
00358       
00359       
00360       
00361 
00362       
00363       
00364       
00365       Transformation T1x_pred=T12*e2->transformation;
00366       Covariance C1x_pred=C12+C2x;
00367       InformationMatrix I1x_pred=C1x_pred.inv();
00368 
00369       e2->transformation=T1x_pred;
00370       e2->informationMatrix=I1x_pred;
00371     }
00372   }
00373 
00374   
00375   std::list<Transformation> tList;
00376   std::list<InformationMatrix> iList;
00377   std::list<Vertex*> vList;
00378 
00379   
00380   for (EdgeList::iterator it2=v2->edges.begin(); it2!=v2->edges.end(); it2++){
00381     Edge* e1x=0;
00382     Edge* e2x=0;
00383     if ( ((*it2)->v1!=v1)){
00384       e2x=*it2;
00385       for (EdgeList::iterator it1=v1->edges.begin(); it1!=v1->edges.end(); it1++){
00386         if ((*it1)->v2==(*it2)->v2)
00387           e1x=*it1;
00388       }
00389 
00390     }
00391     if (e1x && e2x){
00392       Transformation t1x=e1x->transformation;
00393       InformationMatrix I1x=e1x->informationMatrix;
00394       Pose p1x=t1x.toPoseType();
00395 
00396       Transformation t2x=e2x->transformation;
00397       InformationMatrix I2x=e2x->informationMatrix;;
00398       Pose p2x=t2x.toPoseType();
00399 
00400       InformationMatrix IM=I1x+I2x;
00401       CovarianceMatrix  CM=IM.inv();
00402       InformationMatrix scale1=CM*I1x;
00403       InformationMatrix scale2=CM*I2x;
00404 
00405 
00406       Pose p1=scale1*p1x;
00407       Pose p2=scale2*p2x;
00408 
00409 
00410       
00411       double s=scale1.values[2][2]*sin(p1x.theta())+ scale2.values[2][2]*sin(p2x.theta());
00412       double c=scale1.values[2][2]*cos(p1x.theta())+ scale2.values[2][2]*cos(p2x.theta());
00413       
00414       DEBUG(2) << "p1x= " << p1x.x() << " " << p1x.y() << " " << p1x.theta() << endl;
00415       DEBUG(2) << "p1x_pred= " << p2x.x() << " " << p2x.y() << " " << p2x.theta() << endl;
00416       
00417       Pose pFinal(p1.x()+p2.x(), p1.y()+p2.y(), atan2(s,c));
00418       DEBUG(2) << "p1x_final= " << pFinal.x() << " " << pFinal.y() << " " << pFinal.theta() << endl;
00419       
00420       e1x->transformation=Transformation(pFinal);
00421       e1x->informationMatrix=IM;
00422     }
00423     if (!e1x && e2x){
00424       tList.push_back(e2x->transformation);
00425       iList.push_back(e2x->informationMatrix);
00426       vList.push_back(e2x->v2);
00427     }
00428   }
00429   removeVertex(v2->id);
00430 
00431   std::list<Transformation>::iterator t=tList.begin();
00432   std::list<InformationMatrix>::iterator i=iList.begin();
00433   std::list<Vertex*>::iterator v=vList.begin();
00434   while (i!=iList.end()){
00435     addEdge(v1,*v,*t,*i);
00436     i++;
00437     t++;
00438     v++;
00439   }
00440 }
00441 
00442 };