base_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_EDGE_H
00018 #define BASE_EDGE_H
00019 
00020 #include <iostream>
00021 #include <limits>
00022 
00023 #include "optimizable_graph.h"
00024 
00025 namespace g2o {
00026 
00027   using namespace Eigen;
00028 
00029   template <int D, typename E>
00030   class BaseEdge : public OptimizableGraph::Edge
00031   {
00032     public:
00033 
00034       static const int Dimension = D;
00035       typedef E Measurement;
00036       typedef Matrix<double, D, 1> ErrorVector;
00037       typedef Matrix<double, D, D> InformationType;
00038 
00039       BaseEdge() : OptimizableGraph::Edge()
00040       {
00041         _dimension = D;
00042       }
00043 
00044       virtual ~BaseEdge() {}
00045 
00046       virtual double chi2() const 
00047       {
00048         return _error.dot(information()*_error);
00049       }
00050 
00051       virtual void robustifyError()
00052       {
00053         double nrm = sqrt(_error.dot(information()*_error));
00054         double w = sqrtOfHuberByNrm(nrm,_huberWidth);
00055         _error *= w;
00056       }
00057 
00058       virtual const double* errorData() const { return _error.data();}
00059       virtual double* errorData() { return _error.data();}
00060       const ErrorVector& error() const { return _error;}
00061       ErrorVector& error() { return _error;}
00062 
00064       const InformationType& information() const { return _information;}
00065       InformationType& information() { return _information;}
00066       void setInformation(const InformationType& information) { _information = information;}
00067 
00068       virtual const double* informationData() const { return _information.data();}
00069       virtual double* informationData() { return _information.data();}
00070 
00072       const Measurement& measurement() const { return _measurement;}
00073       Measurement& measurement() { return _measurement;}
00074       virtual void setMeasurement(const Measurement& m) { _measurement = m;}
00075 
00076       virtual int rank() const {return _dimension;}
00077 
00082       const Measurement& inverseMeasurement() const { return _inverseMeasurement;}
00083       Measurement& inverseMeasurement() { return _inverseMeasurement;}
00084       virtual void setInverseMeasurement(const Measurement& im) { _inverseMeasurement = im;}
00085 
00086       virtual void initialEstimate(const OptimizableGraph::VertexSet& from, OptimizableGraph::Vertex* to)
00087       {
00088         (void) from; (void) to;
00089         std::cerr << __PRETTY_FUNCTION__ << " is not implemented, please give implementation in your derived class" << std::endl;
00090       }
00091 
00092     protected:
00093 
00094       Measurement _measurement;
00095       Measurement _inverseMeasurement;
00096       InformationType _information;
00097       ErrorVector _error;
00098 
00099     public:
00100       EIGEN_MAKE_ALIGNED_OPERATOR_NEW
00101   };
00102 
00103 } // end namespace g2o
00104 
00105 #endif


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