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

base class to represent an edge connecting an arbitrary number of nodes D - Dimension of the measurement E - type to represent the measurement More...

#include <base_multi_edge.h>

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

List of all members.

Classes

struct  HessianHelper
 helper for mapping the Hessian memory of the upper triangular block More...

Public Types

typedef BaseEdge< D, E >
::ErrorVector 
ErrorVector
typedef Map< MatrixXd,
MatrixXd::Flags &AlignedBit?Aligned:Unaligned > 
HessianBlockType
typedef BaseEdge< D, E >
::InformationType 
InformationType
typedef MatrixXd JacobianType
typedef BaseEdge< D, E >
::Measurement 
Measurement

Public Member Functions

 BaseMultiEdge ()
virtual void constructQuadraticForm ()
virtual void linearizeOplus ()
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)
virtual void resize (size_t size)

Static Public Attributes

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

Protected Attributes

std::vector< HessianHelper_hessian
std::vector< JacobianType_jacobianOplus
 jacobians of the edge (w.r.t. oplus)

Detailed Description

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

base class to represent an edge connecting an arbitrary number of nodes D - Dimension of the measurement E - type to represent the measurement

Definition at line 38 of file base_multi_edge.h.


Member Typedef Documentation

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

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

Definition at line 56 of file base_multi_edge.h.

template<int D, typename E>
typedef Map<MatrixXd, MatrixXd::Flags & AlignedBit ? Aligned : Unaligned > g2o::BaseMultiEdge< D, E >::HessianBlockType

Definition at line 59 of file base_multi_edge.h.

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

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

Definition at line 57 of file base_multi_edge.h.

template<int D, typename E>
typedef MatrixXd g2o::BaseMultiEdge< D, E >::JacobianType

Definition at line 55 of file base_multi_edge.h.

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

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

Definition at line 54 of file base_multi_edge.h.


Constructor & Destructor Documentation

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

Definition at line 61 of file base_multi_edge.h.


Member Function Documentation

template<int D, typename E >
void BaseMultiEdge::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 39 of file base_multi_edge.h.

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

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

Implements g2o::OptimizableGraph::Edge.

Reimplemented in g2o::EdgeProjectP2MC_Intrinsics, and g2o::EdgeProjectXYZ2UV.

Definition at line 120 of file base_multi_edge.h.

template<int D, typename E >
void BaseMultiEdge::mapHessianMemory ( double *  d,
int  i,
int  j,
bool  rowMajor 
) [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 196 of file base_multi_edge.h.

template<int D, typename E >
void BaseMultiEdge::resize ( size_t  size) [virtual]

resizes the number of vertices connected by this edge

Reimplemented from g2o::HyperGraph::Edge.

Definition at line 223 of file base_multi_edge.h.


Member Data Documentation

template<int D, typename E>
std::vector<HessianHelper> g2o::BaseMultiEdge< D, E >::_hessian [protected]

Definition at line 85 of file base_multi_edge.h.

template<int D, typename E>
std::vector<JacobianType> g2o::BaseMultiEdge< D, E >::_jacobianOplus [protected]

jacobians of the edge (w.r.t. oplus)

Definition at line 87 of file base_multi_edge.h.

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

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

Definition at line 53 of file base_multi_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