Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
g2o::OptimizationAlgorithmLevenberg Class Reference

Implementation of the Levenberg Algorithm. More...

#include <optimization_algorithm_levenberg.h>

Inheritance diagram for g2o::OptimizationAlgorithmLevenberg:
Inheritance graph
[legend]

Public Member Functions

double currentLambda () const
 return the currently used damping factor More...
 
int levenbergIteration ()
 return the number of levenberg iterations performed in the last round More...
 
int maxTrialsAfterFailure () const
 get the number of inner iterations for Levenberg-Marquardt More...
 
 OptimizationAlgorithmLevenberg (Solver *solver)
 
virtual void printVerbose (std::ostream &os) const
 
void setMaxTrialsAfterFailure (int max_trials)
 the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt More...
 
void setUserLambdaInit (double lambda)
 specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to compute a suitable value More...
 
virtual SolverResult solve (int iteration, bool online=false)
 
double userLambdaInit ()
 return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda More...
 
virtual ~OptimizationAlgorithmLevenberg ()
 
- 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)
 
Solversolver ()
 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 SparseOptimizeroptimizer () const
 return the optimizer operating on More...
 
SparseOptimizeroptimizer ()
 
void printProperties (std::ostream &os) const
 
const PropertyMapproperties () const
 return the properties of the solver More...
 
void setOptimizer (SparseOptimizer *optimizer)
 
bool updatePropertiesFromString (const std::string &propString)
 
virtual ~OptimizationAlgorithm ()
 

Protected Member Functions

double computeLambdaInit () const
 
double computeScale () const
 

Protected Attributes

double _currentLambda
 
double _goodStepLowerScale
 lower bound for lambda decrease if a good LM step More...
 
double _goodStepUpperScale
 upper bound for lambda decrease if a good LM step More...
 
int _levenbergIterations
 the numer of levenberg iterations performed to accept the last step More...
 
Property< int > * _maxTrialsAfterFailure
 
int _nBad
 
double _ni
 
double _tau
 
Property< double > * _userLambdaInit
 
- 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...
 

Additional Inherited Members

- Public Types inherited from g2o::OptimizationAlgorithm
enum  SolverResult { Terminate =2, OK =1, Fail =-1 }
 

Detailed Description

Implementation of the Levenberg Algorithm.

Definition at line 37 of file optimization_algorithm_levenberg.h.

Constructor & Destructor Documentation

g2o::OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg ( Solver solver)
explicit

construct the Levenberg algorithm, which will use the given Solver for solving the linearized system.

Definition at line 43 of file optimization_algorithm_levenberg.cpp.

g2o::OptimizationAlgorithmLevenberg::~OptimizationAlgorithmLevenberg ( )
virtual

Definition at line 57 of file optimization_algorithm_levenberg.cpp.

Member Function Documentation

double g2o::OptimizationAlgorithmLevenberg::computeLambdaInit ( ) const
protected

helper for Levenberg, this function computes the initial damping factor, if the user did not specify an own value, see setUserLambdaInit()

Definition at line 166 of file optimization_algorithm_levenberg.cpp.

double g2o::OptimizationAlgorithmLevenberg::computeScale ( ) const
protected

Definition at line 182 of file optimization_algorithm_levenberg.cpp.

double g2o::OptimizationAlgorithmLevenberg::currentLambda ( ) const
inline

return the currently used damping factor

Definition at line 52 of file optimization_algorithm_levenberg.h.

int g2o::OptimizationAlgorithmLevenberg::levenbergIteration ( )
inline

return the number of levenberg iterations performed in the last round

Definition at line 66 of file optimization_algorithm_levenberg.h.

int g2o::OptimizationAlgorithmLevenberg::maxTrialsAfterFailure ( ) const
inline

get the number of inner iterations for Levenberg-Marquardt

Definition at line 58 of file optimization_algorithm_levenberg.h.

void g2o::OptimizationAlgorithmLevenberg::printVerbose ( std::ostream &  os) const
virtual

called by the optimizer if verbose. re-implement, if you want to print something

Reimplemented from g2o::OptimizationAlgorithm.

Definition at line 201 of file optimization_algorithm_levenberg.cpp.

void g2o::OptimizationAlgorithmLevenberg::setMaxTrialsAfterFailure ( int  max_trials)

the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt

Definition at line 191 of file optimization_algorithm_levenberg.cpp.

void g2o::OptimizationAlgorithmLevenberg::setUserLambdaInit ( double  lambda)

specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to compute a suitable value

Definition at line 196 of file optimization_algorithm_levenberg.cpp.

OptimizationAlgorithm::SolverResult g2o::OptimizationAlgorithmLevenberg::solve ( int  iteration,
bool  online = false 
)
virtual

Solve one iteration. The SparseOptimizer running on-top will call this for the given number of iterations.

Parameters
iterationindicates the current iteration

Implements g2o::OptimizationAlgorithm.

Definition at line 61 of file optimization_algorithm_levenberg.cpp.

double g2o::OptimizationAlgorithmLevenberg::userLambdaInit ( )
inline

return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda

Definition at line 61 of file optimization_algorithm_levenberg.h.

Member Data Documentation

double g2o::OptimizationAlgorithmLevenberg::_currentLambda
protected

Definition at line 72 of file optimization_algorithm_levenberg.h.

double g2o::OptimizationAlgorithmLevenberg::_goodStepLowerScale
protected

lower bound for lambda decrease if a good LM step

Definition at line 74 of file optimization_algorithm_levenberg.h.

double g2o::OptimizationAlgorithmLevenberg::_goodStepUpperScale
protected

upper bound for lambda decrease if a good LM step

Definition at line 75 of file optimization_algorithm_levenberg.h.

int g2o::OptimizationAlgorithmLevenberg::_levenbergIterations
protected

the numer of levenberg iterations performed to accept the last step

Definition at line 77 of file optimization_algorithm_levenberg.h.

Property<int>* g2o::OptimizationAlgorithmLevenberg::_maxTrialsAfterFailure
protected

Definition at line 70 of file optimization_algorithm_levenberg.h.

int g2o::OptimizationAlgorithmLevenberg::_nBad
protected

Definition at line 79 of file optimization_algorithm_levenberg.h.

double g2o::OptimizationAlgorithmLevenberg::_ni
protected

Definition at line 76 of file optimization_algorithm_levenberg.h.

double g2o::OptimizationAlgorithmLevenberg::_tau
protected

Definition at line 73 of file optimization_algorithm_levenberg.h.

Property<double>* g2o::OptimizationAlgorithmLevenberg::_userLambdaInit
protected

Definition at line 71 of file optimization_algorithm_levenberg.h.


The documentation for this class was generated from the following files:


orb_slam2_ros
Author(s):
autogenerated on Wed Apr 21 2021 02:53:06