Base class for graph-based global alignment classes. More...
#include <keyframe_graph_solver.h>
Public Member Functions | |
KeyframeGraphSolver (const ros::NodeHandle &nh, const ros::NodeHandle &nh_private) | |
Constructor from ROS noehandles. | |
virtual void | solve (KeyframeVector &keyframes, KeyframeAssociationVector &associations)=0 |
Main method to call to perform graph solving. | |
virtual | ~KeyframeGraphSolver () |
Default destructor. | |
Protected Attributes | |
ros::NodeHandle | nh_ |
the public nodehandle | |
ros::NodeHandle | nh_private_ |
the private nodehandle |
Base class for graph-based global alignment classes.
The class takes as input a vector of RGBD keyframes and a vector of associations between them, and modifies the keyframe poses based on the minimization of some error metric.
Definition at line 42 of file keyframe_graph_solver.h.
ccny_rgbd::KeyframeGraphSolver::KeyframeGraphSolver | ( | const ros::NodeHandle & | nh, |
const ros::NodeHandle & | nh_private | ||
) |
Constructor from ROS noehandles.
nh | the public nodehandle |
nh_private | the private notehandle |
Definition at line 28 of file keyframe_graph_solver.cpp.
ccny_rgbd::KeyframeGraphSolver::~KeyframeGraphSolver | ( | ) | [virtual] |
Default destructor.
Definition at line 37 of file keyframe_graph_solver.cpp.
virtual void ccny_rgbd::KeyframeGraphSolver::solve | ( | KeyframeVector & | keyframes, |
KeyframeAssociationVector & | associations | ||
) | [pure virtual] |
Main method to call to perform graph solving.
The keyframe poses will be modified according to some error propagation model informed by the graph defined by the keyframe associations.
keyframes | vector of keyframes |
associations | vector of input keyframe associations |
Implemented in ccny_rgbd::KeyframeGraphSolverG2O.
ros::NodeHandle ccny_rgbd::KeyframeGraphSolver::nh_ [protected] |
the public nodehandle
Definition at line 72 of file keyframe_graph_solver.h.
the private nodehandle
Definition at line 73 of file keyframe_graph_solver.h.