#include <base_binary_edge.h>
Public Types | |
typedef BaseEdge< D, E > ::ErrorVector | ErrorVector |
typedef Map< Matrix< double, Dj, Di >, Matrix< double, Dj, Di >::Flags &AlignedBit?Aligned:Unaligned > | HessianBlockTransposedType |
typedef Map< Matrix< double, Di, Dj >, Matrix< double, Di, Dj >::Flags &AlignedBit?Aligned:Unaligned > | HessianBlockType |
typedef BaseEdge< D, E > ::InformationType | InformationType |
typedef Matrix< double, D, Di > | JacobianXiOplusType |
typedef Matrix< double, D, Dj > | JacobianXjOplusType |
typedef BaseEdge< D, E > ::Measurement | Measurement |
typedef VertexXi | VertexXiType |
typedef VertexXj | VertexXjType |
Public Member Functions | |
BaseBinaryEdge () | |
virtual void | constructQuadraticForm () |
virtual OptimizableGraph::Vertex * | createFrom () |
virtual OptimizableGraph::Vertex * | createTo () |
const JacobianXiOplusType & | jacobianOplusXi () const |
returns the result of the linearization in the manifold space for the node xi | |
const JacobianXjOplusType & | jacobianOplusXj () const |
returns the result of the linearization in the manifold space for the node xj | |
virtual void | linearizeOplus () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
Static Public Attributes | |
static const int | Di = VertexXiType::Dimension |
static const int | Dimension = BaseEdge<D, E>::Dimension |
static const int | Dj = VertexXjType::Dimension |
Protected Attributes | |
HessianBlockType | _hessian |
bool | _hessianRowMajor |
HessianBlockTransposedType | _hessianTransposed |
JacobianXiOplusType | _jacobianOplusXi |
JacobianXjOplusType | _jacobianOplusXj |
Definition at line 31 of file base_binary_edge.h.
typedef BaseEdge<D,E>::ErrorVector g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::ErrorVector |
Reimplemented from g2o::BaseEdge< D, E >.
Definition at line 45 of file base_binary_edge.h.
typedef Map<Matrix<double, Dj, Di>, Matrix<double, Dj, Di>::Flags & AlignedBit ? Aligned : Unaligned > g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::HessianBlockTransposedType |
Definition at line 49 of file base_binary_edge.h.
typedef Map<Matrix<double, Di, Dj>, Matrix<double, Di, Dj>::Flags & AlignedBit ? Aligned : Unaligned > g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::HessianBlockType |
Definition at line 48 of file base_binary_edge.h.
typedef BaseEdge<D,E>::InformationType g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::InformationType |
Reimplemented from g2o::BaseEdge< D, E >.
Definition at line 46 of file base_binary_edge.h.
typedef Matrix<double, D, Di> g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::JacobianXiOplusType |
Definition at line 43 of file base_binary_edge.h.
typedef Matrix<double, D, Dj> g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::JacobianXjOplusType |
Definition at line 44 of file base_binary_edge.h.
typedef BaseEdge<D,E>::Measurement g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::Measurement |
Reimplemented from g2o::BaseEdge< D, E >.
Definition at line 42 of file base_binary_edge.h.
typedef VertexXi g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::VertexXiType |
Definition at line 35 of file base_binary_edge.h.
typedef VertexXj g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::VertexXjType |
Definition at line 36 of file base_binary_edge.h.
g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::BaseBinaryEdge | ( | ) | [inline] |
Definition at line 51 of file base_binary_edge.h.
void BaseBinaryEdge::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 30 of file base_binary_edge.h.
OptimizableGraph::Vertex * BaseBinaryEdge::createFrom | ( | ) | [virtual] |
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 19 of file base_binary_edge.h.
OptimizableGraph::Vertex * BaseBinaryEdge::createTo | ( | ) | [virtual] |
Reimplemented from g2o::OptimizableGraph::Edge.
Definition at line 24 of file base_binary_edge.h.
const JacobianXiOplusType& g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::jacobianOplusXi | ( | ) | const [inline] |
returns the result of the linearization in the manifold space for the node xi
Definition at line 69 of file base_binary_edge.h.
const JacobianXjOplusType& g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::jacobianOplusXj | ( | ) | const [inline] |
returns the result of the linearization in the manifold space for the node xj
Definition at line 71 of file base_binary_edge.h.
void BaseBinaryEdge::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::EdgeProjectP2SC, g2o::Edge_V_V_GICP, g2o::EdgeProjectXYZ2UVQ, g2o::EdgeProjectP2MC, g2o::EdgeProjectXYZ2UV, g2o::EdgeSE3Expmap, g2o::EdgeSE3, g2o::EdgeSE2, and g2o::EdgeSE2PointXY.
Definition at line 73 of file base_binary_edge.h.
void BaseBinaryEdge::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 150 of file base_binary_edge.h.
HessianBlockType g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::_hessian [protected] |
Definition at line 89 of file base_binary_edge.h.
bool g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::_hessianRowMajor [protected] |
Definition at line 88 of file base_binary_edge.h.
HessianBlockTransposedType g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::_hessianTransposed [protected] |
Definition at line 90 of file base_binary_edge.h.
JacobianXiOplusType g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::_jacobianOplusXi [protected] |
Definition at line 91 of file base_binary_edge.h.
JacobianXjOplusType g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::_jacobianOplusXj [protected] |
Definition at line 92 of file base_binary_edge.h.
const int g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::Di = VertexXiType::Dimension [static] |
Definition at line 38 of file base_binary_edge.h.
const int g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::Dimension = BaseEdge<D, E>::Dimension [static] |
Reimplemented from g2o::BaseEdge< D, E >.
Definition at line 41 of file base_binary_edge.h.
const int g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >::Dj = VertexXjType::Dimension [static] |
Definition at line 39 of file base_binary_edge.h.