2D pose Vertex, (x,y,theta) More...
#include <vertex_se2.h>
Public Member Functions | |
virtual int | estimateDimension () const |
virtual bool | getEstimateData (double *est) const |
virtual bool | getMinimalEstimateData (double *est) const |
virtual int | minimalEstimateDimension () const |
virtual void | oplus (double *update) |
update the position of the node from the parameters in v | |
virtual bool | read (std::istream &is) |
read the vertex from a stream, i.e., the internal state of the vertex | |
virtual bool | setEstimateData (const double *est) |
virtual bool | setMinimalEstimateData (const double *est) |
virtual void | setToOrigin () |
sets the node to the origin (used in the multilevel stuff) | |
EIGEN_MAKE_ALIGNED_OPERATOR_NEW | VertexSE2 () |
virtual bool | write (std::ostream &os) const |
write the vertex to a stream |
2D pose Vertex, (x,y,theta)
Definition at line 30 of file types/slam2d/vertex_se2.h.
Definition at line 34 of file types/slam2d/vertex_se2.cpp.
virtual int g2o::VertexSE2::estimateDimension | ( | ) | const [inline, virtual] |
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 60 of file types/slam2d/vertex_se2.h.
virtual bool g2o::VertexSE2::getEstimateData | ( | double * | estimate | ) | const [inline, virtual] |
writes the estimater to an array of double
Reimplemented from g2o::OptimizableGraph::Vertex.
Definition at line 52 of file types/slam2d/vertex_se2.h.
virtual bool g2o::VertexSE2::getMinimalEstimateData | ( | double * | estimate | ) | const [inline, virtual] |
writes the estimater to an array of double
Reimplemented from g2o::OptimizableGraph::Vertex.
Definition at line 66 of file types/slam2d/vertex_se2.h.
virtual int g2o::VertexSE2::minimalEstimateDimension | ( | ) | const [inline, virtual] |
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 70 of file types/slam2d/vertex_se2.h.
virtual void g2o::VertexSE2::oplus | ( | double * | v | ) | [inline, virtual] |
update the position of the node from the parameters in v
Implements g2o::OptimizableGraph::Vertex.
Reimplemented in g2o::OnlineVertexSE2.
Definition at line 40 of file types/slam2d/vertex_se2.h.
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 39 of file types/slam2d/vertex_se2.cpp.
virtual bool g2o::VertexSE2::setEstimateData | ( | const double * | estimate | ) | [inline, virtual] |
sets the initial estimate from an array of double
Reimplemented from g2o::OptimizableGraph::Vertex.
Definition at line 47 of file types/slam2d/vertex_se2.h.
virtual bool g2o::VertexSE2::setMinimalEstimateData | ( | const double * | estimate | ) | [inline, virtual] |
sets the initial estimate from an array of double
Reimplemented from g2o::OptimizableGraph::Vertex.
Definition at line 62 of file types/slam2d/vertex_se2.h.
virtual void g2o::VertexSE2::setToOrigin | ( | ) | [inline, virtual] |
sets the node to the origin (used in the multilevel stuff)
Implements g2o::OptimizableGraph::Vertex.
Definition at line 36 of file types/slam2d/vertex_se2.h.
bool g2o::VertexSE2::write | ( | std::ostream & | os | ) | const [virtual] |
write the vertex to a stream
Implements g2o::OptimizableGraph::Vertex.
Definition at line 47 of file types/slam2d/vertex_se2.cpp.