This is a solver for "structure-only" optimization". More...
#include <structure_only_solver.h>
Public Member Functions | |
void | calc (g2o::HyperGraph::VertexIDMap &vertices, int num_iters, int num_max_trials=10) |
void | setVerbose (bool verbose) |
StructureOnlySolver () | |
bool | verbose () const |
Protected Attributes | |
bool | _verbose |
This is a solver for "structure-only" optimization".
Given the problem of landmark-based SLAM or bundle adjustment, this class performs optimization on the landmarks while the poses are kept fixed. This can be done very efficiently, since the position on the landmarks are indepdented given the poses are known.
This class slightly misuses the API of g2o. It is designed in a way, it can work on the very same graph which reflects the problem of landmark-based SLAM, bundle adjustment and which is meant to be solved using the Schur complement. Thus, it can be called just before or after joint-optimization without the need of additional setup.
This class is still considered as being experimentally!
Definition at line 45 of file structure_only_solver.h.
g2o::StructureOnlySolver< PointDoF >::StructureOnlySolver | ( | ) | [inline] |
Definition at line 48 of file structure_only_solver.h.
void g2o::StructureOnlySolver< PointDoF >::calc | ( | g2o::HyperGraph::VertexIDMap & | vertices, |
int | num_iters, | ||
int | num_max_trials = 10 |
||
) | [inline] |
Definition at line 53 of file structure_only_solver.h.
void g2o::StructureOnlySolver< PointDoF >::setVerbose | ( | bool | verbose | ) | [inline] |
Definition at line 267 of file structure_only_solver.h.
bool g2o::StructureOnlySolver< PointDoF >::verbose | ( | ) | const [inline] |
Definition at line 262 of file structure_only_solver.h.
bool g2o::StructureOnlySolver< PointDoF >::_verbose [protected] |
Definition at line 273 of file structure_only_solver.h.