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

A general case Vertex for optimization. More...

#include <optimizable_graph.h>

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

Public Member Functions

void addUserData (Data *obs)
 
virtual const double & b (int i) const =0
 get the b vector element More...
 
virtual double & b (int i)=0
 
virtual double * bData ()=0
 return a pointer to the b vector associated with this vertex More...
 
CacheContainercacheContainer ()
 
virtual void clearQuadraticForm ()=0
 
virtual Vertexclone () const
 returns a deep copy of the current vertex More...
 
int colInHessian () const
 get the row of this vertex in the Hessian More...
 
virtual int copyB (double *b_) const =0
 
int dimension () const
 dimension of the estimated state belonging to this node More...
 
virtual void discardTop ()=0
 pop the last element from the stack, without restoring the current estimate More...
 
virtual int estimateDimension () const
 
bool fixed () const
 true => this node is fixed during the optimization More...
 
int G2O_ATTRIBUTE_DEPRECATED (tempIndex() const)
 
void G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti))
 
virtual bool getEstimateData (double *estimate) const
 
virtual bool getEstimateData (std::vector< double > &estimate) const
 
virtual bool getMinimalEstimateData (double *estimate) const
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) const
 
const OptimizableGraphgraph () const
 
OptimizableGraphgraph ()
 
virtual const double & hessian (int i, int j) const =0
 get the element from the hessian matrix More...
 
virtual double & hessian (int i, int j)=0
 
virtual double * hessianData ()=0
 
virtual double hessianDeterminant () const =0
 
int hessianIndex () const
 temporary index of this node in the parameter vector obtained from linearization More...
 
void lockQuadraticForm ()
 
virtual void mapHessianMemory (double *d)=0
 
bool marginalized () const
 true => this node is marginalized out during the optimization More...
 
virtual int minimalEstimateDimension () const
 
void oplus (const double *v)
 
virtual void pop ()=0
 restore the position of the vertex by retrieving the position from the stack More...
 
virtual void push ()=0
 backup the position of the vertex to a stack More...
 
virtual bool read (std::istream &is)=0
 read the vertex from a stream, i.e., the internal state of the vertex More...
 
void setColInHessian (int c)
 set the row of this vertex in the Hessian More...
 
bool setEstimateData (const double *estimate)
 
bool setEstimateData (const std::vector< double > &estimate)
 
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization More...
 
void setHessianIndex (int ti)
 set the temporary index of the vertex in the parameter blocks More...
 
virtual void setId (int id)
 sets the id of the node in the graph be sure that the graph keeps consistent after changing the id More...
 
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization More...
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff) More...
 
void setUserData (Data *obs)
 
virtual double solveDirect (double lambda=0)=0
 
virtual int stackSize () const =0
 return the stack size More...
 
void unlockQuadraticForm ()
 
virtual void updateCache ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
 Vertex ()
 
virtual bool write (std::ostream &os) const =0
 write the vertex to a stream More...
 
virtual ~Vertex ()
 
- Public Member Functions inherited from g2o::HyperGraph::Vertex
const EdgeSetedges () const
 returns the set of hyper-edges that are leaving/entering in this vertex More...
 
EdgeSetedges ()
 returns the set of hyper-edges that are leaving/entering in this vertex More...
 
virtual HyperGraphElementType elementType () const
 
int id () const
 returns the id More...
 
 Vertex (int id=-1)
 creates a vertex having an ID specified by the argument More...
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 

Protected Member Functions

virtual void oplusImpl (const double *v)=0
 
virtual bool setEstimateDataImpl (const double *)
 
virtual bool setMinimalEstimateDataImpl (const double *)
 
virtual void setToOriginImpl ()=0
 sets the node to the origin (used in the multilevel stuff) More...
 

Protected Attributes

CacheContainer_cacheContainer
 
int _colInHessian
 
int _dimension
 
bool _fixed
 
OptimizableGraph_graph
 
int _hessianIndex
 
bool _marginalized
 
OpenMPMutex _quadraticFormMutex
 
Data_userData
 
- Protected Attributes inherited from g2o::HyperGraph::Vertex
EdgeSet _edges
 
int _id
 

Friends

struct OptimizableGraph
 

Detailed Description

A general case Vertex for optimization.

Definition at line 127 of file optimizable_graph.h.

Constructor & Destructor Documentation

g2o::OptimizableGraph::Vertex::Vertex ( )

Definition at line 63 of file optimizable_graph.cpp.

g2o::OptimizableGraph::Vertex::~Vertex ( )
virtual

Reimplemented from g2o::HyperGraph::Vertex.

Definition at line 84 of file optimizable_graph.cpp.

