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

#include <base_unary_edge.h>

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

List of all members.

Public Types

typedef BaseEdge< D, E >
::ErrorVector 
ErrorVector
typedef BaseEdge< D, E >
::InformationType 
InformationType
typedef Matrix< double, D,
VertexXiType::Dimension > 
JacobianXiOplusType
typedef BaseEdge< D, E >
::Measurement 
Measurement
typedef VertexXi VertexXiType

Public Member Functions

 BaseUnaryEdge ()
virtual void constructQuadraticForm ()
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)
const JacobianXiOplusTypejacobianOplusXi () const
 returns the result of the linearization in the manifold space for the node xi
virtual void linearizeOplus ()
virtual void mapHessianMemory (double *, int, int, bool)

Static Public Attributes

static const int Dimension = BaseEdge<D, E>::Dimension

Protected Attributes

JacobianXiOplusType _jacobianOplusXi

Detailed Description

template<int D, typename E, typename VertexXi>
class g2o::BaseUnaryEdge< D, E, VertexXi >

Definition at line 32 of file base_unary_edge.h.


Member Typedef Documentation

template<int D, typename E, typename VertexXi>
typedef BaseEdge<D,E>::ErrorVector g2o::BaseUnaryEdge< D, E, VertexXi >::ErrorVector

Reimplemented from g2o::BaseEdge< D, E >.

Definition at line 39 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
typedef BaseEdge<D,E>::InformationType g2o::BaseUnaryEdge< D, E, VertexXi >::InformationType

Reimplemented from g2o::BaseEdge< D, E >.

Definition at line 40 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
typedef Matrix<double, D, VertexXiType::Dimension> g2o::BaseUnaryEdge< D, E, VertexXi >::JacobianXiOplusType

Definition at line 38 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
typedef BaseEdge<D,E>::Measurement g2o::BaseUnaryEdge< D, E, VertexXi >::Measurement

Reimplemented from g2o::BaseEdge< D, E >.

Definition at line 36 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
typedef VertexXi g2o::BaseUnaryEdge< D, E, VertexXi >::VertexXiType

Definition at line 37 of file base_unary_edge.h.


Constructor & Destructor Documentation

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

Definition at line 42 of file base_unary_edge.h.


Member Function Documentation

template<int D, typename E , typename VertexXiType >
void BaseUnaryEdge::constructQuadraticForm ( ) [virtual]

Linearizes the constraint in the edge. Makes side effect on the vertices of the graph by changing the parameter vector b and the hessian blocks ii and jj. The off diagoinal block is accesed via _hessian.

Implements g2o::OptimizableGraph::Edge.

Definition at line 19 of file base_unary_edge.h.

template<int D, typename E , typename VertexXiType >
void BaseUnaryEdge::initialEstimate ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
) [virtual]

set the estimate of the to vertex, based on the estimate of the from vertices in the edge.

Reimplemented from g2o::BaseEdge< D, E >.

Reimplemented in g2o::EdgeSE2Prior.

Definition at line 85 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
const JacobianXiOplusType& g2o::BaseUnaryEdge< D, E, VertexXi >::jacobianOplusXi ( ) const [inline]

returns the result of the linearization in the manifold space for the node xi

Definition at line 54 of file base_unary_edge.h.

template<int D, typename E , typename VertexXiType >
void BaseUnaryEdge::linearizeOplus ( ) [virtual]

Linearizes the oplus operator in the vertex, and stores the result in temporary variables _jacobianOplusXi and _jacobianOplusXj

Implements g2o::OptimizableGraph::Edge.

Definition at line 41 of file base_unary_edge.h.

template<int D, typename E, typename VertexXi>
virtual void g2o::BaseUnaryEdge< D, E, VertexXi >::mapHessianMemory ( double *  d,
int  i,
int  j,
bool  rowMajor 
) [inline, virtual]

maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm

Parameters:
dthe memory location to which we map
iindex of the vertex i
jindex of the vertex j (j > i, upper triangular fashion)
rowMajorif true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed

Implements g2o::OptimizableGraph::Edge.

Definition at line 60 of file base_unary_edge.h.


Member Data Documentation

template<int D, typename E, typename VertexXi>
JacobianXiOplusType g2o::BaseUnaryEdge< D, E, VertexXi >::_jacobianOplusXi [protected]

Definition at line 73 of file base_unary_edge.h.

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

Reimplemented from g2o::BaseEdge< D, E >.

Definition at line 35 of file base_unary_edge.h.


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


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