g2o
|
Generic interface for a non-linear solver operating on a graph. More...
#include <optimization_algorithm.h>
Public Member Functions | |
OptimizationAlgorithm () | |
virtual | ~OptimizationAlgorithm () |
virtual bool | init (bool online=false)=0 |
virtual SolverResult | solve (int iteration, bool online=false)=0 |
virtual bool | computeMarginals (SparseBlockMatrix< MatrixXD > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0 |
virtual bool | updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0 |
virtual void | printVerbose (std::ostream &os) const |
const SparseOptimizer * | optimizer () const |
return the optimizer operating on More... | |
SparseOptimizer * | optimizer () |
void | setOptimizer (SparseOptimizer *optimizer) |
const PropertyMap & | properties () const |
return the properties of the solver More... | |
bool | updatePropertiesFromString (const std::string &propString) |
void | printProperties (std::ostream &os) const |
Protected Attributes | |
SparseOptimizer * | _optimizer |
the optimizer the solver is working on More... | |
PropertyMap | _properties |
the properties of your solver, use this to store the parameters of your solver More... | |
Private Member Functions | |
OptimizationAlgorithm (const OptimizationAlgorithm &) | |
OptimizationAlgorithm & | operator= (const OptimizationAlgorithm &) |
Generic interface for a non-linear solver operating on a graph.
Definition at line 47 of file optimization_algorithm.h.
g2o::OptimizationAlgorithm::OptimizationAlgorithm | ( | ) |
Definition at line 33 of file optimization_algorithm.cpp.
|
virtual |
Definition at line 38 of file optimization_algorithm.cpp.
|
inlineprivate |
Definition at line 112 of file optimization_algorithm.h.
|
pure virtual |
computes the block diagonal elements of the pattern specified in the input and stores them in given SparseBlockMatrix. If your solver does not support computing the marginals, return false.
Implemented in g2o::StructureOnlySolver< PointDoF >, and g2o::OptimizationAlgorithmWithHessian.
Referenced by g2o::SparseOptimizer::computeMarginals().
|
pure virtual |
initialize the solver, called once before the first call to solve()
Implemented in g2o::StructureOnlySolver< PointDoF >, and g2o::OptimizationAlgorithmWithHessian.
Referenced by g2o::computeSimpleStars(), g2o::Star::labelStarEdges(), g2o::SparseOptimizerIncremental::optimize(), g2o::SparseOptimizerOnline::optimize(), and g2o::SparseOptimizer::optimize().
|
inlineprivate |
Definition at line 113 of file optimization_algorithm.h.
|
inline |
return the optimizer operating on
Definition at line 85 of file optimization_algorithm.h.
Referenced by g2o::StructureOnlySolver< PointDoF >::init(), and setOptimizer().
|
inline |
Definition at line 86 of file optimization_algorithm.h.
void g2o::OptimizationAlgorithm::printProperties | ( | std::ostream & | os | ) | const |
print the properties to a stream in a human readable fashion
Definition at line 42 of file optimization_algorithm.cpp.
References _properties, and g2o::BaseProperty::toString().
Referenced by main().
|
inlinevirtual |
called by the optimizer if verbose. re-implement, if you want to print something
Reimplemented in g2o::OptimizationAlgorithmDogleg, g2o::OptimizationAlgorithmGaussNewton, and g2o::OptimizationAlgorithmLevenberg.
Definition at line 81 of file optimization_algorithm.h.
Referenced by g2o::SparseOptimizer::optimize().
|
inline |
return the properties of the solver
Definition at line 94 of file optimization_algorithm.h.
Referenced by MainWindow::on_btnOptimizerParamaters_clicked().
void g2o::OptimizationAlgorithm::setOptimizer | ( | SparseOptimizer * | optimizer | ) |
specify on which optimizer the solver should work on
Definition at line 57 of file optimization_algorithm.cpp.
References _optimizer, and optimizer().
Referenced by g2o::SparseOptimizer::setAlgorithm().
|
pure virtual |
Solve one iteration. The SparseOptimizer running on-top will call this for the given number of iterations.
iteration | indicates the current iteration |
Implemented in g2o::StructureOnlySolver< PointDoF >, g2o::SolverSLAM2DLinear, g2o::OptimizationAlgorithmDogleg, g2o::OptimizationAlgorithmGaussNewton, and g2o::OptimizationAlgorithmLevenberg.
Referenced by g2o::SparseOptimizer::optimize().
bool g2o::OptimizationAlgorithm::updatePropertiesFromString | ( | const std::string & | propString | ) |
update the properties from a string, see PropertyMap::updateMapFromString()
Definition at line 52 of file optimization_algorithm.cpp.
References _properties, and g2o::PropertyMap::updateMapFromString().
Referenced by main().
|
pure virtual |
update the structures for online processing
Implemented in g2o::StructureOnlySolver< PointDoF >, and g2o::OptimizationAlgorithmWithHessian.
Referenced by g2o::SparseOptimizer::updateInitialization().
|
protected |
the optimizer the solver is working on
Definition at line 107 of file optimization_algorithm.h.
Referenced by g2o::OptimizationAlgorithmLevenberg::computeLambdaInit(), g2o::OptimizationAlgorithmWithHessian::init(), setOptimizer(), g2o::OptimizationAlgorithmLevenberg::solve(), g2o::OptimizationAlgorithmGaussNewton::solve(), g2o::OptimizationAlgorithmDogleg::solve(), and g2o::SolverSLAM2DLinear::solveOrientation().
|
protected |
the properties of your solver, use this to store the parameters of your solver
Definition at line 108 of file optimization_algorithm.h.
Referenced by g2o::OptimizationAlgorithmDogleg::OptimizationAlgorithmDogleg(), g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(), g2o::OptimizationAlgorithmWithHessian::OptimizationAlgorithmWithHessian(), printProperties(), and updatePropertiesFromString().