edge_se2_pointxy_bearing.cpp
Go to the documentation of this file.
00001 // g2o - General Graph Optimization
00002 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
00003 // 
00004 // g2o is free software: you can redistribute it and/or modify
00005 // it under the terms of the GNU Lesser General Public License as published
00006 // by the Free Software Foundation, either version 3 of the License, or
00007 // (at your option) any later version.
00008 // 
00009 // g2o is distributed in the hope that it will be useful,
00010 // but WITHOUT ANY WARRANTY; without even the implied warranty of
00011 // MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE.  See the
00012 // GNU Lesser General Public License for more details.
00013 // 
00014 // You should have received a copy of the GNU Lesser General Public License
00015 // along with this program.  If not, see <http://www.gnu.org/licenses/>.
00016 
00017 #include "edge_se2_pointxy_bearing.h"
00018 
00019 #ifdef WINDOWS
00020 #include <windows.h>
00021 #endif
00022 
00023 #ifdef G2O_HAVE_OPENGL
00024 #ifdef __APPLE__
00025 #include <OpenGL/gl.h>
00026 #else
00027 #include <GL/gl.h>
00028 #endif
00029 #endif
00030 
00031 namespace g2o {
00032 
00033   EdgeSE2PointXYBearing::EdgeSE2PointXYBearing()
00034   {
00035   }
00036 
00037 
00038   void EdgeSE2PointXYBearing::initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* /*to*/)
00039   {
00040     assert(from.size() == 1 && from.count(_vertices[0]) == 1 && "Can not initialize VertexSE2 position by VertexPointXY");
00041 
00042     if (from.count(_vertices[0]) != 1)
00043       return;
00044     double r=2.;
00045     const VertexSE2* v1 = static_cast<const VertexSE2*>(_vertices[0]);
00046     VertexPointXY* l2 = static_cast<VertexPointXY*>(_vertices[1]);
00047     SE2 t=v1->estimate();
00048     t.rotation().angle()+=_measurement;
00049     Vector2d vr;
00050     vr[0]=r; vr[1]=0;
00051     l2->estimate()=t*vr;
00052   }
00053 
00054   bool EdgeSE2PointXYBearing::read(std::istream& is)
00055   {
00056     is >> measurement() >> information()(0,0);
00057     inverseMeasurement() = -measurement();
00058     return true;
00059   }
00060 
00061   bool EdgeSE2PointXYBearing::write(std::ostream& os) const
00062   {
00063     os << measurement() << " " << information()(0,0);
00064     return os.good();
00065   }
00066 
00067 
00068   EdgeSE2PointXYBearingWriteGnuplotAction::EdgeSE2PointXYBearingWriteGnuplotAction(): WriteGnuplotAction(typeid(EdgeSE2PointXYBearing).name()){}
00069 
00070   HyperGraphElementAction* EdgeSE2PointXYBearingWriteGnuplotAction::operator()(HyperGraph::HyperGraphElement* element,
00071                                                                                HyperGraphElementAction::Parameters* params_){
00072     if (typeid(*element).name()!=_typeName)
00073       return 0;
00074     WriteGnuplotAction::Parameters* params=static_cast<WriteGnuplotAction::Parameters*>(params_);
00075     if (!params->os){
00076       std::cerr << __PRETTY_FUNCTION__ << ": warning, on valid os specified" << std::endl;
00077       return 0;
00078     }
00079 
00080     EdgeSE2PointXYBearing* e =  static_cast<EdgeSE2PointXYBearing*>(element);
00081     VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertices()[0]);
00082     VertexPointXY* toEdge   = static_cast<VertexPointXY*>(e->vertices()[1]);
00083     *(params->os) << fromEdge->estimate().translation().x() << " " << fromEdge->estimate().translation().y()
00084       << " " << fromEdge->estimate().rotation().angle() << std::endl;
00085     *(params->os) << toEdge->estimate().x() << " " << toEdge->estimate().y() << std::endl;
00086     *(params->os) << std::endl;
00087     return this;
00088   }
00089 
00090 #ifdef G2O_HAVE_OPENGL
00091   EdgeSE2PointXYBearingDrawAction::EdgeSE2PointXYBearingDrawAction(): DrawAction(typeid(EdgeSE2PointXYBearing).name()){}
00092 
00093   HyperGraphElementAction* EdgeSE2PointXYBearingDrawAction::operator()(HyperGraph::HyperGraphElement* element,  HyperGraphElementAction::Parameters* /*params_*/){
00094     if (typeid(*element).name()!=_typeName)
00095       return 0;
00096     EdgeSE2PointXYBearing* e =  static_cast<EdgeSE2PointXYBearing*>(element);
00097     VertexSE2* fromEdge = static_cast<VertexSE2*>(e->vertices()[0]);
00098     VertexPointXY* toEdge   = static_cast<VertexPointXY*>(e->vertices()[1]);
00099     glColor3f(0.3,0.3,0.1);
00100     glBegin(GL_LINES);
00101     glVertex3f(fromEdge->estimate().translation().x(),fromEdge->estimate().translation().y(),0.);
00102     glVertex3f(toEdge->estimate().x(),toEdge->estimate().y(),0.);
00103     glEnd();
00104     return this;
00105   }
00106 #endif
00107 
00108 } // end namespace


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:31:02