Public Member Functions | Protected Member Functions | Protected Attributes | Friends | List of all members
g2o::OptimizableGraph::Edge Class Referenceabstract

#include <optimizable_graph.h>

Inheritance diagram for g2o::OptimizableGraph::Edge:
Inheritance graph
[legend]

Public Member Functions

virtual bool allVerticesFixed () const =0
 
virtual double chi2 () const =0
 computes the chi2 based on the cached error value, only valid after computeError has been called. More...
 
virtual Edgeclone () const
 
virtual void computeError ()=0
 
virtual void constructQuadraticForm ()=0
 
virtual VertexcreateFrom ()
 
virtual VertexcreateTo ()
 
int dimension () const
 returns the dimensions of the error function More...
 
 Edge ()
 
virtual const double * errorData () const =0
 returns the error vector cached after calling the computeError; More...
 
virtual double * errorData ()=0
 
virtual bool getMeasurementData (double *m) const
 
OptimizableGraphgraph ()
 
const OptimizableGraphgraph () const
 
virtual const double * informationData () const =0
 returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd> More...
 
virtual double * informationData ()=0
 
virtual void initialEstimate (const OptimizableGraph::VertexSet &from, OptimizableGraph::Vertex *to)=0
 
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 void linearizeOplus (JacobianWorkspace &jacobianWorkspace)=0
 
virtual void mapHessianMemory (double *d, int i, int j, bool rowMajor)=0
 
virtual int measurementDimension () const
 
size_t numParameters () const
 
const Parameterparameter (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)
 
RobustKernelrobustKernel () 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
 
virtual void resize (size_t size)
 
void setId (int id)
 
void setVertex (size_t i, Vertex *v)
 
const Vertexvertex (size_t i) const
 
Vertexvertex (size_t i)
 
const VertexContainervertices () const
 
VertexContainervertices ()
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 

Protected Member Functions

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 &parameters)
 
virtual bool resolveCaches ()
 
bool resolveParameters ()
 

Protected Attributes

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
 

Friends

struct OptimizableGraph
 

Detailed Description

Definition at line 382 of file optimizable_graph.h.

Constructor & Destructor Documentation

g2o::OptimizableGraph::Edge::Edge ( )

Definition at line 132 of file optimizable_graph.cpp.

g2o::OptimizableGraph::Edge::~Edge ( )
virtual

Reimplemented from g2o::HyperGraph::Edge.

Definition at line 138 of file optimizable_graph.cpp.

Member Function Documentation

virtual bool g2o::OptimizableGraph::Edge::allVerticesFixed ( ) const
pure virtual
virtual double g2o::OptimizableGraph::Edge::chi2 ( ) const
pure virtual

computes the chi2 based on the cached error value, only valid after computeError has been called.

Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, and g2o::BaseEdge< D, Sim3 >.

OptimizableGraph::Edge * g2o::OptimizableGraph::Edge::clone ( ) const
virtual

Definition at line 224 of file optimizable_graph.cpp.

virtual void g2o::OptimizableGraph::Edge::computeError ( )
pure virtual
virtual void g2o::OptimizableGraph::Edge::constructQuadraticForm ( )
pure virtual
virtual Vertex* g2o::OptimizableGraph::Edge::createFrom ( )
inlinevirtual
virtual Vertex* g2o::OptimizableGraph::Edge::createTo ( )
inlinevirtual
int g2o::OptimizableGraph::Edge::dimension ( ) const
inline

returns the dimensions of the error function

Definition at line 472 of file optimizable_graph.h.

virtual const double* g2o::OptimizableGraph::Edge::errorData ( ) const
pure virtual

returns the error vector cached after calling the computeError;

Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, and g2o::BaseEdge< D, Sim3 >.

virtual double* g2o::OptimizableGraph::Edge::errorData ( )
pure virtual
bool g2o::OptimizableGraph::Edge::getMeasurementData ( double *  m) const
virtual

writes the measurement to an array of double

Returns
true on success

Definition at line 209 of file optimizable_graph.cpp.

OptimizableGraph * g2o::OptimizableGraph::Edge::graph ( )

Definition at line 143 of file optimizable_graph.cpp.

const OptimizableGraph * g2o::OptimizableGraph::Edge::graph ( ) const

Definition at line 152 of file optimizable_graph.cpp.

virtual const double* g2o::OptimizableGraph::Edge::informationData ( ) const
pure virtual

returns the memory of the information matrix, usable for example with a Eigen::Map<MatrixXd>

Implemented in g2o::BaseEdge< D, E >, g2o::BaseEdge< D, Vector2d >, g2o::BaseEdge< D, Vector3d >, and g2o::BaseEdge< D, Sim3 >.

virtual double* g2o::OptimizableGraph::Edge::informationData ( )
pure virtual
virtual void g2o::OptimizableGraph::Edge::initialEstimate ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
pure virtual
virtual double g2o::OptimizableGraph::Edge::initialEstimatePossible ( const OptimizableGraph::VertexSet from,
OptimizableGraph::Vertex to 
)
inlinevirtual

override in your class if it's possible to initialize the vertices in certain combinations. The return value may correspond to the cost for initiliaizng the vertex but should be positive if the initialization is possible and negative if not possible.

Reimplemented in g2o::EdgeSim3.

Definition at line 464 of file optimizable_graph.h.

