Templatized BaseVertex. More...
#include <base_vertex.h>
Public Types | |
typedef std::stack< EstimateType, std::vector< EstimateType, Eigen::aligned_allocator< EstimateType > > > | BackupStackType |
typedef T | EstimateType |
typedef Eigen::Map< Matrix< double, D, D >, Matrix< double, D, D >::Flags &PacketAccessBit?Aligned:Unaligned > | HessianBlockType |
Public Member Functions | |
HessianBlockType & | A () |
return the hessian block associated with the vertex More... | |
const HessianBlockType & | A () const |
virtual const double & | b (int i) const |
get the b vector element More... | |
virtual double & | b (int i) |
Matrix< double, D, 1 > & | b () |
return right hand side b of the constructed linear system More... | |
const Matrix< double, D, 1 > & | b () const |
BaseVertex () | |
virtual double * | bData () |
return a pointer to the b vector associated with this vertex More... | |
virtual void | clearQuadraticForm () |
virtual int | copyB (double *b_) const |
virtual void | discardTop () |
pop the last element from the stack, without restoring the current estimate More... | |
const EstimateType & | estimate () const |
return the current estimate of the vertex More... | |
virtual const double & | hessian (int i, int j) const |
get the element from the hessian matrix More... | |
virtual double & | hessian (int i, int j) |
virtual double * | hessianData () |
virtual double | hessianDeterminant () const |
virtual void | mapHessianMemory (double *d) |
virtual void | pop () |
restore the position of the vertex by retrieving the position from the stack More... | |
virtual void | push () |
backup the position of the vertex to a stack More... | |
void | setEstimate (const EstimateType &et) |
set the estimate for the vertex also calls updateCache() More... | |
virtual double | solveDirect (double lambda=0) |
virtual int | stackSize () const |
return the stack size More... | |
Public Member Functions inherited from g2o::OptimizableGraph::Vertex | |
void | addUserData (Data *obs) |
CacheContainer * | cacheContainer () |
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... | |
int | dimension () const |
dimension of the estimated state belonging to this node 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 () |
int | hessianIndex () const |
temporary index of this node in the parameter vector obtained from linearization More... | |
void | lockQuadraticForm () |
bool | marginalized () const |
true => this node is marginalized out during the optimization More... | |
virtual int | minimalEstimateDimension () const |
void | oplus (const double *v) |
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) |
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 () |
Static Public Attributes | |
static const int | Dimension = D |
dimension of the estimate (minimal) in the manifold space More... | |
Protected Attributes | |
Matrix< double, D, 1 > | _b |
BackupStackType | _backup |
EstimateType | _estimate |
HessianBlockType | _hessian |
Protected Attributes inherited from g2o::OptimizableGraph::Vertex | |
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 |
Additional Inherited Members | |
Protected Member Functions inherited from g2o::OptimizableGraph::Vertex | |
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... | |
Templatized BaseVertex.
Templatized BaseVertex D : minimal dimension of the vertex, e.g., 3 for rotation in 3D T : internal type to represent the estimate, e.g., Quaternion for rotation in 3D
Definition at line 53 of file base_vertex.h.
typedef std::stack<EstimateType, std::vector<EstimateType, Eigen::aligned_allocator<EstimateType> > > g2o::BaseVertex< D, T >::BackupStackType |
Definition at line 58 of file base_vertex.h.
typedef T g2o::BaseVertex< D, T >::EstimateType |
Definition at line 55 of file base_vertex.h.
typedef Eigen::Map<Matrix<double, D, D>, Matrix<double,D,D>::Flags & PacketAccessBit ? Aligned : Unaligned > g2o::BaseVertex< D, T >::HessianBlockType |
Definition at line 62 of file base_vertex.h.
BaseVertex::BaseVertex | ( | ) |
Definition at line 29 of file base_vertex.h.
|
inline |
return the hessian block associated with the vertex
Definition at line 93 of file base_vertex.h.
|
inline |
Definition at line 94 of file base_vertex.h.
|
inlinevirtual |
get the b vector element
Implements g2o::OptimizableGraph::Vertex.
Definition at line 79 of file base_vertex.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 80 of file base_vertex.h.
|
inline |
return right hand side b of the constructed linear system
Definition at line 90 of file base_vertex.h.
|
inline |
Definition at line 91 of file base_vertex.h.
|
inlinevirtual |
return a pointer to the b vector associated with this vertex
Implements g2o::OptimizableGraph::Vertex.
Definition at line 81 of file base_vertex.h.
|
virtual |
set the b vector part of this vertex to zero
Implements g2o::OptimizableGraph::Vertex.
Definition at line 48 of file base_vertex.h.
|
inlinevirtual |
copies the b vector in the array b_
Implements g2o::OptimizableGraph::Vertex.
Definition at line 74 of file base_vertex.h.
|
inlinevirtual |
pop the last element from the stack, without restoring the current estimate
Implements g2o::OptimizableGraph::Vertex.
Definition at line 98 of file base_vertex.h.
|
inline |
return the current estimate of the vertex
Definition at line 102 of file base_vertex.h.
|
inlinevirtual |
get the element from the hessian matrix
Implements g2o::OptimizableGraph::Vertex.
Definition at line 67 of file base_vertex.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 68 of file base_vertex.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 70 of file base_vertex.h.
|
inlinevirtual |
Implements g2o::OptimizableGraph::Vertex.
Definition at line 69 of file base_vertex.h.
|
virtual |
maps the internal matrix to some external memory location
Implements g2o::OptimizableGraph::Vertex.
Definition at line 53 of file base_vertex.h.
|
inlinevirtual |
restore the position of the vertex by retrieving the position from the stack
Implements g2o::OptimizableGraph::Vertex.
Definition at line 97 of file base_vertex.h.
|
inlinevirtual |
backup the position of the vertex to a stack
Implements g2o::OptimizableGraph::Vertex.
Definition at line 96 of file base_vertex.h.
|
inline |
set the estimate for the vertex also calls updateCache()
Definition at line 104 of file base_vertex.h.
|
virtual |
updates the current vertex with the direct solution x += H_ii
Implements g2o::OptimizableGraph::Vertex.
Definition at line 37 of file base_vertex.h.
|
inlinevirtual |
return the stack size
Implements g2o::OptimizableGraph::Vertex.
Definition at line 99 of file base_vertex.h.
|
protected |
Definition at line 108 of file base_vertex.h.
|
protected |
Definition at line 110 of file base_vertex.h.
|
protected |
Definition at line 109 of file base_vertex.h.
|
protected |
Definition at line 107 of file base_vertex.h.
|
static |
dimension of the estimate (minimal) in the manifold space
Definition at line 60 of file base_vertex.h.