A general case Vertex for optimization. More...
#include <optimizable_graph.h>
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... | |
CacheContainer * | cacheContainer () |
virtual void | clearQuadraticForm ()=0 |
virtual Vertex * | clone () 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 OptimizableGraph * | graph () const |
OptimizableGraph * | graph () |
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 Data * | userData () const |
the user data associated with this vertex More... | |
Data * | userData () |
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 EdgeSet & | edges () const |
returns the set of hyper-edges that are leaving/entering in this vertex More... | |
EdgeSet & | edges () |
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 |
A general case Vertex for optimization.
Definition at line 127 of file optimizable_graph.h.
g2o::OptimizableGraph::Vertex::Vertex | ( | ) |
Definition at line 63 of file optimizable_graph.cpp.
|
virtual |
Reimplemented from g2o::HyperGraph::Vertex.
Definition at line 84 of file optimizable_graph.cpp.
|
inline |
Definition at line 141 of file optimizable_graph.h.
|
pure virtual |
get the b vector element
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.
|
pure virtual |
|
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.
|
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 >.
|
virtual |
returns a deep copy of the current vertex
Definition at line 92 of file optimizable_graph.cpp.
|
inline |
get the row of this vertex in the Hessian
Definition at line 323 of file optimizable_graph.h.
|
pure virtual |
copies the b vector in the array b_
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.
|
inline |
dimension of the estimated state belonging to this node
Definition at line 315 of file optimizable_graph.h.
|
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 >.
|
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.
|
inline |
true => this node is fixed during the optimization
Definition at line 305 of file optimizable_graph.h.
|
inline |
Definition at line 299 of file optimizable_graph.h.
|
inline |
Definition at line 302 of file optimizable_graph.h.
|
virtual |
writes the estimater to an array of double
Definition at line 104 of file optimizable_graph.cpp.
|
inlinevirtual |
writes the estimater to an array of double
Definition at line 215 of file optimizable_graph.h.
|
virtual |
writes the estimate to an array of double
Definition at line 121 of file optimizable_graph.cpp.
|
inlinevirtual |
writes the estimate to an array of double
Definition at line 259 of file optimizable_graph.h.
|
inline |
Definition at line 325 of file optimizable_graph.h.
|
inline |
Definition at line 327 of file optimizable_graph.h.
|
pure virtual |
get the element from the hessian matrix
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.
|
pure virtual |
|
pure virtual |
|
pure virtual |
|
inline |
temporary index of this node in the parameter vector obtained from linearization
Definition at line 298 of file optimizable_graph.h.
|
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.
|
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 >.
|
inline |
true => this node is marginalized out during the optimization
Definition at line 310 of file optimizable_graph.h.
|
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.
|
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.
|
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.
|
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 >.
|
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 >.
|
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.
|
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()
Definition at line 97 of file optimizable_graph.cpp.
|
inline |
sets the initial estimate from an array of double Implement setEstimateDataImpl()
Definition at line 197 of file optimizable_graph.h.
|
inlineprotectedvirtual |
writes the estimater to an array of double
Definition at line 372 of file optimizable_graph.h.
|
inline |
true => this node should be considered fixed during the optimization
Definition at line 307 of file optimizable_graph.h.
|
inline |
set the temporary index of the vertex in the parameter blocks
Definition at line 301 of file optimizable_graph.h.
|
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.
|
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()
Definition at line 114 of file optimizable_graph.cpp.
|
inline |
sets the initial estimate from an array of double. Implement setMinimalEstimateDataImpl()
Definition at line 241 of file optimizable_graph.h.
|
inlineprotectedvirtual |
sets the initial estimate from an array of double
Definition at line 378 of file optimizable_graph.h.
|
inline |
sets the node to the origin (used in the multilevel stuff)
Definition at line 151 of file optimizable_graph.h.
|
protectedpure virtual |
sets the node to the origin (used in the multilevel stuff)
Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.
|
inline |
Definition at line 140 of file optimizable_graph.h.
|
pure virtual |
updates the current vertex with the direct solution x += H_ii
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.
|
pure virtual |
return the stack size
Implemented in g2o::BaseVertex< D, T >, g2o::BaseVertex< 7, Sim3 >, g2o::BaseVertex< 3, Vector3d >, and g2o::BaseVertex< 6, SE3Quat >.
|
inline |
unlock the block of the hessian and the b vector associated with this vertex
Definition at line 337 of file optimizable_graph.h.
|
virtual |
Definition at line 77 of file optimizable_graph.cpp.
|
inline |
the user data associated with this vertex
Definition at line 137 of file optimizable_graph.h.
|
inline |
Definition at line 138 of file optimizable_graph.h.
|
pure virtual |
write the vertex to a stream
Implemented in g2o::VertexSE3Expmap, g2o::VertexSim3Expmap, and g2o::VertexSBAPointXYZ.
|
friend |
Definition at line 129 of file optimizable_graph.h.
|
protected |
Definition at line 357 of file optimizable_graph.h.
|
protected |
Definition at line 354 of file optimizable_graph.h.
|
protected |
Definition at line 353 of file optimizable_graph.h.
|
protected |
Definition at line 351 of file optimizable_graph.h.
|
protected |
Definition at line 348 of file optimizable_graph.h.
|
protected |
Definition at line 350 of file optimizable_graph.h.
|
protected |
Definition at line 352 of file optimizable_graph.h.
|
protected |
Definition at line 355 of file optimizable_graph.h.
|
protected |
Definition at line 349 of file optimizable_graph.h.