Public Member Functions
g2o::VertexSE3 Class Reference

3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion. More...

#include <vertex_se3_quat.h>

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

List of all members.

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 VertexSE3 ()
virtual bool write (std::ostream &os) const
 write the vertex to a stream

Detailed Description

3D pose Vertex, (x,y,z,qw,qx,qy,qz) the parameterization for the increments constructed is a 6d vector (x,y,z,qx,qy,qz) (note that we leave out the w part of the quaternion.

Definition at line 33 of file vertex_se3_quat.h.


Constructor & Destructor Documentation

Definition at line 32 of file vertex_se3_quat.cpp.


Member Function Documentation

virtual int g2o::VertexSE3::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 62 of file vertex_se3_quat.h.

virtual bool g2o::VertexSE3::getEstimateData ( double *  estimate) const [inline, virtual]

writes the estimater to an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 55 of file vertex_se3_quat.h.

virtual bool g2o::VertexSE3::getMinimalEstimateData ( double *  estimate) const [inline, virtual]

writes the estimater to an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 72 of file vertex_se3_quat.h.

virtual int g2o::VertexSE3::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 78 of file vertex_se3_quat.h.

virtual void g2o::VertexSE3::oplus ( double *  v) [inline, virtual]

update the position of the node from the parameters in v

Implements g2o::OptimizableGraph::Vertex.

Reimplemented in g2o::VertexSCam, and g2o::OnlineVertexSE3.

Definition at line 82 of file vertex_se3_quat.h.

bool g2o::VertexSE3::read ( std::istream &  is) [virtual]

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

Implements g2o::OptimizableGraph::Vertex.

Reimplemented in g2o::VertexSCam.

Definition at line 37 of file vertex_se3_quat.cpp.

virtual bool g2o::VertexSE3::setEstimateData ( const double *  estimate) [inline, virtual]

sets the initial estimate from an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 47 of file vertex_se3_quat.h.

virtual bool g2o::VertexSE3::setMinimalEstimateData ( const double *  estimate) [inline, virtual]

sets the initial estimate from an array of double

Returns:
true on success

Reimplemented from g2o::OptimizableGraph::Vertex.

Definition at line 66 of file vertex_se3_quat.h.

virtual void g2o::VertexSE3::setToOrigin ( ) [inline, virtual]

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 39 of file vertex_se3_quat.h.

bool g2o::VertexSE3::write ( std::ostream &  os) const [virtual]

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Reimplemented in g2o::VertexSCam.

Definition at line 45 of file vertex_se3_quat.cpp.


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


re_vision
Author(s): Dorian Galvez-Lopez
autogenerated on Sun Jan 5 2014 11:34:31