base_binary_edge.h
Go to the documentation of this file.
00001 // g2o - General Graph Optimization
00002 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, H. Strasdat, 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 BASE_BINARY_EDGE_H
00018 #define BASE_BINARY_EDGE_H
00019 
00020 #include <iostream>
00021 #include <limits>
00022 
00023 #include "base_edge.h"
00024 #include "g2o/config.h"
00025 
00026 namespace g2o {
00027 
00028   using namespace Eigen;
00029 
00030   template <int D, typename E, typename VertexXi, typename VertexXj>
00031   class BaseBinaryEdge : public BaseEdge<D, E>
00032   {
00033     public:
00034 
00035       typedef VertexXi VertexXiType;
00036       typedef VertexXj VertexXjType;
00037 
00038       static const int Di = VertexXiType::Dimension;
00039       static const int Dj = VertexXjType::Dimension;
00040 
00041       static const int Dimension = BaseEdge<D, E>::Dimension;
00042       typedef typename BaseEdge<D,E>::Measurement Measurement;
00043       typedef Matrix<double, D, Di> JacobianXiOplusType;
00044       typedef Matrix<double, D, Dj> JacobianXjOplusType;
00045       typedef typename BaseEdge<D,E>::ErrorVector ErrorVector;
00046       typedef typename BaseEdge<D,E>::InformationType InformationType;
00047 
00048       typedef Map<Matrix<double, Di, Dj>, Matrix<double, Di, Dj>::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockType;
00049       typedef Map<Matrix<double, Dj, Di>, Matrix<double, Dj, Di>::Flags & AlignedBit ? Aligned : Unaligned > HessianBlockTransposedType;
00050 
00051       BaseBinaryEdge() : BaseEdge<D,E>(),
00052       _hessianRowMajor(false),
00053       _hessian(0, VertexXiType::Dimension, VertexXjType::Dimension), // HACK we map to the null pointer for initializing the Maps
00054       _hessianTransposed(0, VertexXjType::Dimension, VertexXiType::Dimension)
00055       {
00056         resize(2);
00057       }
00058 
00059       virtual OptimizableGraph::Vertex* createFrom();
00060       virtual OptimizableGraph::Vertex* createTo();
00061 
00066       virtual void linearizeOplus();
00067 
00069       const JacobianXiOplusType& jacobianOplusXi() const { return _jacobianOplusXi;}
00071       const JacobianXjOplusType& jacobianOplusXj() const { return _jacobianOplusXj;}
00072 
00073       virtual void constructQuadraticForm() ;
00074 
00075       virtual void mapHessianMemory(double* d, int i, int j, bool rowMajor);
00076 
00077       using BaseEdge<D,E>::resize;
00078       using BaseEdge<D,E>::computeError;
00079 
00080     protected:
00081       using BaseEdge<D,E>::_measurement;
00082       using BaseEdge<D,E>::_inverseMeasurement;
00083       using BaseEdge<D,E>::_information;
00084       using BaseEdge<D,E>::_error;
00085       using BaseEdge<D,E>::_vertices;
00086       using BaseEdge<D,E>::_dimension;
00087 
00088       bool _hessianRowMajor;
00089       HessianBlockType _hessian;
00090       HessianBlockTransposedType _hessianTransposed;
00091       JacobianXiOplusType _jacobianOplusXi;
00092       JacobianXjOplusType _jacobianOplusXj;
00093 
00094     public:
00095       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00096   };
00097 
00098 #include "base_binary_edge.hpp"
00099 
00100 } // end namespace g2o
00101 
00102 #endif


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