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>

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) | |
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.
| 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.
| typedef Map<MatrixXd, MatrixXd::Flags & AlignedBit ? Aligned : Unaligned > g2o::BaseMultiEdge< D, E >::HessianBlockType |
Definition at line 59 of file base_multi_edge.h.
| 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.
| typedef MatrixXd g2o::BaseMultiEdge< D, E >::JacobianType |
Definition at line 55 of file base_multi_edge.h.
| 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.
| g2o::BaseMultiEdge< D, E >::BaseMultiEdge | ( | ) | [inline] |
Definition at line 61 of file base_multi_edge.h.
| 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.
| 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.
| 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
| d | the memory location to which we map |
| i | index of the vertex i |
| j | index of the vertex j (j > i, upper triangular fashion) |
| rowMajor | if 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.
| 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.
std::vector<HessianHelper> g2o::BaseMultiEdge< D, E >::_hessian [protected] |
Definition at line 85 of file base_multi_edge.h.
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.
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.