All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines
Public Member Functions | Protected Types | Protected Attributes
vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT > Class Template Reference

Specialized interface for Keyframe Manager where pose-graph is a tree. More...

#include <vo.h>

Inheritance diagram for vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >:
Inheritance graph
[legend]

List of all members.

Public Member Functions

virtual bool buildNewKeyframe ()=0
 decides if current frame should be keyframe.
 KeyframeVisualOdometry (shared_ptr< NodeBuilderTT< PoseGraphT > > _nbuilder, shared_ptr< EdgeBuilder< PoseGraphT > > _ebuilder, size_t _target_past_verticies_size=1, shared_ptr< VodomLogger< PoseGraphT > > _logger=shared_ptr< VodomLogger< PoseGraphT > >())
virtual void newKeyframeBuilt ()=0
 stuff that needs to be done after creating new keyframe.
virtual shared_ptr< VertexDprocessPose0 (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, bool debug_images=false, bool trajectory_file=false)

Protected Types

typedef graph_traits
< PoseGraphT >
::vertex_descriptor 
VertexD

Protected Attributes

VertexD current_keyframe
bool has_pvd
bool initial_pose_registred
NodeBuilderTT< PoseGraphT >
::InputType 
keyframe_image
G2ORunner2< PoseGraphT > opt
NodeBuilderTT< PoseGraphT >
::InputType 
pvd_image
int total_vertex_count
NodeBuilderTT< PoseGraphT >
::InputType 
vd_image
int window_idx
vector< VertexDwindow_vertices

Detailed Description

template<template< class > class NodeBuilderTT, class PoseGraphT>
class vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >

Specialized interface for Keyframe Manager where pose-graph is a tree.

This is specialization of Keyframe Manager where pose-graph is a tree. For each node in the tree, lists correspond to non-keyframe poses and first or the first and the last poses of the trajectory. When calling KeyframeVisualOdometry::processPose0, new node is allways connected to the last keyframe.

After adding new vertex to the pose-graph, KeyframeVisualOdometry::buildNewKeyframe determines if the added vertex is a keyframe.

After addition of each new vertex, the pose-graph is optimalized. After that, poses that are no longer useful for optimalization are removed.

Definition at line 334 of file vo.h.


Member Typedef Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
typedef graph_traits<PoseGraphT>::vertex_descriptor vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::VertexD [protected]

Constructor & Destructor Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::KeyframeVisualOdometry ( shared_ptr< NodeBuilderTT< PoseGraphT > >  _nbuilder,
shared_ptr< EdgeBuilder< PoseGraphT > >  _ebuilder,
size_t  _target_past_verticies_size = 1,
shared_ptr< VodomLogger< PoseGraphT > >  _logger = shared_ptr<VodomLogger<PoseGraphT> >() 
) [inline]

Definition at line 349 of file vo.h.


Member Function Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual bool vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::buildNewKeyframe ( ) [pure virtual]
template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual void vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::newKeyframeBuilt ( ) [pure virtual]
template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual shared_ptr<VertexD> vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::processPose0 ( typename NodeBuilderTT< PoseGraphT >::InputType  input,
int  pose_id,
uint64_t  pose_timestamp,
bool  debug_images = false,
bool  trajectory_file = false 
) [inline, virtual]
Todo:
delete new_pose ?

Implements vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >.

Definition at line 365 of file vo.h.


Member Data Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
VertexD vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::current_keyframe [protected]

Reimplemented in vslam::ScaleErrorKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.

Definition at line 340 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
bool vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::has_pvd [protected]

Definition at line 339 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
bool vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::initial_pose_registred [protected]

Reimplemented in vslam::ScaleErrorKeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.

Definition at line 338 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
NodeBuilderTT<PoseGraphT>::InputType vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::keyframe_image [protected]

Definition at line 345 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
G2ORunner2<PoseGraphT> vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::opt [protected]

Definition at line 347 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
NodeBuilderTT<PoseGraphT>::InputType vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::pvd_image [protected]

Definition at line 345 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
int vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::total_vertex_count [protected]

Definition at line 343 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
NodeBuilderTT<PoseGraphT>::InputType vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::vd_image [protected]

Definition at line 345 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
int vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::window_idx [protected]

Definition at line 342 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
vector<VertexD> vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >::window_vertices [protected]

Definition at line 341 of file vo.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:16