Generic interface for a non-linear solver operating on a graph. More...
#include <optimization_algorithm.h>
Public Types | |
enum | SolverResult { Terminate =2, OK =1, Fail =-1 } |
Public Member Functions | |
virtual bool | computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices)=0 |
virtual bool | init (bool online=false)=0 |
OptimizationAlgorithm () | |
const SparseOptimizer * | optimizer () const |
return the optimizer operating on More... | |
SparseOptimizer * | optimizer () |
void | printProperties (std::ostream &os) const |
virtual void | printVerbose (std::ostream &os) const |
const PropertyMap & | properties () const |
return the properties of the solver More... | |
void | setOptimizer (SparseOptimizer *optimizer) |
virtual SolverResult | solve (int iteration, bool online=false)=0 |
bool | updatePropertiesFromString (const std::string &propString) |
virtual bool | updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges)=0 |
virtual | ~OptimizationAlgorithm () |
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 & | operator= (const OptimizationAlgorithm &) |
OptimizationAlgorithm (const OptimizationAlgorithm &) | |
Generic interface for a non-linear solver operating on a graph.
Definition at line 46 of file optimization_algorithm.h.
Enumerator | |
---|---|
Terminate | |
OK | |
Fail |
Definition at line 49 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 111 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::OptimizationAlgorithmWithHessian.
|
pure virtual |
initialize the solver, called once before the first call to solve()
Implemented in g2o::OptimizationAlgorithmWithHessian.
|
inlineprivate |
Definition at line 112 of file optimization_algorithm.h.
|
inline |
return the optimizer operating on
Definition at line 84 of file optimization_algorithm.h.
|
inline |
Definition at line 85 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.
|
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 80 of file optimization_algorithm.h.
|
inline |
return the properties of the solver
Definition at line 93 of file optimization_algorithm.h.
void g2o::OptimizationAlgorithm::setOptimizer | ( | SparseOptimizer * | optimizer | ) |
specify on which optimizer the solver should work on
Definition at line 57 of file optimization_algorithm.cpp.
|
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::OptimizationAlgorithmDogleg, g2o::OptimizationAlgorithmGaussNewton, and g2o::OptimizationAlgorithmLevenberg.
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.
|
pure virtual |
update the structures for online processing
Implemented in g2o::OptimizationAlgorithmWithHessian.
|
protected |
the optimizer the solver is working on
Definition at line 106 of file optimization_algorithm.h.
|
protected |
the properties of your solver, use this to store the parameters of your solver
Definition at line 107 of file optimization_algorithm.h.