g2o
Loading...
Searching...
No Matches
Public Member Functions | Public Attributes | List of all members
g2o::VertexPointXY Class Reference

#include <vertex_point_xy.h>

Inheritance diagram for g2o::VertexPointXY:
Inheritance graph
[legend]
Collaboration diagram for g2o::VertexPointXY:
Collaboration graph
[legend]

Public Member Functions

 VertexPointXY ()
 
virtual void setToOriginImpl ()
 sets the node to the origin (used in the multilevel stuff)
 
virtual bool setEstimateDataImpl (const double *est)
 
virtual bool getEstimateData (double *est) const
 
virtual int estimateDimension () const
 
virtual bool setMinimalEstimateDataImpl (const double *est)
 
virtual bool getMinimalEstimateData (double *est) const
 
virtual int minimalEstimateDimension () const
 
virtual void oplusImpl (const double *update)
 
virtual bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream
 
- Public Member Functions inherited from g2o::BaseVertex< 2, Vector2 >
 BaseVertex ()
 
 BaseVertex (const BaseVertex &)=delete
 
BaseVertexoperator= (const BaseVertex &)=delete
 
virtual const double & hessian (int i, int j) const
 get the element from the hessian matrix
 
virtual double & hessian (int i, int j)
 
virtual double hessianDeterminant () const
 
virtual double * hessianData ()
 
virtual void mapHessianMemory (double *d)
 
virtual int copyB (double *b_) const
 
virtual const double & b (int i) const
 get the b vector element
 
virtual double & b (int i)
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b ()
 return right hand side b of the constructed linear system
 
const Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b () const
 
virtual double * bData ()
 return a pointer to the b vector associated with this vertex
 
virtual void clearQuadraticForm ()
 
virtual double solveDirect (double lambda=0)
 
HessianBlockTypeA ()
 return the hessian block associated with the vertex
 
const HessianBlockTypeA () const
 
virtual void push ()
 backup the position of the vertex to a stack
 
virtual void pop ()
 
virtual void discardTop ()
 
virtual int stackSize () const
 return the stack size
 
const EstimateTypeestimate () const
 return the current estimate of the vertex
 
void setEstimate (const EstimateType &et)
 set the estimate for the vertex also calls updateCache()
 
- Public Member Functions inherited from g2o::OptimizableGraph::Vertex
 Vertex ()
 
virtual ~Vertex ()
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff)
 
bool setEstimateData (const double *estimate)
 
bool setEstimateData (const std::vector< double > &estimate)
 
template<typename Derived >
bool setEstimateData (const Eigen::MatrixBase< Derived > &estimate)
 
virtual bool getEstimateData (std::vector< double > &estimate) const
 
template<typename Derived >
bool getEstimateData (Eigen::MatrixBase< Derived > &estimate) const
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
template<typename Derived >
bool setMinimalEstimateData (const Eigen::MatrixBase< Derived > &estimate)
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) const
 
template<typename Derived >
bool getMinimalEstimateData (Eigen::MatrixBase< Derived > &estimate) const
 
void oplus (const double *v)
 
int hessianIndex () const
 
int G2O_ATTRIBUTE_DEPRECATED (tempIndex() const)
 
void setHessianIndex (int ti)
 set the temporary index of the vertex in the parameter blocks
 
void G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti))
 
bool fixed () const
 true => this node is fixed during the optimization
 
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization
 
bool marginalized () const
 true => this node is marginalized out during the optimization
 
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization
 
int dimension () const
 dimension of the estimated state belonging to this node
 
virtual void setId (int id)
 
void setColInHessian (int c)
 set the row of this vertex in the Hessian
 
int colInHessian () const
 get the row of this vertex in the Hessian
 
const OptimizableGraphgraph () const
 
OptimizableGraphgraph ()
 
void lockQuadraticForm ()
 
void unlockQuadraticForm ()
 
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
 
int id () const
 returns the id
 
const EdgeSetedges () const
 returns the set of hyper-edges that are leaving/entering in this vertex
 
EdgeSetedges ()
 returns the set of hyper-edges that are leaving/entering in this vertex
 
virtual HyperGraphElementType elementType () const
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex
 
DatauserData ()
 
void setUserData (Data *obs)
 
void addUserData (Data *obs)
 

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
 

Additional Inherited Members

