All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends
Public Member Functions | Private Member Functions | Private Attributes
rgbdtools::KeyframeGraphSolverG2O Class Reference

Graph-based global alignement using g2o (generalized graph optimizaiton) More...

#include <keyframe_graph_solver_g2o.h>

Inheritance diagram for rgbdtools::KeyframeGraphSolverG2O:
Inheritance graph
[legend]

List of all members.

Public Member Functions

 KeyframeGraphSolverG2O ()
 Constructor from ROS noehandles.
 KeyframeGraphSolverG2O ()
 Constructor from ROS noehandles.
void solve (KeyframeVector &keyframes, const KeyframeAssociationVector &associations)
 Main method to call to perform graph solving using g2o.
void solve (KeyframeVector &keyframes, const KeyframeAssociationVector &associations)
 Main method to call to perform graph solving using g2o.
void solve (KeyframeVector &keyframes, const KeyframeAssociationVector &associations, AffineTransformVector &path)
void solve (KeyframeVector &keyframes, const KeyframeAssociationVector &associations, AffineTransformVector &path)
 ~KeyframeGraphSolverG2O ()
 Default destructor.
 ~KeyframeGraphSolverG2O ()
 Default destructor.

Private Member Functions

void addEdge (int from_idx, int to_idx, const AffineTransform &relative_pose, const Eigen::Matrix< double, 6, 6 > &information_matrix)
 Adds an edge to the g2o structure.
void addEdge (int from_idx, int to_idx, const AffineTransform &relative_pose, const Eigen::Matrix< double, 6, 6 > &information_matrix)
 Adds an edge to the g2o structure.
void addVertex (const AffineTransform &vertex_pose, int vertex_idx)
 Adds a vertex to the g2o structure.
void addVertex (const AffineTransform &vertex_pose, int vertex_idx)
 Adds a vertex to the g2o structure.
void getOptimizedPoses (AffineTransformVector &poses_)
 copies the (optimized) poses from the g2o structure into the keyframe vector
void getOptimizedPoses (AffineTransformVector &poses_)
 copies the (optimized) poses from the g2o structure into the keyframe vector
void optimizeGraph ()
 runs the optimization
void optimizeGraph ()
 runs the optimization

Private Attributes

g2o::BlockSolver_6_3::LinearSolverType * linearSolver
g2o::SparseOptimizer optimizer
g2o::BlockSolver_6_3 * solver_ptr
int vertexIdx

Detailed Description

Graph-based global alignement using g2o (generalized graph optimizaiton)

Definition at line 50 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.


Constructor & Destructor Documentation

Constructor from ROS noehandles.

Definition at line 28 of file keyframe_graph_solver_g2o.cpp.

Default destructor.

Definition at line 43 of file keyframe_graph_solver_g2o.cpp.

Constructor from ROS noehandles.

Default destructor.


Member Function Documentation

void rgbdtools::KeyframeGraphSolverG2O::addEdge ( int  from_idx,
int  to_idx,
const AffineTransform relative_pose,
const Eigen::Matrix< double, 6, 6 > &  information_matrix 
) [private]

Adds an edge to the g2o structure.

Definition at line 225 of file keyframe_graph_solver_g2o.cpp.

void rgbdtools::KeyframeGraphSolverG2O::addEdge ( int  from_idx,
int  to_idx,
const AffineTransform relative_pose,
const Eigen::Matrix< double, 6, 6 > &  information_matrix 
) [private]

Adds an edge to the g2o structure.

void rgbdtools::KeyframeGraphSolverG2O::addVertex ( const AffineTransform vertex_pose,
int  vertex_idx 
) [private]

Adds a vertex to the g2o structure.

void rgbdtools::KeyframeGraphSolverG2O::addVertex ( const AffineTransform vertex_pose,
int  vertex_idx 
) [private]

Adds a vertex to the g2o structure.

Definition at line 189 of file keyframe_graph_solver_g2o.cpp.

copies the (optimized) poses from the g2o structure into the keyframe vector

Parameters:
keyframesthe vector of keyframes to modify the poses

Definition at line 273 of file keyframe_graph_solver_g2o.cpp.

copies the (optimized) poses from the g2o structure into the keyframe vector

Parameters:
keyframesthe vector of keyframes to modify the poses

runs the optimization

Definition at line 261 of file keyframe_graph_solver_g2o.cpp.

runs the optimization

void rgbdtools::KeyframeGraphSolverG2O::solve ( KeyframeVector keyframes,
const KeyframeAssociationVector associations 
) [virtual]

Main method to call to perform graph solving using g2o.

Parameters:
keyframesvector of keyframes
associationsvector of input keyframe associations

Implements rgbdtools::KeyframeGraphSolver.

Definition at line 126 of file keyframe_graph_solver_g2o.cpp.

void rgbdtools::KeyframeGraphSolverG2O::solve ( KeyframeVector keyframes,
const KeyframeAssociationVector associations 
) [virtual]

Main method to call to perform graph solving using g2o.

Parameters:
keyframesvector of keyframes
associationsvector of input keyframe associations

Implements rgbdtools::KeyframeGraphSolver.

void rgbdtools::KeyframeGraphSolverG2O::solve ( KeyframeVector keyframes,
const KeyframeAssociationVector associations,
AffineTransformVector path 
) [virtual]

Implements rgbdtools::KeyframeGraphSolver.

Definition at line 48 of file keyframe_graph_solver_g2o.cpp.

void rgbdtools::KeyframeGraphSolverG2O::solve ( KeyframeVector keyframes,
const KeyframeAssociationVector associations,
AffineTransformVector path 
) [virtual]

Member Data Documentation

g2o::BlockSolver_6_3::LinearSolverType * rgbdtools::KeyframeGraphSolverG2O::linearSolver [private]
g2o::SparseOptimizer rgbdtools::KeyframeGraphSolverG2O::optimizer [private]
g2o::BlockSolver_6_3 * rgbdtools::KeyframeGraphSolverG2O::solver_ptr [private]

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


lib_rgbdtools
Author(s): Ivan Dryanovski
autogenerated on Tue Aug 27 2013 10:33:55