All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines
Public Member Functions | Public Attributes | Protected Attributes
vslam::g2o_types::VertexPointXYZ< PoseGraphT > Class Template Reference

Represents landmark variable (vertex) in g2o graph. More...

#include <vertex_landmark.h>

List of all members.

Public Member Functions

virtual void oplusImpl (const double *update)
virtual void setToOriginImpl ()
 VertexPointXYZ (int _points_idx, Points< PoseGraphT > &_points)
 VertexPointXYZ ()
virtual ~VertexPointXYZ ()
Unimplemented

Required by the interface, but not required for our use of g2o. Not intended for use. Not implemented.

virtual bool read (std::istream &is)
virtual bool write (std::ostream &os) const

Public Attributes

 EIGEN_MAKE_ALIGNED_OPERATOR_NEW
bool save_state
 Controls if state is copied into pose-graph 'g' on destruction.

Protected Attributes

bool initialized
 Guard againt improper init. by required nonparametric contructor.
int pointds_idx
 Corresponding landmark index in 'points'.
Points< PoseGraphT > * points

Detailed Description

template<class PoseGraphT>
class vslam::g2o_types::VertexPointXYZ< PoseGraphT >

Represents landmark variable (vertex) in g2o graph.

Pose is parametrized as a point in 3D space wrt. to world CF. On destruction, the results of the optimalization are saved into pose-graph

See also:
g2o_types

Definition at line 27 of file vertex_landmark.h.


Constructor & Destructor Documentation

template<class PoseGraphT>
vslam::g2o_types::VertexPointXYZ< PoseGraphT >::VertexPointXYZ ( int  _points_idx,
Points< PoseGraphT > &  _points 
) [inline]

Definition at line 39 of file vertex_landmark.h.

template<class PoseGraphT>
vslam::g2o_types::VertexPointXYZ< PoseGraphT >::VertexPointXYZ ( ) [inline]

required by the g2o interface

Definition at line 45 of file vertex_landmark.h.

template<class PoseGraphT>
virtual vslam::g2o_types::VertexPointXYZ< PoseGraphT >::~VertexPointXYZ ( ) [inline, virtual]
Todo:
Turned of code that discarded results with moderate or high distance from the pre-optimization value. Investicate the influence on the results of VO, and if appropriate, delete it (original code is kept commented out).

Definition at line 73 of file vertex_landmark.h.


Member Function Documentation

template<class PoseGraphT>
virtual void vslam::g2o_types::VertexPointXYZ< PoseGraphT >::oplusImpl ( const double *  update) [inline, virtual]

Definition at line 63 of file vertex_landmark.h.

template<class PoseGraphT>
virtual bool vslam::g2o_types::VertexPointXYZ< PoseGraphT >::read ( std::istream &  is) [inline, virtual]

Definition at line 56 of file vertex_landmark.h.

template<class PoseGraphT>
virtual void vslam::g2o_types::VertexPointXYZ< PoseGraphT >::setToOriginImpl ( ) [inline, virtual]

Definition at line 47 of file vertex_landmark.h.

template<class PoseGraphT>
virtual bool vslam::g2o_types::VertexPointXYZ< PoseGraphT >::write ( std::ostream &  os) const [inline, virtual]

Definition at line 57 of file vertex_landmark.h.


Member Data Documentation

template<class PoseGraphT>
vslam::g2o_types::VertexPointXYZ< PoseGraphT >::EIGEN_MAKE_ALIGNED_OPERATOR_NEW

Definition at line 35 of file vertex_landmark.h.

template<class PoseGraphT>
bool vslam::g2o_types::VertexPointXYZ< PoseGraphT >::initialized [protected]

Guard againt improper init. by required nonparametric contructor.

Definition at line 32 of file vertex_landmark.h.

template<class PoseGraphT>
int vslam::g2o_types::VertexPointXYZ< PoseGraphT >::pointds_idx [protected]

Corresponding landmark index in 'points'.

Definition at line 30 of file vertex_landmark.h.

template<class PoseGraphT>
Points<PoseGraphT>* vslam::g2o_types::VertexPointXYZ< PoseGraphT >::points [protected]

Definition at line 31 of file vertex_landmark.h.

template<class PoseGraphT>
bool vslam::g2o_types::VertexPointXYZ< PoseGraphT >::save_state

Controls if state is copied into pose-graph 'g' on destruction.

Definition at line 37 of file vertex_landmark.h.


The documentation for this class was generated from the following file:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines


pose_estimation
Author(s): Jiri Divis/jiridivis@gmail.com
autogenerated on Wed Mar 27 2013 21:00:17