- Public Types inherited from g2o::BaseVertex< 2, Vector2 >
using EstimateType = Vector2
 
using BackupStackType = std::stack< EstimateType, std::vector< EstimateType > >
 
using HessianBlockType = Eigen::Map< Eigen::Matrix< double, D, D, Eigen::ColMajor >, Eigen::Matrix< double, D, D, Eigen::ColMajor >::Flags &Eigen::PacketAccessBit ? Eigen::Aligned :Eigen::Unaligned >
 
- Static Public Attributes inherited from g2o::BaseVertex< 2, Vector2 >
static const int Dimension
 dimension of the estimate (minimal) in the manifold space
 
- Protected Attributes inherited from g2o::BaseVertex< 2, Vector2 >
HessianBlockType _hessian
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > _b
 
EstimateType _estimate
 
BackupStackType _backup
 
- Protected Attributes inherited from g2o::OptimizableGraph::Vertex
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
 

Detailed Description

Definition at line 39 of file vertex_point_xy.h.

Constructor & Destructor Documentation

◆ VertexPointXY()

g2o::VertexPointXY::VertexPointXY ( )

Definition at line 40 of file vertex_point_xy.cpp.

40 : BaseVertex<2, Vector2>() {
41 _estimate.setZero();
42}

References g2o::BaseVertex< 2, Vector2 >::_estimate.

Member Function Documentation

◆ estimateDimension()

virtual int g2o::VertexPointXY::estimateDimension ( ) const
inlinevirtual

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

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 58 of file vertex_point_xy.h.

58{ return 2; }

◆ getEstimateData()

virtual bool g2o::VertexPointXY::getEstimateData ( double *  estimate) const
inlinevirtual

writes the estimater to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 52 of file vertex_point_xy.h.

52 {
53 est[0] = _estimate[0];
54 est[1] = _estimate[1];
55 return true;
56 }

◆ getMinimalEstimateData()

virtual bool g2o::VertexPointXY::getMinimalEstimateData ( double *  estimate) const
inlinevirtual

writes the estimate to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 64 of file vertex_point_xy.h.

64 {
65 return getEstimateData(est);
66 }
virtual bool getEstimateData(double *est) const

◆ minimalEstimateDimension()

virtual int g2o::VertexPointXY::minimalEstimateDimension ( ) const
inlinevirtual

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

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 68 of file vertex_point_xy.h.

68{ return 2; }

◆ oplusImpl()

virtual void g2o::VertexPointXY::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 70 of file vertex_point_xy.h.

70 {
71 _estimate[0] += update[0];
72 _estimate[1] += update[1];
73 }

◆ read()

bool g2o::VertexPointXY::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 44 of file vertex_point_xy.cpp.

44 {
46}
bool readVector(std::istream &is, Eigen::DenseBase< Derived > &b)
Definition io_helper.h:42

References g2o::BaseVertex< 2, Vector2 >::_estimate, and g2o::internal::readVector().

◆ setEstimateDataImpl()

virtual bool g2o::VertexPointXY::setEstimateDataImpl ( const double *  )
inlinevirtual

writes the estimater to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 46 of file vertex_point_xy.h.

46 {
47 _estimate[0] = est[0];
48 _estimate[1] = est[1];
49 return true;
50 }

◆ setMinimalEstimateDataImpl()

virtual bool g2o::VertexPointXY::setMinimalEstimateDataImpl ( const double *  )
inlinevirtual

sets the initial estimate from an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 60 of file vertex_point_xy.h.

60 {
61 return setEstimateData(est);
62 }
bool setEstimateData(const double *estimate)

◆ setToOriginImpl()

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

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 44 of file vertex_point_xy.h.

44{ _estimate.setZero(); }

◆ write()

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

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Definition at line 48 of file vertex_point_xy.cpp.

48 {
49 return internal::writeVector(os, estimate());
50}
const EstimateType & estimate() const
return the current estimate of the vertex
bool writeVector(std::ostream &os, const Eigen::DenseBase< Derived > &b)
Definition io_helper.h:36

References g2o::BaseVertex< 2, Vector2 >::estimate(), and g2o::internal::writeVector().

Member Data Documentation

◆ EIGEN_MAKE_ALIGNED_OPERATOR_NEW

g2o::VertexPointXY::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 41 of file vertex_point_xy.h.


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