All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Defines
Public Types | Public Member Functions | Public Attributes | Private Member Functions
vslam::G2OGraphBuilder< G > Class Template Reference

Interface for building g2o graph. More...

#include <graph_opt.h>

Inheritance diagram for vslam::G2OGraphBuilder< G >:
Inheritance graph
[legend]

List of all members.

Public Types

typedef graph_traits< G >
::vertex_descriptor 
VDT

Public Member Functions

 G2OGraphBuilder (int _first_landmark_id, double _max_error)
void operator() (g2o::SparseOptimizer &optimizer, G &g, Points< G > &points, VDT startv)

Public Attributes

const int first_landmark_id
const double max_error

Private Member Functions

virtual void buildGraphImpl (g2o::SparseOptimizer &optimizer, G &g, Points< G > &points, VDT startv)=0

Detailed Description

template<class G>
class vslam::G2OGraphBuilder< G >

Interface for building g2o graph.

This in effect determine what is optimized and how. G2ORunner2 is just a shall that does g2o stuff that is independet of the g2o optimalization graph.

Definition at line 70 of file graph_opt.h.


Member Typedef Documentation

template<class G>
typedef graph_traits<G>::vertex_descriptor vslam::G2OGraphBuilder< G >::VDT

Definition at line 72 of file graph_opt.h.


Constructor & Destructor Documentation

template<class G>
vslam::G2OGraphBuilder< G >::G2OGraphBuilder ( int  _first_landmark_id,
double  _max_error 
) [inline]
Parameters:
_first_landmark_idDetermines maximum number of poses and landmarks in the g2o graph. There can be _first_landmark_id poses and (MAX_INT - first_landmark_id) landmarks.
_max_errorMaximum reprojection error allowed to add a landmark. If exceeded a warning is issued.

Definition at line 85 of file graph_opt.h.


Member Function Documentation

template<class G>
virtual void vslam::G2OGraphBuilder< G >::buildGraphImpl ( g2o::SparseOptimizer &  optimizer,
G &  g,
Points< G > &  points,
VDT  startv 
) [private, pure virtual]
template<class G>
void vslam::G2OGraphBuilder< G >::operator() ( g2o::SparseOptimizer &  optimizer,
G &  g,
Points< G > &  points,
VDT  startv 
) [inline]
Parameters:
[in,out]optimizerg2o graph representation.
Precondition:
this is intended to be called only from G2ORunner2 ( 'optimizer' has to be initialized).

Definition at line 96 of file graph_opt.h.


Member Data Documentation

template<class G>
const int vslam::G2OGraphBuilder< G >::first_landmark_id

Definition at line 74 of file graph_opt.h.

template<class G>
const double vslam::G2OGraphBuilder< G >::max_error

Definition at line 75 of file graph_opt.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