Public Member Functions | Public Attributes
g2o::VertexSE3Expmap Class Reference

SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential map. More...

#include <types_six_dof_expmap.h>

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

List of all members.

Public Member Functions

Vector2d cam_map (const Vector3d &trans_xyz) const
virtual void oplus (double *update_)
 update the position of the node from the parameters in v
bool read (std::istream &is)
 read the vertex from a stream, i.e., the internal state of the vertex
virtual void setToOrigin ()
 sets the node to the origin (used in the multilevel stuff)
Vector3d stereocam_uvq_map (const Vector3d &trans_xyz) const
Vector3d stereocam_uvu_map (const Vector3d &trans_xyz) const
EIGEN_MAKE_ALIGNED_OPERATOR_NEW VertexSE3Expmap ()
bool write (std::ostream &os) const
 write the vertex to a stream

Public Attributes

double _baseline
Vector2d _focal_length
Vector2d _principle_point

Detailed Description

SE3 Vertex parameterized internally with a transformation matrix and externally with its exponential map.

Definition at line 36 of file types_six_dof_expmap.h.


Constructor & Destructor Documentation

Definition at line 35 of file types_six_dof_expmap.cpp.


Member Function Documentation

Vector2d g2o::VertexSE3Expmap::cam_map ( const Vector3d &  trans_xyz) const [inline]

Definition at line 69 of file types_six_dof_expmap.h.

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

update the position of the node from the parameters in v

Implements g2o::OptimizableGraph::Vertex.

Definition at line 49 of file types_six_dof_expmap.h.

bool g2o::VertexSE3Expmap::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 types_six_dof_expmap.cpp.

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

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

Implements g2o::OptimizableGraph::Vertex.

Definition at line 45 of file types_six_dof_expmap.h.

Vector3d g2o::VertexSE3Expmap::stereocam_uvq_map ( const Vector3d &  trans_xyz) const [inline]

Definition at line 80 of file types_six_dof_expmap.h.

Vector3d g2o::VertexSE3Expmap::stereocam_uvu_map ( const Vector3d &  trans_xyz) const [inline]

Definition at line 94 of file types_six_dof_expmap.h.

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

write the vertex to a stream

Implements g2o::OptimizableGraph::Vertex.

Definition at line 58 of file types_six_dof_expmap.cpp.


Member Data Documentation

Definition at line 66 of file types_six_dof_expmap.h.

Definition at line 65 of file types_six_dof_expmap.h.

Definition at line 64 of file types_six_dof_expmap.h.


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