Public Types | Public Member Functions | Static Public Attributes | Protected Attributes
g2o::BaseEdge< D, E > Class Template Reference

#include <base_edge.h>

Inheritance diagram for g2o::BaseEdge< D, E >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef Matrix< double, D, 1 > ErrorVector
typedef Matrix< double, D, DInformationType
typedef E Measurement

Public Member Functions

 BaseEdge ()
virtual double chi2 () const
 computes the chi2 based on the cached error value, only valid after computeError has been called.
const ErrorVectorerror () const
ErrorVectorerror ()
virtual const double * errorData () const
 returns the error vector cached after calling the computeError;
virtual double * errorData ()
const InformationTypeinformation () const
 information matrix of the constraint
InformationTypeinformation ()
virtual const double * informationData () const
 returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>
virtual double * informationData ()
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
const MeasurementinverseMeasurement () const
MeasurementinverseMeasurement ()
const Measurementmeasurement () const
 accessor functions for the measurement represented by the edge
Measurementmeasurement ()
virtual int rank () const
virtual void robustifyError ()
void setInformation (const InformationType &information)
virtual void setInverseMeasurement (const Measurement &im)
virtual void setMeasurement (const Measurement &m)
virtual ~BaseEdge ()

Static Public Attributes

static const int Dimension = D

Protected Attributes

ErrorVector _error
InformationType _information
Measurement _inverseMeasurement
Measurement _measurement

Detailed Description

template<int D, typename E>
class g2o::BaseEdge< D, E >

Definition at line 30 of file base_edge.h.


Member Typedef Documentation

template<int D, typename E>
typedef Matrix<double, D, 1> g2o::BaseEdge< D, E >::ErrorVector
template<int D, typename E>
typedef Matrix<double, D, D> g2o::BaseEdge< D, E >::InformationType
template<int D, typename E>
typedef E g2o::BaseEdge< D, E >::Measurement

Constructor & Destructor Documentation

template<int D, typename E>
g2o::BaseEdge< D, E >::BaseEdge ( ) [inline]

Definition at line 39 of file base_edge.h.

template<int D, typename E>
virtual g2o::BaseEdge< D, E >::~BaseEdge ( ) [inline, virtual]

Definition at line 44 of file base_edge.h.


Member Function Documentation

template<int D, typename E>
virtual double g2o::BaseEdge< D, E >::chi2 ( ) const [inline, virtual]

computes the chi2 based on the cached error value, only valid after computeError has been called.

Implements g2o::OptimizableGraph::Edge.

Definition at line 46 of file base_edge.h.

template<int D, typename E>
const ErrorVector& g2o::BaseEdge< D, E >::error ( ) const [inline]

Definition at line 60 of file base_edge.h.

template<int D, typename E>
ErrorVector& g2o::BaseEdge< D, E >::error ( ) [inline]

Definition at line 61 of file base_edge.h.

template<int D, typename E>
virtual const double* g2o::BaseEdge< D, E >::errorData ( ) const [inline, virtual]

returns the error vector cached after calling the computeError;

Implements g2o::OptimizableGraph::Edge.

Definition at line 58 of file base_edge.h.

template<int D, typename E>
virtual double* g2o::BaseEdge< D, E >::errorData ( ) [inline, virtual]

Implements g2o::OptimizableGraph::Edge.

Definition at line 59 of file base_edge.h.

template<int D, typename E>
const InformationType& g2o::BaseEdge< D, E >::information ( ) const [inline]

information matrix of the constraint

Definition at line 64 of file base_edge.h.

template<int D, typename E>
InformationType& g2o::BaseEdge< D, E >::information ( ) [inline]

Definition at line 65 of file base_edge.h.

template<int D, typename E>
virtual const double* g2o::BaseEdge< D, E >::informationData ( ) const [inline, virtual]

returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>

Implements g2o::OptimizableGraph::Edge.

Definition at line 68 of file base_edge.h.

template<int D, typename E>
virtual double* g2o::BaseEdge< D, E >::informationData ( ) [inline, virtual]

Implements g2o::OptimizableGraph::Edge.

Definition at line 69 of file base_edge.h.

template<int D, typename E>
virtual void g2o::BaseEdge< D, E >::initialEstimate ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
) [inline, virtual]
template<int D, typename E>
const Measurement& g2o::BaseEdge< D, E >::inverseMeasurement ( ) const [inline]

accessor functions for the inverse measurement, you may use this to cache the inverse measurement in case you need it to compute, for example, the error vector.

Definition at line 82 of file base_edge.h.

template<int D, typename E>
Measurement& g2o::BaseEdge< D, E >::inverseMeasurement ( ) [inline]

Definition at line 83 of file base_edge.h.

template<int D, typename E>
const Measurement& g2o::BaseEdge< D, E >::measurement ( ) const [inline]

accessor functions for the measurement represented by the edge

Definition at line 72 of file base_edge.h.

template<int D, typename E>
Measurement& g2o::BaseEdge< D, E >::measurement ( ) [inline]

Definition at line 73 of file base_edge.h.

template<int D, typename E>
virtual int g2o::BaseEdge< D, E >::rank ( ) const [inline, virtual]

Definition at line 76 of file base_edge.h.

template<int D, typename E>
virtual void g2o::BaseEdge< D, E >::robustifyError ( ) [inline, virtual]

robustify the error of the edge using an robust kernel/M-estimator this is only called if robustKernel==true

Implements g2o::OptimizableGraph::Edge.

Definition at line 51 of file base_edge.h.

template<int D, typename E>
void g2o::BaseEdge< D, E >::setInformation ( const InformationType information) [inline]

Definition at line 66 of file base_edge.h.

template<int D, typename E>
virtual void g2o::BaseEdge< D, E >::setInverseMeasurement ( const Measurement im) [inline, virtual]

Definition at line 84 of file base_edge.h.

template<int D, typename E>
virtual void g2o::BaseEdge< D, E >::setMeasurement ( const Measurement m) [inline, virtual]

Reimplemented in g2o::EdgeSE3, and g2o::EdgeSE2.

Definition at line 74 of file base_edge.h.


Member Data Documentation

template<int D, typename E>
ErrorVector g2o::BaseEdge< D, E >::_error [protected]

Definition at line 97 of file base_edge.h.

template<int D, typename E>
InformationType g2o::BaseEdge< D, E >::_information [protected]

Definition at line 96 of file base_edge.h.

template<int D, typename E>
Measurement g2o::BaseEdge< D, E >::_inverseMeasurement [protected]

Definition at line 95 of file base_edge.h.

template<int D, typename E>
Measurement g2o::BaseEdge< D, E >::_measurement [protected]

Definition at line 94 of file base_edge.h.

template<int D, typename E>
const int g2o::BaseEdge< D, E >::Dimension = D [static]

The documentation for this class was generated from the following file:


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