All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines
Public Member Functions
vslam::SimpleVisualOdometry< NodeBuilderTT, PoseGraphT > Class Template Reference

All frames are considered keyframes (useful for debugging and testing). More...

#include <vo.h>

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

List of all members.

Public Member Functions

virtual bool buildNewKeyframe ()
 decides if current frame should be keyframe.
virtual void newKeyframeBuilt ()
 stuff that needs to be done after creating new keyframe.
 SimpleVisualOdometry (shared_ptr< NodeBuilderTT< PoseGraphT > > _nbuilder, shared_ptr< EdgeBuilder< PoseGraphT > > _ebuilder, size_t _target_past_verticies_size, shared_ptr< VodomLogger< PoseGraphT > > _logger=shared_ptr< VodomLogger< PoseGraphT > >())

Detailed Description

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

All frames are considered keyframes (useful for debugging and testing).

Definition at line 447 of file vo.h.


Constructor & Destructor Documentation

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

Definition at line 450 of file vo.h.


Member Function Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual bool vslam::SimpleVisualOdometry< NodeBuilderTT, PoseGraphT >::buildNewKeyframe ( ) [inline, virtual]

decides if current frame should be keyframe.

Implements vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.

Definition at line 458 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual void vslam::SimpleVisualOdometry< NodeBuilderTT, PoseGraphT >::newKeyframeBuilt ( ) [inline, virtual]

stuff that needs to be done after creating new keyframe.

Implements vslam::KeyframeVisualOdometry< NodeBuilderTT, PoseGraphT >.

Definition at line 459 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