optimization_algorithm_levenberg.h
Go to the documentation of this file.
1 // g2o - General Graph Optimization
2 // Copyright (C) 2011 R. Kuemmerle, G. Grisetti, W. Burgard
3 // All rights reserved.
4 //
5 // Redistribution and use in source and binary forms, with or without
6 // modification, are permitted provided that the following conditions are
7 // met:
8 //
9 // * Redistributions of source code must retain the above copyright notice,
10 // this list of conditions and the following disclaimer.
11 // * Redistributions in binary form must reproduce the above copyright
12 // notice, this list of conditions and the following disclaimer in the
13 // documentation and/or other materials provided with the distribution.
14 //
15 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS
16 // IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED
17 // TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A
18 // PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT
19 // HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL,
20 // SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED
21 // TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR
22 // PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF
23 // LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING
24 // NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
25 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
26 
27 #ifndef G2O_SOLVER_LEVENBERG_H
28 #define G2O_SOLVER_LEVENBERG_H
29 
31 
32 namespace g2o {
33 
38  {
39  public:
46 
47  virtual SolverResult solve(int iteration, bool online = false);
48 
49  virtual void printVerbose(std::ostream& os) const;
50 
52  double currentLambda() const { return _currentLambda;}
53 
55  void setMaxTrialsAfterFailure(int max_trials);
56 
59 
61  double userLambdaInit() {return _userLambdaInit->value();}
63  void setUserLambdaInit(double lambda);
64 
67 
68  protected:
69  // Levenberg parameters
73  double _tau;
76  double _ni;
78  //RAUL
79  int _nBad;
80 
85  double computeLambdaInit() const;
86  double computeScale() const;
87 
88  };
89 
90 } // end namespace
91 
92 #endif
double currentLambda() const
return the currently used damping factor
double userLambdaInit()
return the lambda set by the user, if < 0 the SparseOptimizer will compute the initial lambda ...
double _goodStepLowerScale
lower bound for lambda decrease if a good LM step
double _goodStepUpperScale
upper bound for lambda decrease if a good LM step
const T & value() const
Definition: property.h:56
int _levenbergIterations
the numer of levenberg iterations performed to accept the last step
Implementation of the Levenberg Algorithm.
int maxTrialsAfterFailure() const
get the number of inner iterations for Levenberg-Marquardt
Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg.
Solver * solver()
return the underlying solver used to solve the linear system
Generic interface for a sparse solver operating on a graph which solves one iteration of the lineariz...
Definition: solver.h:43
virtual void printVerbose(std::ostream &os) const
void setUserLambdaInit(double lambda)
specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to com...
int levenbergIteration()
return the number of levenberg iterations performed in the last round
void setMaxTrialsAfterFailure(int max_trials)
the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt ...
virtual SolverResult solve(int iteration, bool online=false)


orb_slam2_ros
Author(s):
autogenerated on Mon Feb 28 2022 23:03:52