Public Member Functions | Protected Attributes | Friends
g2o::OptimizableGraph::Vertex Class Reference

A general case Vertex for optimization. More...

#include <optimizable_graph.h>

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

List of all members.

Public Member Functions

virtual const double & b (int i) const =0
 get the b vector element
virtual double & b (int i)=0
virtual double * bData ()=0
 return a pointer to the b vector associated with this vertex
virtual void clearQuadraticForm ()=0
virtual Vertexclone () const
 returns a deep copy of the current vertex
int colInHessian () const
 get the row of this vertex in the Hessian
virtual int copyB (double *b_) const =0
int dimension () const
 dimension of the estimated state belonging to this node
virtual void discardTop ()=0
 pop the last element from the stack, without restoring the current estimate
virtual int estimateDimension () const
bool fixed () const
 true => this node is fixed during the optimization
virtual bool getEstimateData (double *estimate) const
virtual bool getMinimalEstimateData (double *estimate) const
const OptimizableGraphgraph () const
virtual const double & hessian (int i, int j) const =0
 get the element from the hessian matrix
virtual double & hessian (int i, int j)=0
virtual double * hessianData ()=0
virtual double hessianDeterminant () const =0
void lockQuadraticForm ()
virtual void mapHessianMemory (double *d)=0
bool marginalized () const
 true => this node is marginalized out during the optimization
virtual int minimalEstimateDimension () const
virtual void oplus (double *v)=0
 update the position of the node from the parameters in v
virtual void pop ()=0
 restore the position of the vertex by retrieving the position from the stack
virtual void push ()=0
 backup the position of the vertex to a stack
virtual bool read (std::istream &is)=0
 read the vertex from a stream, i.e., the internal state of the vertex
void setColInHessian (int c)
 set the row of this vertex in the Hessian
virtual bool setEstimateData (const double *estimate)
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization
void setId (int id)
 sets the id of the node in the graph be sure that the graph keeps consistent after changing the id
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization
virtual bool setMinimalEstimateData (const double *estimate)
void setTempIndex (int ti)
 set the temporary index of the vertex in the parameter blocks
virtual void setToOrigin ()=0
 sets the node to the origin (used in the multilevel stuff)
virtual void setUncertainty (double *c)=0
 sets the covariance/information of the node, used internally
void setUserData (Data *obs)
virtual double solveDirect (double lambda=0)=0
virtual int stackSize () const =0
 return the stack size
int tempIndex () const
 temporary index of this node in the parameter vector obtained from linearization
virtual double * uncertaintyData ()=0
 return the pointer to the uncertainty (marginal covariance)
void unlockQuadraticForm ()
const DatauserData () const
 the user data associated with this vertex
DatauserData ()
 Vertex ()
virtual bool write (std::ostream &os) const =0
 write the vertex to a stream
virtual ~Vertex ()

Protected Attributes

int _colInHessian
int _dimension
bool _fixed
OptimizableGraph_graph
bool _marginalized
OpenMPMutex _quadraticFormMutex
int _tempIndex
Data_userData

Friends

struct OptimizableGraph

Detailed Description

A general case Vertex for optimization.

Definition at line 100 of file optimizable_graph.h.


Constructor & Destructor Documentation

Definition at line 39 of file optimizable_graph.cpp.

Reimplemented from g2o::HyperGraph::Vertex.

Definition at line 47 of file optimizable_graph.cpp.


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]
virtual void g2o::OptimizableGraph::Vertex::clearQuadraticForm ( ) [pure virtual]

returns a deep copy of the current vertex

Definition at line 52 of file optimizable_graph.cpp.

get the row of this vertex in the Hessian

Definition at line 228 of file optimizable_graph.h.

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

dimension of the estimated state belonging to this node

Definition at line 220 of file optimizable_graph.h.

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

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

Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.

Definition at line 68 of file optimizable_graph.cpp.

true => this node is fixed during the optimization

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

Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.

Definition at line 63 of file optimizable_graph.cpp.

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

writes the estimater to an array of double

Returns:
true on success

Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.

Definition at line 78 of file optimizable_graph.cpp.

Definition at line 230 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]

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 241 of file optimizable_graph.h.

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

true => this node is marginalized out during the optimization

Definition at line 215 of file optimizable_graph.h.

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

Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.

Definition at line 83 of file optimizable_graph.cpp.

virtual void g2o::OptimizableGraph::Vertex::oplus ( double *  v) [pure 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]

set the row of this vertex in the Hessian

Definition at line 226 of file optimizable_graph.h.

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

sets the initial estimate from an array of double

Returns:
true on success

Reimplemented in g2o::VertexSE2, g2o::VertexSE3, and g2o::VertexPointXY.

Definition at line 58 of file optimizable_graph.cpp.

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

Definition at line 212 of file optimizable_graph.h.

void g2o::OptimizableGraph::Vertex::setId ( int  id) [inline]

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

Definition at line 223 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 217 of file optimizable_graph.h.

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

sets the initial estimate from an array of double

Returns:
true on success

Reimplemented in g2o::VertexSE3, g2o::VertexSE2, and g2o::VertexPointXY.

Definition at line 73 of file optimizable_graph.cpp.

set the temporary index of the vertex in the parameter blocks

Definition at line 207 of file optimizable_graph.h.

virtual void g2o::OptimizableGraph::Vertex::setToOrigin ( ) [pure virtual]
virtual void g2o::OptimizableGraph::Vertex::setUncertainty ( double *  c) [pure virtual]

Definition at line 113 of file optimizable_graph.h.

virtual double g2o::OptimizableGraph::Vertex::solveDirect ( double  lambda = 0) [pure virtual]
virtual int g2o::OptimizableGraph::Vertex::stackSize ( ) const [pure virtual]

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

Definition at line 205 of file optimizable_graph.h.

virtual double* g2o::OptimizableGraph::Vertex::uncertaintyData ( ) [pure virtual]

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

Definition at line 245 of file optimizable_graph.h.

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

the user data associated with this vertex

Definition at line 110 of file optimizable_graph.h.

Definition at line 111 of file optimizable_graph.h.

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

Friends And Related Function Documentation

friend struct OptimizableGraph [friend]

Definition at line 102 of file optimizable_graph.h.


Member Data Documentation

Definition at line 259 of file optimizable_graph.h.

Definition at line 258 of file optimizable_graph.h.

Definition at line 256 of file optimizable_graph.h.

Definition at line 253 of file optimizable_graph.h.

Definition at line 257 of file optimizable_graph.h.

Definition at line 260 of file optimizable_graph.h.

Definition at line 255 of file optimizable_graph.h.

Definition at line 254 of file optimizable_graph.h.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:30