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

This is top-level calss for VO. More...

#include <vo.h>

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

List of all members.

Public Member Functions

virtual pair< pair< VertexD,
VertexD >, bool > 
getLastEdge ()
 return last constructed edge in the pose-graph.
PoseGraphT & getPoseGraph ()
shared_ptr< SE3 > processPose (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, std::deque< SE3 > &past_poses, bool debug_images=false, bool trajectory_file=false)
 process new image.
shared_ptr< SE3 > processPose (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, bool debug_images=false, bool trajectory_file=false)
 process new image.
virtual shared_ptr< VertexDprocessPose0 (typename NodeBuilderTT< PoseGraphT >::InputType input, int pose_id, uint64_t pose_timestamp, bool debug_images=false, bool trajectory_file=false)=0
 VisualOdometry (shared_ptr< NodeBuilderTT< PoseGraphT > > _nbuilder, shared_ptr< EdgeBuilder< PoseGraphT > > _ebuilder, size_t _target_past_verticies_size=2, shared_ptr< VodomLogger< PoseGraphT > > _logger=shared_ptr< VodomLogger< PoseGraphT > >())

Protected Types

typedef graph_traits
< PoseGraphT >
::vertex_descriptor 
VertexD

Protected Member Functions

void pose2dVisualization (std::string prefix, typename graph_traits< PoseGraphT >::vertex_descriptor vd1, typename graph_traits< PoseGraphT >::vertex_descriptor vd2, typename NodeBuilderTT< PoseGraphT >::InputType input_vd1, typename NodeBuilderTT< PoseGraphT >::InputType input_vd2)
 draw debugging images for edge (vd1, vd2)
template<class T >
std::string viewIDString (T view, T from, T to)

Protected Attributes

shared_ptr< EdgeBuilder
< PoseGraphT > > 
ebuilder
PoseGraphT graph
 pose-graph class.
shared_ptr< VodomLogger
< PoseGraphT > > 
logger
shared_ptr< NodeBuilderTT
< PoseGraphT > > 
nbuilder
std::deque< VertexDpast_vertices
Points< PoseGraphT > points
 landmark maneger class.
VertexD pvd
size_t target_past_verticies_size
VertexD vd
YAML::Emitter yaml_out

Static Protected Attributes

static const int MINSEQ = 1000000

Detailed Description

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

This is top-level calss for VO.

The VO is obtained by sucessive calls to VisualOdometry::processPose, which basically takes an image and produces T_wc, where w is world CF and c is camera cf for the given image.

Template Parameters:
NodeBuilderTTClass template of the type fulfilling OneDetectorNodeBuilder interface
PoseGraphTboost::adjacency_list type.

The implamentation of this interface also called _Keyframe Manager_.

Definition at line 88 of file vo.h.


Member Typedef Documentation

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

Constructor & Destructor Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::VisualOdometry ( shared_ptr< NodeBuilderTT< PoseGraphT > >  _nbuilder,
shared_ptr< EdgeBuilder< PoseGraphT > >  _ebuilder,
size_t  _target_past_verticies_size = 2,
shared_ptr< VodomLogger< PoseGraphT > >  _logger = shared_ptr<VodomLogger<PoseGraphT> >() 
) [inline]
Parameters:
_nbuilderinstance of OneDetectorNodeBuilder to be used for processing new images.
_ebuilderinstance of EdgeBuilder to be used for RBT estimate between nodes of the pose-graph.
_target_past_verticies_sizenumber of past poses to store, see VisualOdometry::processPose

Definition at line 118 of file vo.h.


Member Function Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual pair<pair<VertexD, VertexD>, bool> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::getLastEdge ( ) [inline, virtual]

return last constructed edge in the pose-graph.

Todo:
consider removal, see past_vertices

Definition at line 211 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
PoseGraphT& vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::getPoseGraph ( ) [inline]
Todo:
make const -- newtestpe requires write aceess. solve this by creating special VisualOdometry class for it.

Definition at line 205 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
void vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::pose2dVisualization ( std::string  prefix,
typename graph_traits< PoseGraphT >::vertex_descriptor  vd1,
typename graph_traits< PoseGraphT >::vertex_descriptor  vd2,
typename NodeBuilderTT< PoseGraphT >::InputType  input_vd1,
typename NodeBuilderTT< PoseGraphT >::InputType  input_vd2 
) [inline, protected]

draw debugging images for edge (vd1, vd2)

Definition at line 227 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
shared_ptr<SE3> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose ( typename NodeBuilderTT< PoseGraphT >::InputType  input,
int  pose_id,
uint64_t  pose_timestamp,
std::deque< SE3 > &  past_poses,
bool  debug_images = false,
bool  trajectory_file = false 
) [inline]

process new image.

Parameters:
inputinput data required by NodeBuilderTT to produce new pose-graph pose. This is typically an image, but may be something else in simulation.
pose_idimage ID that is used in the debugging output associate poses to images.
past_posesRBTs for VisualOdometry::target_past_verticies_size most recent poses.

Definition at line 138 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
shared_ptr<SE3> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose ( typename NodeBuilderTT< PoseGraphT >::InputType  input,
int  pose_id,
uint64_t  pose_timestamp,
bool  debug_images = false,
bool  trajectory_file = false 
) [inline]

process new image.

See also:
VisualOdometry::processPose

Definition at line 184 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
virtual shared_ptr<VertexD> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::processPose0 ( typename NodeBuilderTT< PoseGraphT >::InputType  input,
int  pose_id,
uint64_t  pose_timestamp,
bool  debug_images = false,
bool  trajectory_file = false 
) [pure virtual]
template<template< class > class NodeBuilderTT, class PoseGraphT >
template<class T >
std::string vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::viewIDString ( view,
from,
to 
) [inline, protected]

Definition at line 218 of file vo.h.


Member Data Documentation

template<template< class > class NodeBuilderTT, class PoseGraphT >
shared_ptr<EdgeBuilder<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::ebuilder [protected]

Definition at line 91 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
PoseGraphT vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::graph [protected]

pose-graph class.

Definition at line 92 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
shared_ptr<VodomLogger<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::logger [protected]

Definition at line 108 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
const int vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::MINSEQ = 1000000 [static, protected]

Definition at line 216 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
shared_ptr<NodeBuilderTT<PoseGraphT> > vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::nbuilder [protected]

Definition at line 90 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
std::deque<VertexD> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::past_vertices [protected]

Stores VisualOdometry::target_past_verticies_size most recent vertices

Definition at line 103 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
Points<PoseGraphT> vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::points [protected]

landmark maneger class.

Definition at line 93 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
VertexD vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::pvd [protected]
Todo:
reconsider removeal.
Invariant:
after calling VisualOdometry::processPose0 it is vertex that was last added vertex after the previous call to VisualOdometry::processPose0.

Definition at line 97 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
size_t vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::target_past_verticies_size [protected]

Definition at line 105 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
VertexD vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::vd [protected]
Invariant:
after calling VisualOdometry::processPose0 its last added vertex.

Definition at line 96 of file vo.h.

template<template< class > class NodeBuilderTT, class PoseGraphT >
YAML::Emitter vslam::VisualOdometry< NodeBuilderTT, PoseGraphT >::yaml_out [protected]
Todo:
consider mooving this to VORosInterface

Definition at line 107 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:17