Member Function Documentation

void g2o::OptimizableGraph::Vertex::addUserData ( Data obs)
inline

Definition at line 141 of file optimizable_graph.h.

virtual const double& g2o::OptimizableGraph::Vertex::b ( int  i) const
pure virtual
virtual double& g2o::OptimizableGraph::Vertex::b ( int  i)
pure virtual
virtual double* g2o::OptimizableGraph::Vertex::bData ( )
pure virtual

return a pointer to the b vector associated with this vertex

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

CacheContainer * g2o::OptimizableGraph::Vertex::cacheContainer ( )

Definition at line 70 of file optimizable_graph.cpp.

virtual void g2o::OptimizableGraph::Vertex::clearQuadraticForm ( )
pure virtual

set the b vector part of this vertex to zero

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

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

returns a deep copy of the current vertex

Definition at line 92 of file optimizable_graph.cpp.

int g2o::OptimizableGraph::Vertex::colInHessian ( ) const
inline

get the row of this vertex in the Hessian

Definition at line 323 of file optimizable_graph.h.

virtual int g2o::OptimizableGraph::Vertex::copyB ( double *  b_) const
pure virtual

copies the b vector in the array b_

Returns
the number of elements copied

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

int g2o::OptimizableGraph::Vertex::dimension ( ) const
inline

dimension of the estimated state belonging to this node

Definition at line 315 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::discardTop ( )
pure virtual

pop the last element from the stack, without restoring the current estimate

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

int g2o::OptimizableGraph::Vertex::estimateDimension ( ) const
virtual

returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported

Definition at line 109 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Vertex::fixed ( ) const
inline

true => this node is fixed during the optimization

Definition at line 305 of file optimizable_graph.h.

int g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( tempIndex()  const)
inline

Definition at line 299 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( setTempIndex(int ti)  )
inline

Definition at line 302 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::getEstimateData ( double *  estimate) const
virtual

writes the estimater to an array of double

Returns
true on success

Definition at line 104 of file optimizable_graph.cpp.

virtual bool g2o::OptimizableGraph::Vertex::getEstimateData ( std::vector< double > &  estimate) const
inlinevirtual

writes the estimater to an array of double

Returns
true on success

Definition at line 215 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( double *  estimate) const
virtual

writes the estimate to an array of double

Returns
true on success

Definition at line 121 of file optimizable_graph.cpp.

virtual bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( std::vector< double > &  estimate) const
inlinevirtual

writes the estimate to an array of double

Returns
true on success

Definition at line 259 of file optimizable_graph.h.

const OptimizableGraph* g2o::OptimizableGraph::Vertex::graph ( ) const
inline

Definition at line 325 of file optimizable_graph.h.

OptimizableGraph* g2o::OptimizableGraph::Vertex::graph ( )
inline

Definition at line 327 of file optimizable_graph.h.

virtual const double& g2o::OptimizableGraph::Vertex::hessian ( int  i,
int  j 
) const
pure virtual
virtual double& g2o::OptimizableGraph::Vertex::hessian ( int  i,
int  j 
)
pure virtual
virtual double* g2o::OptimizableGraph::Vertex::hessianData ( )
pure virtual
virtual double g2o::OptimizableGraph::Vertex::hessianDeterminant ( ) const
pure virtual
int g2o::OptimizableGraph::Vertex::hessianIndex ( ) const
inline

temporary index of this node in the parameter vector obtained from linearization

Definition at line 298 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::lockQuadraticForm ( )
inline

lock for the block of the hessian and the b vector associated with this vertex, to avoid race-conditions if multi-threaded.

Definition at line 333 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::mapHessianMemory ( double *  d)
pure virtual

maps the internal matrix to some external memory location

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

bool g2o::OptimizableGraph::Vertex::marginalized ( ) const
inline

true => this node is marginalized out during the optimization

Definition at line 310 of file optimizable_graph.h.

int g2o::OptimizableGraph::Vertex::minimalEstimateDimension ( ) const
virtual

returns the dimension of the extended representation used by get/setEstimate(double*) -1 if it is not supported

Definition at line 126 of file optimizable_graph.cpp.

void g2o::OptimizableGraph::Vertex::oplus ( const double *  v)
inline

Update the position of the node from the parameters in v. Depends on the implementation of oplusImpl in derived classes to actually carry out the update. Will also call updateCache() to update the caches of depending on the vertex.

Definition at line 291 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::oplusImpl ( const double *  v)
protectedpure virtual

update the position of the node from the parameters in v. Implement in your class!

Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.

virtual void g2o::OptimizableGraph::Vertex::pop ( )
pure virtual

restore the position of the vertex by retrieving the position from the stack

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

