NDEVR
API Documentation
BaseBinaryEdge< D, E, VertexXi, VertexXj >

Base class for edges connecting exactly two vertices in the graph. More...

Inheritance diagram for BaseBinaryEdge< D, E, VertexXi, VertexXj >:
[legend]
Collaboration diagram for BaseBinaryEdge< D, E, VertexXi, VertexXj >:
[legend]

Public Types

typedef BaseEdge< D, E >::ErrorVector ErrorVector
 The error vector type.
typedef Eigen::Map< Eigen::Matrix< g_type, Dj, Di >, Eigen::Matrix< g_type, Di, Dj >::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned > HessianBlockTransposedType
 Mapped transposed Hessian block type.
typedef Eigen::Map< Eigen::Matrix< g_type, Di, Dj >, Eigen::Matrix< g_type, Di, Dj >::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned > HessianBlockType
 Mapped Hessian block type.
typedef BaseEdge< D, E >::InformationType InformationType
 The information matrix type.
typedef Eigen::Matrix< g_type, D, Di >::AlignedMapType JacobianXiOplusType
 Jacobian type w.r.t. vertex Xi.
typedef Eigen::Matrix< g_type, D, Dj >::AlignedMapType JacobianXjOplusType
 Jacobian type w.r.t. vertex Xj.
typedef BaseEdge< D, E >::Measurement Measurement
 The measurement type.
typedef VertexXi VertexXiType
 Type of the first (source) vertex.
typedef VertexXj VertexXjType
 Type of the second (target) vertex.
Public Types inherited from BaseEdge< D, E >
typedef Eigen::Matrix< g_type, t_dims, 1 > ErrorVector
 Fixed-size error vector type.
typedef Eigen::Matrix< g_type, t_dims, t_dims > InformationType
 Fixed-size information (inverse covariance) matrix type.
typedef E Measurement
 The measurement type stored by this edge.

Public Member Functions

 BaseBinaryEdge ()
 Constructs an empty binary edge with null-mapped Hessian and Jacobian memory.
bool allVerticesFixed () const final override
 Returns true if both vertices are fixed.
void constructQuadraticForm ()
 Constructs the quadratic form (Hessian blocks and gradient) from the linearized edge.
void constructQuadraticForm2 ()
 Constructs the quadratic form using an optimized evaluation order.
const JacobianXiOplusTypejacobianOplusXi () const
 returns the result of the linearization in the manifold space for the node xi
const JacobianXjOplusTypejacobianOplusXj () const
 returns the result of the linearization in the manifold space for the node xj
virtual void linearizeOplus ()
 Numerically linearizes the oplus operator by finite differences for both vertices.
void linearizeOplusAndConstructQuadraticForm (JacobianWorkspace &jacobianWorkspace) final override
 Linearizes the oplus operator and constructs the quadratic form in one step.
void mapHessianMemory (g_type *d, int i, int j, bool rowMajor) final override
 Maps the Hessian block memory to an external buffer.
virtual void setVertex (uint04 i, HyperGraph::HGVertex *v) final override
 Sets vertex i to the given pointer, with type-checking.
virtual const HyperGraph::HGVertexvertex (uint04 i) const final override
 Returns a const pointer to vertex i (0 or 1).
virtual HyperGraph::HGVertexvertex (uint04 i) final override
 Returns a mutable pointer to vertex i (0 or 1).
virtual uint04 vertexCount () const final override
 Returns the number of vertices (always 2 for binary edges).
Public Member Functions inherited from BaseEdge< D, E >
 BaseEdge ()
 Default constructor.
g_type chi2 () const final override
 Computes the chi-squared error: e^T * Omega * e.
virtual sint04 dimension () const final override
 Returns the dimension of the error vector.
const ErrorVectorerror () const
 Returns a const reference to the error vector.
const InformationTypeinformation () const
 Returns a const reference to the information matrix.
const g_type * informationData () const final override
 Returns a const pointer to the raw information matrix data.
const Measurementmeasurement () const
 accessor functions for the measurement represented by the edge
int rank () const
 Returns the rank (dimension) of the error.
g_type scalerInformation () const
 information matrix of the constraint
void setInformation (const InformationType &information)
 Sets the information matrix.
void setMeasurement (const Measurement &m)
 Sets the measurement for this edge.
Public Member Functions inherited from OptimizableGraph::OGEdge
 OGEdge ()
 Default constructor.
void clearRobustKernel ()
 Removes the robust kernel from this edge.
virtual void computeError ()=0
 Computes the error of the edge and stores it internally.
long long internalId () const
 the internal ID of the edge
int level () const
 returns the level of the edge
RobustKernelrobustKernel () const
 if NOT NULL, error of this edge will be robustifed with the kernel
void setLevel (int l)
 sets the level of the edge
void setRobustKernel (RobustKernel &ptr)
 specify the robust kernel to be used in this edge
Public Member Functions inherited from HyperGraph::HGEdge
 HGEdge (int id=-1)
 creates and empty edge with no vertices
int id () const
 returns the id of this edge
