base class to represent an edge connecting an arbitrary number of nodes 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 Eigen::Map< MatrixXd, MatrixXd::Flags &PacketAccessBit?Aligned:Unaligned > | HessianBlockType |
typedef BaseEdge< D, E >::InformationType | InformationType |
typedef MatrixXd::MapType | JacobianType |
typedef BaseEdge< D, E >::Measurement | Measurement |
Public Types inherited from g2o::BaseEdge< D, E > | |
typedef Matrix< double, D, 1 > | ErrorVector |
typedef Matrix< double, D, D > | InformationType |
typedef E | Measurement |
Public Member Functions | |
virtual bool | allVerticesFixed () const |
BaseMultiEdge () | |
virtual void | constructQuadraticForm () |
virtual void | linearizeOplus (JacobianWorkspace &jacobianWorkspace) |
virtual void | linearizeOplus () |
virtual void | mapHessianMemory (double *d, int i, int j, bool rowMajor) |
virtual void | resize (size_t size) |
Public Member Functions inherited from g2o::BaseEdge< D, E > | |
BaseEdge () | |
virtual double | chi2 () const |
computes the chi2 based on the cached error value, only valid after computeError has been called. More... | |
const ErrorVector & | error () const |
ErrorVector & | error () |
virtual const double * | errorData () const |
returns the error vector cached after calling the computeError; More... | |
virtual double * | errorData () |
const InformationType & | information () const |
information matrix of the constraint More... | |
InformationType & | information () |
virtual const double * | informationData () const |
returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd> More... | |
virtual double * | informationData () |
virtual void | initialEstimate (const OptimizableGraph::VertexSet &, OptimizableGraph::Vertex *) |
const Measurement & | measurement () const |
accessor functions for the measurement represented by the edge More... | |
virtual int | rank () const |
void | setInformation (const InformationType &information) |
virtual void | setMeasurement (const Measurement &m) |
virtual | ~BaseEdge () |
Public Member Functions inherited from g2o::OptimizableGraph::Edge | |
virtual Edge * | clone () const |
virtual void | computeError ()=0 |
virtual Vertex * | createFrom () |
virtual Vertex * | createTo () |
int | dimension () const |
returns the dimensions of the error function More... | |
Edge () | |
virtual bool | getMeasurementData (double *m) const |
OptimizableGraph * | graph () |
const OptimizableGraph * | graph () const |
virtual double | initialEstimatePossible (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to) |
long long | internalId () const |
the internal ID of the edge More... | |
int | level () const |
returns the level of the edge More... | |
virtual int | measurementDimension () const |
size_t | numParameters () const |
const Parameter * | parameter (int argNo) const |
virtual bool | read (std::istream &is)=0 |
read the vertex from a stream, i.e., the internal state of the vertex More... | |
void | resizeParameters (size_t newSize) |
RobustKernel * | robustKernel () const |
if NOT NULL, error of this edge will be robustifed with the kernel More... | |
void | setLevel (int l) |
sets the level of the edge More... | |
virtual bool | setMeasurementData (const double *m) |
virtual bool | setMeasurementFromState () |
bool | setParameterId (int argNum, int paramId) |
void | setRobustKernel (RobustKernel *ptr) |
virtual bool | write (std::ostream &os) const =0 |
write the vertex to a stream More... | |
virtual | ~Edge () |
Public Member Functions inherited from g2o::HyperGraph::Edge | |
Edge (int id=-1) | |
creates and empty edge with no vertices More... | |
virtual HyperGraphElementType | elementType () const |
int | id () const |
void | setId (int id) |
void | setVertex (size_t i, Vertex *v) |
const Vertex * | vertex (size_t i) const |
Vertex * | vertex (size_t i) |
const VertexContainer & | vertices () const |
VertexContainer & | vertices () |
Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement | |
virtual | ~HyperGraphElement () |
Static Public Attributes | |
static const int | Dimension = BaseEdge<D,E>::Dimension |
Static Public Attributes inherited from g2o::BaseEdge< D, E > | |
static const int | Dimension = D |
Protected Member Functions | |
void | computeQuadraticForm (const InformationType &omega, const ErrorVector &weightedError) |
Protected Member Functions inherited from g2o::BaseEdge< D, E > | |
InformationType | robustInformation (const Eigen::Vector3d &rho) |
Protected Member Functions inherited from g2o::OptimizableGraph::Edge | |
template<typename ParameterType > | |
bool | installParameter (ParameterType *&p, size_t argNo, int paramId=-1) |
template<typename CacheType > | |
void | resolveCache (CacheType *&cache, OptimizableGraph::Vertex *, const std::string &_type, const ParameterVector ¶meters) |
virtual bool | resolveCaches () |
bool | resolveParameters () |
Protected Attributes | |
std::vector< HessianHelper > | _hessian |
std::vector< JacobianType, aligned_allocator< JacobianType > > | _jacobianOplus |
jacobians of the edge (w.r.t. oplus) More... | |
Protected Attributes inherited from g2o::BaseEdge< D, E > | |
ErrorVector | _error |
InformationType | _information |
Measurement | _measurement |
Protected Attributes inherited from g2o::OptimizableGraph::Edge | |
std::vector< int > | _cacheIds |
int | _dimension |
long long | _internalId |
int | _level |
std::vector< int > | _parameterIds |
std::vector< Parameter ** > | _parameters |
std::vector< std::string > | _parameterTypes |
RobustKernel * | _robustKernel |
Protected Attributes inherited from g2o::HyperGraph::Edge | |
int | _id |
unique id More... | |
VertexContainer | _vertices |
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 51 of file base_multi_edge.h.
typedef BaseEdge<D,E>::ErrorVector g2o::BaseMultiEdge< D, E >::ErrorVector |
Definition at line 67 of file base_multi_edge.h.
typedef Eigen::Map<MatrixXd, MatrixXd::Flags & PacketAccessBit ? Aligned : Unaligned > g2o::BaseMultiEdge< D, E >::HessianBlockType |
Definition at line 69 of file base_multi_edge.h.
typedef BaseEdge<D,E>::InformationType g2o::BaseMultiEdge< D, E >::InformationType |
Definition at line 68 of file base_multi_edge.h.
typedef MatrixXd::MapType g2o::BaseMultiEdge< D, E >::JacobianType |
Definition at line 66 of file base_multi_edge.h.
typedef BaseEdge<D,E>::Measurement g2o::BaseMultiEdge< D, E >::Measurement |
Definition at line 65 of file base_multi_edge.h.
|
inline |
Definition at line 71 of file base_multi_edge.h.
|
virtual |
Implements g2o::OptimizableGraph::Edge.
Definition at line 161 of file base_multi_edge.h.
|
protected |
Definition at line 172 of file base_multi_edge.h.
|
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 37 of file base_multi_edge.h.
|
virtual |
Linearizes the constraint in the edge in the manifold space, and store the result in the given workspace
Implements g2o::OptimizableGraph::Edge.
Definition at line 53 of file base_multi_edge.h.
|
virtual |
Linearizes the oplus operator in the vertex, and stores the result in temporary variable vector _jacobianOplus
Definition at line 64 of file base_multi_edge.h.
|
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 130 of file base_multi_edge.h.
|
virtual |
resizes the number of vertices connected by this edge
Reimplemented from g2o::HyperGraph::Edge.
Definition at line 150 of file base_multi_edge.h.
|
protected |
Definition at line 100 of file base_multi_edge.h.
|
protected |
jacobians of the edge (w.r.t. oplus)
Definition at line 101 of file base_multi_edge.h.
|
static |
Definition at line 64 of file base_multi_edge.h.