Public Member Functions | List of all members
g2o::VertexSE3Expmap Class Reference

SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential map. More...

#include <types_six_dof_expmap.h>

Inheritance diagram for g2o::VertexSE3Expmap:
Inheritance graph
[legend]

Public Member Functions

virtual void oplusImpl (const double *update_)
 
bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex More...
 
virtual void setToOriginImpl ()
 sets the node to the origin (used in the multilevel stuff) More...
 
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSE3Expmap ()
 
bool write (std::ostream &os) const
 write the vertex to a stream More...
 
- Public Member Functions inherited from g2o::BaseVertex< 6, SE3Quat >
HessianBlockTypeA ()
 return the hessian block associated with the vertex More...
 
const HessianBlockTypeA () 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 EstimateTypeestimate () 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)
 
CacheContainercacheContainer ()
 
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...
 
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 OptimizableGraphgraph () const
 
OptimizableGraphgraph ()
 
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)
 
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 DatauserData () const
 the user data associated with this vertex More...
 
DatauserData ()
 
 Vertex ()
 
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 ()
 

Additional Inherited Members

- Public Types inherited from g2o::BaseVertex< 6, SE3Quat >
typedef std::stack< EstimateType, std::vector< EstimateType, Eigen::aligned_allocator< EstimateType > > > BackupStackType
 
typedef SE3Quat EstimateType
 
typedef Eigen::Map< Matrix< double, D, D >, Matrix< double, D, D >::Flags &PacketAccessBit?Aligned:Unaligned > HessianBlockType
 
- Static Public Attributes inherited from g2o::BaseVertex< 6, SE3Quat >
static const int Dimension
 dimension of the estimate (minimal) in the manifold space More...
 
- Protected Member Functions inherited from g2o::OptimizableGraph::Vertex
virtual bool setEstimateDataImpl (const double *)
 
virtual bool setMinimalEstimateDataImpl (const double *)
 
- Protected Attributes inherited from g2o::BaseVertex< 6, SE3Quat >
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
 

Detailed Description

SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential map.

Definition at line 59 of file types_six_dof_expmap.h.

Constructor & Destructor Documentation

g2o::VertexSE3Expmap::VertexSE3Expmap ( )

Definition at line 52 of file types_six_dof_expmap.cpp.

Member Function Documentation

virtual void g2o::VertexSE3Expmap::oplusImpl ( const double *  v)
inlinevirtual

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 73 of file types_six_dof_expmap.h.

bool g2o::VertexSE3Expmap::read ( std::istream &  is)
virtual

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 55 of file types_six_dof_expmap.cpp.

virtual void g2o::VertexSE3Expmap::setToOriginImpl ( )
inlinevirtual

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 69 of file types_six_dof_expmap.h.

bool g2o::VertexSE3Expmap::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Definition at line 65 of file types_six_dof_expmap.cpp.


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