g2o
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]
Collaboration diagram for g2o::OptimizableGraph::Vertex:
Collaboration graph
[legend]

Public Member Functions

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

Protected Member Functions

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

Protected Attributes

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

Friends

struct OptimizableGraph
 

Detailed Description

A general case Vertex for optimization.

Definition at line 107 of file optimizable_graph.h.

Constructor & Destructor Documentation

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

Reimplemented from g2o::HyperGraph::Vertex.

Definition at line 74 of file optimizable_graph.cpp.

References _cacheContainer, and _userData.

75  {
76  delete _cacheContainer;
77  delete _userData;
78  }

Member Function Documentation

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
CacheContainer * g2o::OptimizableGraph::Vertex::cacheContainer ( )
virtual void g2o::OptimizableGraph::Vertex::clearQuadraticForm ( )
pure virtual
OptimizableGraph::Vertex * g2o::OptimizableGraph::Vertex::clone ( ) const
virtual

returns a deep copy of the current vertex

Definition at line 80 of file optimizable_graph.cpp.

Referenced by g2o::OptimizableGraph::addGraph(), and main().

81  {
82  return 0;
83  }
int g2o::OptimizableGraph::Vertex::colInHessian ( ) const
inline
virtual int g2o::OptimizableGraph::Vertex::copyB ( double *  b_) const
pure virtual
int g2o::OptimizableGraph::Vertex::dimension ( ) const
inline
virtual void g2o::OptimizableGraph::Vertex::discardTop ( )
pure virtual
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

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexSE2, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.

Definition at line 97 of file optimizable_graph.cpp.

Referenced by g2o::SparseOptimizer::initializeOptimization().

98  {
99  return -1;
100  }
bool g2o::OptimizableGraph::Vertex::fixed ( ) const
inline
int g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( tempIndex()  const)
inline

Definition at line 267 of file optimizable_graph.h.

267 { return hessianIndex();}
int hessianIndex() const
temporary index of this node in the parameter vector obtained from linearization
void g2o::OptimizableGraph::Vertex::G2O_ATTRIBUTE_DEPRECATED ( setTempIndex(int ti)  )
inline

Definition at line 270 of file optimizable_graph.h.

270 { setHessianIndex(ti);}
void setHessianIndex(int ti)
set the temporary index of the vertex in the parameter blocks
bool g2o::OptimizableGraph::Vertex::getEstimateData ( double *  estimate) const
virtual

writes the estimater to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexSE2, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.

Definition at line 92 of file optimizable_graph.cpp.

Referenced by g2o::SparseOptimizer::initializeOptimization().

93  {
94  return false;
95  }
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 183 of file optimizable_graph.h.

183  {
184  int dim = estimateDimension();
185  if (dim < 0)
186  return false;
187  estimate.resize(dim);
188  return getEstimateData(&estimate[0]);
189  };
virtual bool getEstimateData(double *estimate) const
virtual int estimateDimension() const
bool g2o::OptimizableGraph::Vertex::getMinimalEstimateData ( double *  estimate) const
virtual

writes the estimate to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexSE2, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexPointXY.

Definition at line 109 of file optimizable_graph.cpp.

Referenced by testMarginals().

110  {
111  return false;
112  }
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 227 of file optimizable_graph.h.

227  {
228  int dim = minimalEstimateDimension();
229  if (dim < 0)
230  return false;
231  estimate.resize(dim);
232  return getMinimalEstimateData(&estimate[0]);
233  };
virtual int minimalEstimateDimension() const
virtual bool getMinimalEstimateData(double *estimate) const
const OptimizableGraph* g2o::OptimizableGraph::Vertex::graph ( ) const
inline
OptimizableGraph* g2o::OptimizableGraph::Vertex::graph ( )
inline

Definition at line 294 of file optimizable_graph.h.

294 {return _graph;}
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
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 300 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::mapHessianMemory ( double *  d)
pure virtual
bool g2o::OptimizableGraph::Vertex::marginalized ( ) const
inline
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

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::deprecated::VertexPointXYZ, g2o::VertexLine2D, g2o::VertexSE2, g2o::VertexPointXYZ, g2o::VertexSegment2D, and g2o::VertexPointXY.

Definition at line 114 of file optimizable_graph.cpp.

Referenced by g2o::EdgeLabeler::labelEdge(), and testMarginals().

115  {
116  return -1;
117  }
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 259 of file optimizable_graph.h.

Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), g2o::EdgeLabeler::labelEdge(), g2o::SparseOptimizer::optimize(), and testMarginals().

260  {
261  oplusImpl(v);
262  updateCache();
263  }
virtual void oplusImpl(const double *v)=0
virtual void g2o::OptimizableGraph::Vertex::oplusImpl ( const double *  v)
protectedpure virtual
virtual void g2o::OptimizableGraph::Vertex::pop ( )
pure virtual
virtual void g2o::OptimizableGraph::Vertex::push ( )
pure virtual
virtual bool g2o::OptimizableGraph::Vertex::read ( std::istream &  is)
pure virtual
void g2o::OptimizableGraph::Vertex::setColInHessian ( int  c)
inline

set the row of this vertex in the Hessian

Definition at line 289 of file optimizable_graph.h.

