Implementation of the Gauss Newton Algorithm. More...
#include <optimization_algorithm_gauss_newton.h>
Public Member Functions | |
OptimizationAlgorithmGaussNewton (Solver *solver) | |
virtual void | printVerbose (std::ostream &os) const |
virtual SolverResult | solve (int iteration, bool online=false) |
virtual | ~OptimizationAlgorithmGaussNewton () |
Public Member Functions inherited from g2o::OptimizationAlgorithmWithHessian | |
virtual bool | buildLinearStructure () |
virtual bool | computeMarginals (SparseBlockMatrix< MatrixXd > &spinv, const std::vector< std::pair< int, int > > &blockIndices) |
virtual bool | init (bool online=false) |
OptimizationAlgorithmWithHessian (Solver *solver) | |
virtual void | setWriteDebug (bool writeDebug) |
Solver * | solver () |
return the underlying solver used to solve the linear system More... | |
virtual void | updateLinearSystem () |
virtual bool | updateStructure (const std::vector< HyperGraph::Vertex * > &vset, const HyperGraph::EdgeSet &edges) |
virtual bool | writeDebug () const |
virtual | ~OptimizationAlgorithmWithHessian () |
Public Member Functions inherited from g2o::OptimizationAlgorithm | |
OptimizationAlgorithm () | |
const SparseOptimizer * | optimizer () const |
return the optimizer operating on More... | |
SparseOptimizer * | optimizer () |
void | printProperties (std::ostream &os) const |
const PropertyMap & | properties () const |
return the properties of the solver More... | |
void | setOptimizer (SparseOptimizer *optimizer) |
bool | updatePropertiesFromString (const std::string &propString) |
virtual | ~OptimizationAlgorithm () |
Additional Inherited Members | |
Public Types inherited from g2o::OptimizationAlgorithm | |
enum | SolverResult { Terminate =2, OK =1, Fail =-1 } |
Protected Attributes inherited from g2o::OptimizationAlgorithmWithHessian | |
Solver * | _solver |
Property< bool > * | _writeDebug |
Protected Attributes inherited from g2o::OptimizationAlgorithm | |
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... | |
Implementation of the Gauss Newton Algorithm.
Definition at line 37 of file optimization_algorithm_gauss_newton.h.
|
explicit |
construct the Gauss Newton algorithm, which use the given Solver for solving the linearized system.
Definition at line 41 of file optimization_algorithm_gauss_newton.cpp.
|
virtual |
Definition at line 46 of file optimization_algorithm_gauss_newton.cpp.
|
virtual |
called by the optimizer if verbose. re-implement, if you want to print something
Reimplemented from g2o::OptimizationAlgorithm.
Definition at line 95 of file optimization_algorithm_gauss_newton.cpp.
|
virtual |
Solve one iteration. The SparseOptimizer running on-top will call this for the given number of iterations.
iteration | indicates the current iteration |
Implements g2o::OptimizationAlgorithm.
Definition at line 50 of file optimization_algorithm_gauss_newton.cpp.