virtual void g2o::OptimizableGraph::Vertex::push ( )
pure virtual

backup the position of the vertex to a stack

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

virtual bool g2o::OptimizableGraph::Vertex::read ( std::istream &  is)
pure virtual

read the vertex from a stream, i.e., the internal state of the vertex

Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.

void g2o::OptimizableGraph::Vertex::setColInHessian ( int  c)
inline

set the row of this vertex in the Hessian

Definition at line 321 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::setEstimateData ( const double *  estimate)

sets the initial estimate from an array of double Implement setEstimateDataImpl()

Returns
true on success

Definition at line 97 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Vertex::setEstimateData ( const std::vector< double > &  estimate)
inline

sets the initial estimate from an array of double Implement setEstimateDataImpl()

Returns
true on success

Definition at line 197 of file optimizable_graph.h.

virtual bool g2o::OptimizableGraph::Vertex::setEstimateDataImpl ( const double *  )
inlineprotectedvirtual

writes the estimater to an array of double

Returns
true on success

Definition at line 372 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::setFixed ( bool  fixed)
inline

true => this node should be considered fixed during the optimization

Definition at line 307 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::setHessianIndex ( int  ti)
inline

set the temporary index of the vertex in the parameter blocks

Definition at line 301 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::setId ( int  id)
inlinevirtual

sets the id of the node in the graph be sure that the graph keeps consistent after changing the id

Reimplemented from g2o::HyperGraph::Vertex.

Definition at line 318 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::setMarginalized ( bool  marginalized)
inline

true => this node should be marginalized out during the optimization

Definition at line 312 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData ( const double *  estimate)

sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()

Returns
true on success

Definition at line 114 of file optimizable_graph.cpp.

bool g2o::OptimizableGraph::Vertex::setMinimalEstimateData ( const std::vector< double > &  estimate)
inline

sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()

Returns
true on success

Definition at line 241 of file optimizable_graph.h.

virtual bool g2o::OptimizableGraph::Vertex::setMinimalEstimateDataImpl ( const double *  )
inlineprotectedvirtual

sets the initial estimate from an array of double

Returns
true on success

Definition at line 378 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::setToOrigin ( )
inline

sets the node to the origin (used in the multilevel stuff)

Definition at line 151 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::setToOriginImpl ( )
protectedpure virtual

sets the node to the origin (used in the multilevel stuff)

Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.

void g2o::OptimizableGraph::Vertex::setUserData ( Data obs)
inline

Definition at line 140 of file optimizable_graph.h.

virtual double g2o::OptimizableGraph::Vertex::solveDirect ( double  lambda = 0)
pure virtual

updates the current vertex with the direct solution x += H_ii

Returns
the determinant of the inverted hessian

Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.

virtual int g2o::OptimizableGraph::Vertex::stackSize ( ) const
pure virtual
void g2o::OptimizableGraph::Vertex::unlockQuadraticForm ( )
inline

unlock the block of the hessian and the b vector associated with this vertex

Definition at line 337 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::updateCache ( )
virtual

Definition at line 77 of file optimizable_graph.cpp.

const Data* g2o::OptimizableGraph::Vertex::userData ( ) const
inline

the user data associated with this vertex

Definition at line 137 of file optimizable_graph.h.

Data* g2o::OptimizableGraph::Vertex::userData ( )
inline

Definition at line 138 of file optimizable_graph.h.

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

write the vertex to a stream

Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.

Friends And Related Function Documentation

friend struct OptimizableGraph
friend

Definition at line 129 of file optimizable_graph.h.

Member Data Documentation

CacheContainer* g2o::OptimizableGraph::Vertex::_cacheContainer
protected

Definition at line 357 of file optimizable_graph.h.

int g2o::OptimizableGraph::Vertex::_colInHessian
protected

Definition at line 354 of file optimizable_graph.h.

int g2o::OptimizableGraph::Vertex::_dimension
protected

Definition at line 353 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::_fixed
protected

Definition at line 351 of file optimizable_graph.h.

OptimizableGraph* g2o::OptimizableGraph::Vertex::_graph
protected

Definition at line 348 of file optimizable_graph.h.

int g2o::OptimizableGraph::Vertex::_hessianIndex
protected

Definition at line 350 of file optimizable_graph.h.

bool g2o::OptimizableGraph::Vertex::_marginalized
protected

Definition at line 352 of file optimizable_graph.h.

OpenMPMutex g2o::OptimizableGraph::Vertex::_quadraticFormMutex
protected

Definition at line 355 of file optimizable_graph.h.

Data* g2o::OptimizableGraph::Vertex::_userData
protected

Definition at line 349 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