g2o
Public Member Functions | Public Attributes | List of all members
g2o::tutorial::VertexPointXY Class Reference

#include <vertex_point_xy.h>

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

Public Member Functions

 VertexPointXY ()
 
virtual void setToOriginImpl ()
 sets the node to the origin (used in the multilevel stuff) More...
 
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 More...
 
virtual bool write (std::ostream &os) const
 write the vertex to a stream More...
 
- Public Member Functions inherited from g2o::BaseVertex< 2, Eigen::Vector2d >
 BaseVertex ()
 
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 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 More...
 
virtual double & b (int i)
 
Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b ()
 return right hand side b of the constructed linear system More...
 
const Eigen::Matrix< double, D, 1, Eigen::ColMajor > & b () const
 
virtual double * bData ()
 return a pointer to the b vector associated with this vertex More...
 
virtual void clearQuadraticForm ()
 
virtual double solveDirect (double lambda=0)
 
HessianBlockTypeA ()
 return the hessian block associated with the vertex More...
 
const HessianBlockTypeA () const
 
virtual void push ()
 backup the position of the vertex to a stack More...
 
virtual void pop ()
 restore the position of the vertex by retrieving the position from the stack More...
 
virtual void discardTop ()
 pop the last element from the stack, without restoring the current estimate More...
 
virtual int stackSize () const
 return the stack size More...
 
const EstimateTypeestimate () const
 return the current estimate of the vertex More...
 
void setEstimate (const EstimateType &et)
 set the estimate for the vertex also calls updateCache() More...
 
- Public Member Functions inherited from g2o::OptimizableGraph::Vertex
 Vertex ()
 
virtual Vertexclone () const
 returns a deep copy of the current vertex More...
 
virtual ~Vertex ()
 
void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff) More...
 
bool setEstimateData (const double *estimate)
 
bool setEstimateData (const std::vector< double > &estimate)
 
virtual bool getEstimateData (double *estimate) const
 
virtual bool getEstimateData (std::vector< double > &estimate) const
 
virtual int estimateDimension () const
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
virtual bool getMinimalEstimateData (double *estimate) const
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) const
 
virtual int minimalEstimateDimension () const
 
void oplus (const double *v)
 
int hessianIndex () const
 temporary index of this node in the parameter vector obtained from linearization More...
 
int G2O_ATTRIBUTE_DEPRECATED (tempIndex() const)
 
void setHessianIndex (int ti)
 set the temporary index of the vertex in the parameter blocks More...
 
void G2O_ATTRIBUTE_DEPRECATED (setTempIndex(int ti))
 
bool fixed () const
 true => this node is fixed during the optimization More...
 
void setFixed (bool fixed)
 true => this node should be considered fixed during the optimization More...
 
bool marginalized () const
 true => this node is marginalized out during the optimization More...
 
void setMarginalized (bool marginalized)
 true => this node should be marginalized out during the optimization More...
 
int dimension () const
 dimension of the estimated state belonging to this node 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 setColInHessian (int c)
 set the row of this vertex in the Hessian More...
 
int colInHessian () const
 get the row of this vertex in the Hessian More...
 
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 More...
 
int id () const
 returns the id More...
 
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
 
- Public Member Functions inherited from g2o::HyperGraph::HyperGraphElement
virtual ~HyperGraphElement ()
 
HyperGraphElementclone () const
 
- Public Member Functions inherited from g2o::HyperGraph::DataContainer
 DataContainer ()
 
virtual ~DataContainer ()
 
const DatauserData () const
 the user data associated with this vertex More...
 
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, Eigen::Vector2d >
typedef Eigen::Vector2d EstimateType
 
typedef std::stack< EstimateType, std::vector< EstimateType, Eigen::aligned_allocator< EstimateType > > > BackupStackType
 
typedef Eigen::Map< Eigen::Matrix< double, D, D, Eigen::ColMajor >, Eigen::Matrix< double, D, D, Eigen::ColMajor >::Flags &Eigen::AlignedBit?Eigen::Aligned:Eigen::Unaligned > HessianBlockType
 
- Static Public Attributes inherited from g2o::BaseVertex< 2, Eigen::Vector2d >
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< 2, Eigen::Vector2d >
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

g2o::tutorial::VertexPointXY::VertexPointXY ( )

Definition at line 34 of file vertex_point_xy.cpp.

References g2o::BaseVertex< 2, Eigen::Vector2d >::_estimate.

34  :
35  BaseVertex<2, Vector2d>()
36  {
37  _estimate.setZero();
38  }

Member Function Documentation

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

50  {
51  _estimate[0] += update[0];
52  _estimate[1] += update[1];
53  }
bool g2o::tutorial::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 40 of file vertex_point_xy.cpp.

References g2o::BaseVertex< 2, Eigen::Vector2d >::_estimate.

41  {
42  is >> _estimate[0] >> _estimate[1];
43  return true;
44  }
virtual void g2o::tutorial::VertexPointXY::setToOriginImpl ( )
inlinevirtual

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 45 of file vertex_point_xy.h.

45  {
46  _estimate.setZero();
47  }
bool g2o::tutorial::VertexPointXY::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Definition at line 46 of file vertex_point_xy.cpp.

References g2o::BaseVertex< 2, Eigen::Vector2d >::estimate().

47  {
48  os << estimate()(0) << " " << estimate()(1);
49  return os.good();
50  }
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99

Member Data Documentation

g2o::tutorial::VertexPointXY::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 42 of file vertex_point_xy.h.


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