void setId (int id)
 sets the id of this edge

Static Public Attributes

static constexpr int Di = VertexXiType::Dimension
 Dimension of the first vertex.
static constexpr int Dj = VertexXjType::Dimension
 Dimension of the second vertex.
Static Public Attributes inherited from BaseEdge< D, E >
static constexpr sint04 Dimension
 Compile-time dimension of the error vector.

Protected Attributes

HessianBlockType _hessian
 Mapped Hessian block for the off-diagonal (i,j) entry.
bool _hessianRowMajor
 Whether the Hessian block is stored in row-major order.
HessianBlockTransposedType _hessianTransposed
 Mapped transposed Hessian block.
JacobianXiOplusType _jacobianOplusXi
 Jacobian of the error w.r.t. vertex Xi.
JacobianXjOplusType _jacobianOplusXj
 Jacobian of the error w.r.t. vertex Xj.
VertexXi * m_a = nullptr
 Pointer to the first (source) vertex.
VertexXj * m_b = nullptr
 Pointer to the second (target) vertex.
Protected Attributes inherited from BaseEdge< D, E >
ErrorVector _error
 The current error vector.
InformationType _information
 The information (inverse covariance) matrix.
Measurement _measurement
 The stored measurement for this edge.
Protected Attributes inherited from OptimizableGraph::OGEdge
int _internalId = 0
 Internal sequential id assigned on insertion.
int _level = 0
 Optimization level for multi-level optimization.
RobustKernel_robustKernel = nullptr
 Optional robust kernel for this edge.
Protected Attributes inherited from HyperGraph::HGEdge
int _id
 unique id

Additional Inherited Members

Protected Member Functions inherited from BaseEdge< D, E >
InformationType robustInformation (const Eigen::Vector3< g_type > &rho) const
 calculate the robust information matrix by updating the information matrix of the error

Detailed Description

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
class BaseBinaryEdge< D, E, VertexXi, VertexXj >

Base class for edges connecting exactly two vertices in the graph.

Template Parameters
DThe dimension of the error vector.
EThe measurement type.
VertexXiThe type of the first vertex.
VertexXjThe type of the second vertex.

Definition at line 17 of file base_binary_edge.h.

Member Function Documentation

◆ linearizeOplusAndConstructQuadraticForm()

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
void BaseBinaryEdge< D, E, VertexXi, VertexXj >::linearizeOplusAndConstructQuadraticForm ( JacobianWorkspace & jacobianWorkspace)
inlinefinaloverridevirtual

Linearizes the oplus operator and constructs the quadratic form in one step.

Parameters
[in]jacobianWorkspaceWorkspace providing temporary memory for Jacobian computation.

Implements OptimizableGraph::OGEdge.

Definition at line 247 of file base_binary_edge.h.

References _jacobianOplusXi, _jacobianOplusXj, constructQuadraticForm(), Di, Dj, and linearizeOplus().

◆ mapHessianMemory()

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
void BaseBinaryEdge< D, E, VertexXi, VertexXj >::mapHessianMemory ( g_type * d,
int i,
int j,
bool rowMajor )
inlinefinaloverridevirtual

Maps the Hessian block memory to an external buffer.

Parameters
[in]dPointer to the external memory.
[in]iIndex of vertex i (unused, asserted to be 0).
[in]jIndex of vertex j (unused, asserted to be 1).
[in]rowMajorIf true, writes the transposed block.

Implements OptimizableGraph::OGEdge.

Definition at line 335 of file base_binary_edge.h.

References _hessian, _hessianRowMajor, and _hessianTransposed.

◆ setVertex()

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
virtual void BaseBinaryEdge< D, E, VertexXi, VertexXj >::setVertex ( uint04 i,
HyperGraph::HGVertex * v )
inlinefinaloverridevirtual

Sets vertex i to the given pointer, with type-checking.

Parameters
[in]iThe vertex index (0 or 1).
[in]vThe vertex pointer to assign.

Implements HyperGraph::HGEdge.

Definition at line 74 of file base_binary_edge.h.

References cast(), m_a, and m_b.

◆ vertex() [1/2]

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
virtual const HyperGraph::HGVertex * BaseBinaryEdge< D, E, VertexXi, VertexXj >::vertex ( uint04 i) const
inlinefinaloverridevirtual

Returns a const pointer to vertex i (0 or 1).

Parameters
[in]iThe vertex index.

Implements HyperGraph::HGEdge.

Definition at line 55 of file base_binary_edge.h.

References m_a, and m_b.

◆ vertex() [2/2]

template<sint04 D, typename E, typename VertexXi, typename VertexXj>
virtual HyperGraph::HGVertex * BaseBinaryEdge< D, E, VertexXi, VertexXj >::vertex ( uint04 i)
inlinefinaloverridevirtual

Returns a mutable pointer to vertex i (0 or 1).

Parameters
[in]iThe vertex index.

Implements HyperGraph::HGEdge.

Definition at line 64 of file base_binary_edge.h.

References m_a, and m_b.


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