![]() |
NDEVR
API Documentation
|
base class to represent an edge connecting an arbitrary number of nodes More...
Classes | |
| struct | HessianHelper |
| helper for mapping the Hessian memory of the upper triangular block More... | |
Public Types | |
| typedef BaseEdge< t_dims, E >::ErrorVector | ErrorVector |
| The error vector type. | |
| typedef BaseEdge< t_dims, E >::InformationType | InformationType |
| The information matrix type. | |
| typedef MatrixX< g_type >::MapType | JacobianType |
| Dynamic-size Jacobian map type. | |
| typedef BaseEdge< t_dims, E >::Measurement | Measurement |
| The measurement type. | |
| Public Types inherited from BaseEdge< t_dims, 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 | |
| BaseMultiEdge () | |
| Default constructor. | |
| bool | allVerticesFixed () const final override |
| Returns true if all connected vertices are fixed. | |
| void | computeQuadraticForm (const InformationType &omega, const ErrorVector &weightedError) |
| Computes the quadratic form contributions for all vertex pairs. | |
| void | constructQuadraticForm () |
| Constructs the quadratic form (Hessian and gradient) from the linearized multi-edge. | |
| void | linearizeOplusAndConstructQuadraticForm (JacobianWorkspace &jacobianWorkspace) final override |
| Linearizes the constraint in the edge in the manifold space, and store the result in the given workspace and Linearizes the constraint in the edge. | |
| void | mapHessianMemory (g_type *d, int i, int j, bool rowMajor) final override |
| maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm | |
| void | resize (uint04 size) |
| Resizes the edge to connect a given number of vertices. | |
| virtual void | setVertex (uint04 i, HyperGraph::HGVertex *v) final override |
| Sets the i-th vertex, with bounds and type checking. | |
| virtual const HyperGraph::HGVertex * | vertex (uint04 i) const final override |
| Returns a const pointer to the i-th vertex. | |
| virtual HyperGraph::HGVertex * | vertex (uint04 i) final override |
| Returns a mutable pointer to the i-th vertex. | |
| virtual uint04 | vertexCount () const final override |
| Returns the number of connected vertices. | |
| Public Member Functions inherited from BaseEdge< t_dims, 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 ErrorVector & | error () const |
| Returns a const reference to the error vector. | |
| const InformationType & | information () 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. | |
| g_type * | informationData () final override |
| Returns a mutable pointer to the raw information matrix data. | |
| const Measurement & | measurement () 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 | setInformation (g_type information) |
| Sets the information matrix to a scaled identity. | |
| 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 | |
| RobustKernel * | robustKernel () 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 Member Functions | |
| static int | computeUpperTriangleIndex (int i, int j) |
| Computes the linear index for the upper-triangular storage of off-diagonal Hessian blocks. | |
Static Public Attributes | |
| static const int | Dimension = BaseEdge<t_dims, E>::Dimension |
| Dimension of the error vector. | |
| Static Public Attributes inherited from BaseEdge< t_dims, E > | |
| static constexpr sint04 | Dimension = t_dims |
| Compile-time dimension of the error vector. | |
Protected Attributes | |
| Buffer< HessianHelper > | _hessian |
| Off-diagonal Hessian blocks (upper triangle). | |
| Buffer< JacobianType > | _jacobianOplus |
| jacobians of the edge (w.r.t. oplus) | |
| Buffer< OptimizableGraph::OGVertex * > | _vertices |
| The connected vertices. | |
| Protected Attributes inherited from BaseEdge< t_dims, 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< t_dims, E > | |
| InformationType | robustInformation (const Eigen::Vector3< g_type > &rho) const |
| calculate the robust information matrix by updating the information matrix of the error | |
base class to represent an edge connecting an arbitrary number of nodes
t_dims - Dimension of the measurement E - type to represent the measurement
Definition at line 21 of file base_multi_edge.h.
|
inline |
Computes the quadratic form contributions for all vertex pairs.
| [in] | omega | The (possibly robustified) information matrix. |
| [in] | weightedError | The weighted error vector. |
Definition at line 207 of file base_multi_edge.h.
References _hessian, _jacobianOplus, _vertices, OptimizableGraph::OGVertex::bData(), computeUpperTriangleIndex(), OptimizableGraph::OGVertex::dimension(), OptimizableGraph::OGVertex::fixed(), BaseMultiEdge< t_dims, E >::HessianHelper::matrix, and BaseMultiEdge< t_dims, E >::HessianHelper::transposed.
Referenced by constructQuadraticForm().
|
inlinestatic |
Computes the linear index for the upper-triangular storage of off-diagonal Hessian blocks.
| [in] | i | Row block index. |
| [in] | j | Column block index (j > i). |
Definition at line 70 of file base_multi_edge.h.
Referenced by computeQuadraticForm(), and mapHessianMemory().
|
inlinefinaloverridevirtual |
Linearizes the constraint in the edge in the manifold space, and store the result in the given workspace and 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 OptimizableGraph::OGEdge.
Definition at line 93 of file base_multi_edge.h.
References _jacobianOplus, _vertices, cast(), constructQuadraticForm(), and OptimizableGraph::OGVertex::dimension().
|
inlinefinaloverridevirtual |
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 OptimizableGraph::OGEdge.
Definition at line 152 of file base_multi_edge.h.
References _hessian, _vertices, computeUpperTriangleIndex(), OptimizableGraph::OGVertex::dimension(), BaseMultiEdge< t_dims, E >::HessianHelper::matrix, and BaseMultiEdge< t_dims, E >::HessianHelper::transposed.
|
inline |
Resizes the edge to connect a given number of vertices.
| [in] | size | The number of vertices. |
Definition at line 174 of file base_multi_edge.h.
References _hessian, _jacobianOplus, and _vertices.
|
inlinefinaloverridevirtual |
Sets the i-th vertex, with bounds and type checking.
| [in] | i | The vertex index. |
| [in] | v | The vertex pointer. |
Implements HyperGraph::HGEdge.
Definition at line 59 of file base_multi_edge.h.