template<typename ParameterType >
bool g2o::OptimizableGraph::Edge::installParameter ( ParameterType *&  p,
size_t  argNo,
int  paramId = -1 
)
inlineprotected

Definition at line 505 of file optimizable_graph.h.

long long g2o::OptimizableGraph::Edge::internalId ( ) const
inline

the internal ID of the edge

Definition at line 483 of file optimizable_graph.h.

int g2o::OptimizableGraph::Edge::level ( ) const
inline

returns the level of the edge

Definition at line 467 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Edge::linearizeOplus ( JacobianWorkspace jacobianWorkspace)
pure virtual
virtual void g2o::OptimizableGraph::Edge::mapHessianMemory ( double *  d,
int  i,
int  j,
bool  rowMajor 
)
pure virtual

maps the internal matrix to some external memory location, you need to provide the memory before calling constructQuadraticForm

Parameters
dthe memory location to which we map
iindex of the vertex i
jindex of the vertex j (j > i, upper triangular fashion)
rowMajorif true, will write in rowMajor order to the block. Since EIGEN is columnMajor by default, this results in writing the transposed

Implemented in g2o::BaseBinaryEdge< D, E, VertexXi, VertexXj >, g2o::BaseBinaryEdge< 2, Vector2d, VertexSBAPointXYZ, VertexSim3Expmap >, g2o::BaseBinaryEdge< 7, Sim3, VertexSim3Expmap, VertexSim3Expmap >, g2o::BaseBinaryEdge< 2, Vector2d, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseBinaryEdge< 3, Vector3d, VertexSBAPointXYZ, VertexSE3Expmap >, g2o::BaseMultiEdge< D, E >, g2o::BaseUnaryEdge< D, E, VertexXi >, g2o::BaseUnaryEdge< 2, Vector2d, VertexSE3Expmap >, and g2o::BaseUnaryEdge< 3, Vector3d, VertexSE3Expmap >.

int g2o::OptimizableGraph::Edge::measurementDimension ( ) const
virtual

returns the dimension of the measurement in the extended representation which is used by get/setMeasurement;

Definition at line 214 of file optimizable_graph.cpp.

size_t g2o::OptimizableGraph::Edge::numParameters ( ) const
inline

Definition at line 490 of file optimizable_graph.h.

const Parameter* g2o::OptimizableGraph::Edge::parameter ( int  argNo) const
inline

Definition at line 489 of file optimizable_graph.h.

virtual bool g2o::OptimizableGraph::Edge::read ( std::istream &  is)
pure virtual
void g2o::OptimizableGraph::Edge::resizeParameters ( size_t  newSize)
inline

Definition at line 491 of file optimizable_graph.h.

template<typename CacheType >
void g2o::OptimizableGraph::Edge::resolveCache ( CacheType *&  cache,
OptimizableGraph::Vertex v,
const std::string &  _type,
const ParameterVector parameters 
)
protected

Definition at line 121 of file cache.h.

bool g2o::OptimizableGraph::Edge::resolveCaches ( )
protectedvirtual

Definition at line 200 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Edge::resolveParameters ( )
protected

Definition at line 171 of file optimizable_graph.cpp.

RobustKernel* g2o::OptimizableGraph::Edge::robustKernel ( ) const
inline

if NOT NULL, error of this edge will be robustifed with the kernel

Definition at line 415 of file optimizable_graph.h.

void g2o::OptimizableGraph::Edge::setLevel ( int  l)
inline

sets the level of the edge

Definition at line 469 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Edge::setMeasurementData ( const double *  m)
virtual

sets the measurement from an array of double

Returns
true on success

Definition at line 204 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Edge::setMeasurementFromState ( )
virtual

sets the estimate to have a zero error, based on the current value of the state variables returns false if not supported.

Definition at line 219 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Edge::setParameterId ( int  argNum,
int  paramId 
)

Definition at line 161 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::Edge::setRobustKernel ( RobustKernel ptr)

specify the robust kernel to be used in this edge

Definition at line 193 of file optimizable_graph.cpp.

virtual bool g2o::OptimizableGraph::Edge::write ( std::ostream &  os) const
pure virtual

Friends And Related Function Documentation

friend struct OptimizableGraph
friend

Definition at line 384 of file optimizable_graph.h.

Member Data Documentation

std::vector<int> g2o::OptimizableGraph::Edge::_cacheIds
protected

Definition at line 502 of file optimizable_graph.h.

int g2o::OptimizableGraph::Edge::_dimension
protected

Definition at line 497 of file optimizable_graph.h.

long long g2o::OptimizableGraph::Edge::_internalId
protected

Definition at line 500 of file optimizable_graph.h.

int g2o::OptimizableGraph::Edge::_level
protected

Definition at line 498 of file optimizable_graph.h.

std::vector<int> g2o::OptimizableGraph::Edge::_parameterIds
protected

Definition at line 524 of file optimizable_graph.h.

std::vector<Parameter**> g2o::OptimizableGraph::Edge::_parameters
protected

Definition at line 523 of file optimizable_graph.h.

std::vector<std::string> g2o::OptimizableGraph::Edge::_parameterTypes
protected

Definition at line 522 of file optimizable_graph.h.

RobustKernel* g2o::OptimizableGraph::Edge::_robustKernel
protected

Definition at line 499 of file optimizable_graph.h.


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


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06