Referenced by g2o::BlockSolver< Traits >::buildStructure(), and g2o::BlockSolver< Traits >::updateStructure().

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 85 of file optimizable_graph.cpp.

References setEstimateDataImpl(), and updateCache().

86  {
87  bool ret = setEstimateDataImpl(v);
88  updateCache();
89  return ret;
90  }
virtual bool setEstimateDataImpl(const double *)
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 165 of file optimizable_graph.h.

165  {
166 #ifndef NDEBUG
167  int dim = estimateDimension();
168  assert((dim == -1) || (estimate.size() == std::size_t(dim)));
169 #endif
170  return setEstimateData(&estimate[0]);
171  };
virtual int estimateDimension() const
bool setEstimateData(const double *estimate)
virtual bool g2o::OptimizableGraph::Vertex::setEstimateDataImpl ( const double *  )
inlineprotectedvirtual

writes the estimater to an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::VertexSE2, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::deprecated::VertexPointXYZ, g2o::VertexPlane, g2o::VertexSegment2D, g2o::VertexPointXYZ, g2o::VertexLine3D, and g2o::VertexPointXY.

Definition at line 339 of file optimizable_graph.h.

Referenced by setEstimateData().

339 { return false;}
void g2o::OptimizableGraph::Vertex::setFixed ( bool  fixed)
inline

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

Definition at line 275 of file optimizable_graph.h.

Referenced by g2o::StructureOnlySolver< PointDoF >::calc(), MainWindow::fixGraph(), g2o::G2oSlamInterface::fixNode(), g2o::Star::labelStarEdges(), main(), and g2o::OptimizableGraph::setFixed().

275 { _fixed = fixed;}
bool fixed() const
true => this node is fixed during the optimization
void g2o::OptimizableGraph::Vertex::setHessianIndex ( int  ti)
inline
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 286 of file optimizable_graph.h.

Referenced by g2o::G2oSlamInterface::addVertex(), main(), Robot::move(), PlaneItem::PlaneItem(), g2o::Gm2dlIO::readGm2dl(), and g2o::OptimizableGraph::setFixed().

286 {_id = id;}
int id() const
returns the id
Definition: hyper_graph.h:148
void g2o::OptimizableGraph::Vertex::setMarginalized ( bool  marginalized)
inline

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

Definition at line 280 of file optimizable_graph.h.

Referenced by main(), and MainWindow::prepare().

bool marginalized() const
true => this node is marginalized out during the optimization
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 102 of file optimizable_graph.cpp.

References setMinimalEstimateDataImpl(), and updateCache().

103  {
104  bool ret = setMinimalEstimateDataImpl(v);
105  updateCache();
106  return ret;
107  }
virtual bool setMinimalEstimateDataImpl(const double *)
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 209 of file optimizable_graph.h.

209  {
210 #ifndef NDEBUG
211  int dim = minimalEstimateDimension();
212  assert((dim == -1) || (estimate.size() == std::size_t(dim)));
213 #endif
214  return setMinimalEstimateData(&estimate[0]);
215  };
bool setMinimalEstimateData(const double *estimate)
virtual int minimalEstimateDimension() const
virtual bool g2o::OptimizableGraph::Vertex::setMinimalEstimateDataImpl ( const double *  )
inlineprotectedvirtual

sets the initial estimate from an array of double

Returns
true on success

Reimplemented in g2o::VertexCam, g2o::VertexSE3, g2o::deprecated::VertexSE3, g2o::VertexLine2D, g2o::VertexSE2, g2o::deprecated::VertexPointXYZ, g2o::VertexSegment2D, g2o::VertexPointXYZ, and g2o::VertexPointXY.

Definition at line 345 of file optimizable_graph.h.

Referenced by setMinimalEstimateData().

345 { return false;}
void g2o::OptimizableGraph::Vertex::setToOrigin ( )
inline

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

Definition at line 119 of file optimizable_graph.h.

Referenced by g2o::SparseOptimizer::setToOrigin().

virtual void setToOriginImpl()=0
sets the node to the origin (used in the multilevel stuff)
virtual void g2o::OptimizableGraph::Vertex::setToOriginImpl ( )
protectedpure virtual
virtual double g2o::OptimizableGraph::Vertex::solveDirect ( double  lambda = 0)
pure virtual
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 304 of file optimizable_graph.h.

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

Friends And Related Function Documentation

friend struct OptimizableGraph
friend

Definition at line 109 of file optimizable_graph.h.

Member Data Documentation

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

Definition at line 324 of file optimizable_graph.h.

Referenced by cacheContainer(), updateCache(), and ~Vertex().

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

Definition at line 321 of file optimizable_graph.h.

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

Definition at line 320 of file optimizable_graph.h.

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

Definition at line 318 of file optimizable_graph.h.

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

Definition at line 315 of file optimizable_graph.h.

Referenced by g2o::OptimizableGraph::addVertex().

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

Definition at line 317 of file optimizable_graph.h.

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

Definition at line 319 of file optimizable_graph.h.

Referenced by g2o::VertexSim3Expmap::VertexSim3Expmap().

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

Definition at line 322 of file optimizable_graph.h.

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

Definition at line 316 of file optimizable_graph.h.

Referenced by ~Vertex().


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