edge_se3_quat.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_SE3_QUAT_
00018 #define _EDGE_SE3_QUAT_
00019 
00020 #include "g2o/config.h"
00021 #include "g2o/core/base_vertex.h"
00022 #include "g2o/core/base_binary_edge.h"
00023 #include "g2o/core/hyper_graph_action.h"
00024 #include "g2o/math_groups/se3quat.h"
00025 
00026 #define EDGE_SE3_QUAT_ANALYTIC_JACOBIAN
00027 
00028 #include "vertex_se3_quat.h"
00029 
00030 namespace g2o {
00031 
00032   using namespace Eigen;
00033 
00034 
00038  class EdgeSE3 : public BaseBinaryEdge<6, SE3Quat, VertexSE3, VertexSE3>
00039 {
00040   public:
00041     EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00042     EdgeSE3();
00043     void computeError()
00044     {
00045       const VertexSE3* v1 = dynamic_cast<const VertexSE3*>(_vertices[0]);
00046       const VertexSE3* v2 = dynamic_cast<const VertexSE3*>(_vertices[1]);
00047       SE3Quat delta = _inverseMeasurement * (v1->estimate().inverse()*v2->estimate());
00048       _error.head<3>() = delta.translation();
00049       // The analytic Jacobians assume the error in this special form (w beeing positive)
00050       if (delta.rotation().w() < 0.)
00051         _error.tail<3>() =  - delta.rotation().vec();
00052       else
00053         _error.tail<3>() =  delta.rotation().vec();
00054     }
00055 
00056     virtual void setMeasurement(const SE3Quat& m){
00057       _measurement = m;
00058       _inverseMeasurement = m.inverse();
00059     }
00060 
00061     virtual bool setMeasurementData(const double* d){
00062       Vector7d v;
00063       v.setZero();
00064       for (int i=0; i<6; i++)
00065         v[i]=d[i];
00066       _measurement.fromVector(v);
00067       _inverseMeasurement = _measurement.inverse();
00068       return true;
00069     }
00070 
00071     virtual bool getMeasurementData(double* d) const{
00072       Vector7d v=_measurement.toVector();
00073       for (int i=0; i<7; i++)
00074         d[i]=v[i];
00075       return true;
00076     }
00077     
00078     virtual int measurementDimension() const {return 7;}
00079 
00080     virtual bool setMeasurementFromState() ;
00081 
00082     virtual bool read(std::istream& is);
00083     virtual bool write(std::ostream& os) const;
00084 
00085     virtual double initialEstimatePossible(const OptimizableGraph::VertexSet& , OptimizableGraph::Vertex* ) { return 1.;}
00086     virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to);
00087 
00088 #ifdef EDGE_SE3_QUAT_ANALYTIC_JACOBIAN
00089     virtual void linearizeOplus();
00090 #endif
00091 };
00092 
00093   class EdgeSE3WriteGnuplotAction: public WriteGnuplotAction {
00094   public:
00095     EdgeSE3WriteGnuplotAction();
00096     virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, 
00097                                                 HyperGraphElementAction::Parameters* params_);
00098   };
00099 
00100 #ifdef G2O_HAVE_OPENGL
00101   class EdgeSE3DrawAction: public DrawAction{
00102   public:
00103     EdgeSE3DrawAction();
00104     virtual HyperGraphElementAction* operator()(HyperGraph::HyperGraphElement* element, 
00105                                                 HyperGraphElementAction::Parameters* params_);
00106   };
00107 #endif
00108 
00109 } // end namespace
00110 
00111 #endif


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