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

2D pose Vertex, (x,y,theta) More...

#include <vertex_se2.h>

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

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSE2 ()
 
virtual void setToOriginImpl ()
 sets the node to the origin (used in the multilevel stuff) More...
 
virtual void oplusImpl (const double *update)
 
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 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< 3, SE2 >
 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 (std::vector< double > &estimate) const
 
bool setMinimalEstimateData (const double *estimate)
 
bool setMinimalEstimateData (const std::vector< double > &estimate)
 
virtual bool getMinimalEstimateData (std::vector< double > &estimate) 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)
 

Additional Inherited Members

- Public Types inherited from g2o::BaseVertex< 3, SE2 >
typedef SE2 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< 3, SE2 >
static const int Dimension
 dimension of the estimate (minimal) in the manifold space More...
 
- Protected Attributes inherited from g2o::BaseVertex< 3, SE2 >
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

2D pose Vertex, (x,y,theta)

Definition at line 41 of file vertex_se2.h.

Constructor & Destructor Documentation

g2o::VertexSE2::VertexSE2 ( )

Definition at line 37 of file vertex_se2.cpp.

37  :
38  BaseVertex<3, SE2>()
39  {
40  }

Member Function Documentation

virtual int g2o::VertexSE2::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 71 of file vertex_se2.h.

71 { return 3; }
virtual bool g2o::VertexSE2::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 65 of file vertex_se2.h.

65  {
66  Eigen::Map<Vector3D> v(est);
67  v = _estimate.toVector();
68  return true;
69  }
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
virtual bool g2o::VertexSE2::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 77 of file vertex_se2.h.

77  {
78  return getEstimateData(est);
79  }
virtual bool getEstimateData(double *est) const
Definition: vertex_se2.h:65
virtual int g2o::VertexSE2::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 81 of file vertex_se2.h.

81 { return 3; }
virtual void g2o::VertexSE2::oplusImpl ( const double *  v)
inlinevirtual

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

Implements g2o::OptimizableGraph::Vertex.

Reimplemented in g2o::OnlineVertexSE2.

Definition at line 51 of file vertex_se2.h.

References g2o::normalize_theta().

Referenced by g2o::OnlineVertexSE2::oplusImpl().

52  {
54  t+=Eigen::Map<const Vector2D>(update);
55  double angle=normalize_theta(_estimate.rotation().angle() + update[2]);
57  _estimate.setRotation(Eigen::Rotation2Dd(angle));
58  }
Eigen::Matrix< double, 2, 1, Eigen::ColMajor > Vector2D
Definition: eigen_types.h:45
const Eigen::Rotation2Dd & rotation() const
rotational component
Definition: se2.h:58
double normalize_theta(double theta)
Definition: misc.h:94
const Vector2D & translation() const
translational component
Definition: se2.h:54
void setTranslation(const Vector2D &t_)
Definition: se2.h:55
void setRotation(const Eigen::Rotation2Dd &R_)
Definition: se2.h:59
bool g2o::VertexSE2::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 42 of file vertex_se2.cpp.

References g2o::BaseVertex< 3, SE2 >::setEstimate().

43  {
44  Vector3D p;
45  is >> p[0] >> p[1] >> p[2];
46  setEstimate(p);
47  return true;
48  }
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
void setEstimate(const EstimateType &et)
set the estimate for the vertex also calls updateCache()
Definition: base_vertex.h:101
virtual bool g2o::VertexSE2::setEstimateDataImpl ( const double *  )
inlinevirtual

writes the estimater to an array of double

Returns
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 60 of file vertex_se2.h.

60  {
61  _estimate=SE2(est[0], est[1], est[2]);
62  return true;
63  }
virtual bool g2o::VertexSE2::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 73 of file vertex_se2.h.

73  {
74  return setEstimateData(est);
75  }
bool setEstimateData(const double *estimate)
virtual void g2o::VertexSE2::setToOriginImpl ( )
inlinevirtual

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 47 of file vertex_se2.h.

47  {
48  _estimate = SE2();
49  }
bool g2o::VertexSE2::write ( std::ostream &  os) const
virtual

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Definition at line 50 of file vertex_se2.cpp.

References g2o::BaseVertex< 3, SE2 >::estimate(), and g2o::SE2::toVector().

51  {
52  Vector3D p = estimate().toVector();
53  os << p[0] << " " << p[1] << " " << p[2];
54  return os.good();
55  }
Vector3D toVector() const
convert to a 3D vector (x, y, theta)
Definition: se2.h:108
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Definition: eigen_types.h:46
const EstimateType & estimate() const
return the current estimate of the vertex
Definition: base_vertex.h:99

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