edge_se2_pointxy_bearing.h
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 #ifndef EDGE_SE2_POINT_XY_BEARING_H
00018 #define EDGE_SE2_POINT_XY_BEARING_H
00019 
00020 #include "g2o/config.h"
00021 #include "vertex_se2.h"
00022 #include "vertex_point_xy.h"
00023 #include "g2o/core/base_binary_edge.h"
00024 
00025 namespace g2o {
00026 
00027   class  EdgeSE2PointXYBearing: public BaseBinaryEdge<1, double, VertexSE2, VertexPointXY>
00028   {
00029     public:
00030       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00031       EdgeSE2PointXYBearing();
00032       void computeError()
00033       {
00034         const VertexSE2* v1 = static_cast<const VertexSE2*>(_vertices[0]);
00035         const VertexPointXY* l2 = static_cast<const VertexPointXY*>(_vertices[1]);
00036         Vector2d delta = (v1->estimate().inverse() * l2->estimate());
00037         double angle = atan2(delta[1], delta[0]);
00038         _error[0] = normalize_theta(_measurement - angle );
00039       }
00040 
00041       virtual bool setMeasurementData(const double* d) {
00042         _measurement=d[0];
00043         _inverseMeasurement = -_measurement;
00044         return true;
00045       }
00046 
00047       virtual bool getMeasurementData(double* d) const {
00048         d[0] = _measurement;
00049         return true;
00050       }
00051 
00052       int measurementDimension() const {return 1;}
00053 
00054       virtual bool setMeasurementFromState(){
00055         const VertexSE2* v1 = static_cast<const VertexSE2*>(_vertices[0]);
00056         const VertexPointXY* l2 = static_cast<const VertexPointXY*>(_vertices[1]);
00057         Vector2d delta = (v1->estimate().inverse() * l2->estimate());
00058         _measurement = atan2(delta[1], delta[0]);
00059         _inverseMeasurement = - _measurement;
00060         return true;
00061       }
00062       
00063       virtual bool read(std::istream& is);
00064       virtual bool write(std::ostream& os) const;
00065 
00066       virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to) { (void) to; return (from.count(_vertices[0]) == 1 ? 1.0 : -1.0);}
00067       virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to);
00068   };
00069 
00070   class EdgeSE2PointXYBearingWriteGnuplotAction: public WriteGnuplotAction {
00071   public:
00072     EdgeSE2PointXYBearingWriteGnuplotAction();
00073     virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, 
00074                                                 HyperGraphElementAction::Parameters* params_);
00075   };
00076 
00077 #ifdef G2O_HAVE_OPENGL
00078   class EdgeSE2PointXYBearingDrawAction: public DrawAction{
00079   public:
00080     EdgeSE2PointXYBearingDrawAction();
00081     virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, 
00082                                                 HyperGraphElementAction::Parameters* params_);
00083   };
00084 #endif
00085 
00086 }
00087 
00088 #endif


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