Graph-based global alignement using g2o (generalized graph optimizaiton) More...
#include <keyframe_graph_solver_g2o.h>
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 |
Graph-based global alignement using g2o (generalized graph optimizaiton)
Definition at line 50 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.
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.
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.
void rgbdtools::KeyframeGraphSolverG2O::getOptimizedPoses | ( | AffineTransformVector & | poses_ | ) | [private] |
copies the (optimized) poses from the g2o structure into the keyframe vector
keyframes | the vector of keyframes to modify the poses |
Definition at line 273 of file keyframe_graph_solver_g2o.cpp.
void rgbdtools::KeyframeGraphSolverG2O::getOptimizedPoses | ( | AffineTransformVector & | poses_ | ) | [private] |
copies the (optimized) poses from the g2o structure into the keyframe vector
keyframes | the vector of keyframes to modify the poses |
void rgbdtools::KeyframeGraphSolverG2O::optimizeGraph | ( | ) | [private] |
runs the optimization
Definition at line 261 of file keyframe_graph_solver_g2o.cpp.
void rgbdtools::KeyframeGraphSolverG2O::optimizeGraph | ( | ) | [private] |
runs the optimization
void rgbdtools::KeyframeGraphSolverG2O::solve | ( | KeyframeVector & | keyframes, |
const KeyframeAssociationVector & | associations | ||
) | [virtual] |
Main method to call to perform graph solving using g2o.
keyframes | vector of keyframes |
associations | vector 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.
keyframes | vector of keyframes |
associations | vector 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] |
Implements rgbdtools::KeyframeGraphSolver.
g2o::BlockSolver_6_3::LinearSolverType * rgbdtools::KeyframeGraphSolverG2O::linearSolver [private] |
Definition at line 78 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.
g2o::SparseOptimizer rgbdtools::KeyframeGraphSolverG2O::optimizer [private] |
Definition at line 77 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.
g2o::BlockSolver_6_3 * rgbdtools::KeyframeGraphSolverG2O::solver_ptr [private] |
Definition at line 79 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.
int rgbdtools::KeyframeGraphSolverG2O::vertexIdx [private] |
Definition at line 76 of file include/rgbdtools/graph/keyframe_graph_solver_g2o.h.