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

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

#include <keyframe_graph_solver_g2o.h>

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

List of all members.

Public Member Functions

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

Private Member Functions

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

Private Attributes

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

Detailed Description

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

Definition at line 42 of file keyframe_graph_solver_g2o.h.


Constructor & Destructor Documentation

Constructor from ROS noehandles.

Parameters:
nhthe public nodehandle
nh_privatethe private notehandle

Definition at line 28 of file keyframe_graph_solver_g2o.cpp.

Default destructor.

Definition at line 43 of file keyframe_graph_solver_g2o.cpp.


Member Function Documentation

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

Adds an edge to the g2o structure.

Definition at line 130 of file keyframe_graph_solver_g2o.cpp.

void ccny_rgbd::KeyframeGraphSolverG2O::addVertex ( const Eigen::Matrix4f &  vertex_pose,
int  vertex_idx 
) [private]

Adds a vertex to the g2o structure.

Definition at line 95 of file keyframe_graph_solver_g2o.cpp.

runs the optimization

Definition at line 166 of file keyframe_graph_solver_g2o.cpp.

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

Main method to call to perform graph solving using g2o.

Parameters:
keyframesvector of keyframes
associationsvector of input keyframe associations

Implements ccny_rgbd::KeyframeGraphSolver.

Definition at line 48 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 178 of file keyframe_graph_solver_g2o.cpp.


Member Data Documentation

g2o::BlockSolverX::LinearSolverType* ccny_rgbd::KeyframeGraphSolverG2O::linearSolver [private]

Definition at line 69 of file keyframe_graph_solver_g2o.h.

g2o::SparseOptimizer ccny_rgbd::KeyframeGraphSolverG2O::optimizer [private]

Definition at line 68 of file keyframe_graph_solver_g2o.h.

g2o::BlockSolverX* ccny_rgbd::KeyframeGraphSolverG2O::solver_ptr [private]

Definition at line 70 of file keyframe_graph_solver_g2o.h.

Definition at line 67 of file keyframe_graph_solver_g2o.h.


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


ccny_rgbd
Author(s): Ivan Dryanovski
autogenerated on Fri Apr 12 2013 20:38:48