optimization_algorithm_levenberg.cpp
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 // Modified Raul Mur Artal (2014)
28 // - Stop criterium (solve function)
29 
31 
32 #include <iostream>
33 
34 #include "../stuff/timeutil.h"
35 
36 #include "sparse_optimizer.h"
37 #include "solver.h"
38 #include "batch_stats.h"
39 using namespace std;
40 
41 namespace g2o {
42 
43  OptimizationAlgorithmLevenberg::OptimizationAlgorithmLevenberg(Solver* solver) :
45  {
46  _currentLambda = -1.;
47  _tau = 1e-5;
48  _goodStepUpperScale = 2./3.;
49  _goodStepLowerScale = 1./3.;
51  _maxTrialsAfterFailure = _properties.makeProperty<Property<int> >("maxTrialsAfterFailure", 10);
52  _ni=2.;
54  _nBad = 0;
55  }
56 
58  {
59  }
60 
62  {
63  assert(_optimizer && "_optimizer not set");
64  assert(_solver->optimizer() == _optimizer && "underlying linear solver operates on different graph");
65 
66  if (iteration == 0 && !online) { // built up the CCS structure, here due to easy time measure
67  bool ok = _solver->buildStructure();
68  if (! ok) {
69  cerr << __PRETTY_FUNCTION__ << ": Failure while building CCS structure" << endl;
71  }
72  }
73 
74  double t=get_monotonic_time();
77  if (globalStats) {
78  globalStats->timeResiduals = get_monotonic_time()-t;
80  }
81 
82  double currentChi = _optimizer->activeRobustChi2();
83  double tempChi=currentChi;
84 
85  double iniChi = currentChi;
86 
88  if (globalStats) {
89  globalStats->timeQuadraticForm = get_monotonic_time()-t;
90  }
91 
92  // core part of the Levenbarg algorithm
93  if (iteration == 0) {
95  _ni = 2;
96  _nBad = 0;
97  }
98 
99  double rho=0;
100  int& qmax = _levenbergIterations;
101  qmax = 0;
102  do {
103  _optimizer->push();
104  if (globalStats) {
105  globalStats->levenbergIterations++;
106  t=get_monotonic_time();
107  }
108  // update the diagonal of the system matrix
110  bool ok2 = _solver->solve();
111  if (globalStats) {
112  globalStats->timeLinearSolution+=get_monotonic_time()-t;
113  t=get_monotonic_time();
114  }
115  _optimizer->update(_solver->x());
116  if (globalStats) {
117  globalStats->timeUpdate = get_monotonic_time()-t;
118  }
119 
120  // restore the diagonal
122 
124  tempChi = _optimizer->activeRobustChi2();
125 
126  if (! ok2)
127  tempChi=std::numeric_limits<double>::max();
128 
129  rho = (currentChi-tempChi);
130  double scale = computeScale();
131  scale += 1e-3; // make sure it's non-zero :)
132  rho /= scale;
133 
134  if (rho>0 && g2o_isfinite(tempChi)){ // last step was good
135  double alpha = 1.-pow((2*rho-1),3);
136  // crop lambda between minimum and maximum factors
137  alpha = (std::min)(alpha, _goodStepUpperScale);
138  double scaleFactor = (std::max)(_goodStepLowerScale, alpha);
139  _currentLambda *= scaleFactor;
140  _ni = 2;
141  currentChi=tempChi;
143  } else {
145  _ni*=2;
146  _optimizer->pop(); // restore the last state before trying to optimize
147  }
148  qmax++;
149  } while (rho<0 && qmax < _maxTrialsAfterFailure->value() && ! _optimizer->terminate());
150 
151  if (qmax == _maxTrialsAfterFailure->value() || rho==0)
152  return Terminate;
153 
154  //Stop criterium (Raul)
155  if((iniChi-currentChi)*1e3<iniChi)
156  _nBad++;
157  else
158  _nBad=0;
159 
160  if(_nBad>=3)
161  return Terminate;
162 
163  return OK;
164  }
165 
167  {
168  if (_userLambdaInit->value() > 0)
169  return _userLambdaInit->value();
170  double maxDiagonal=0.;
171  for (size_t k = 0; k < _optimizer->indexMapping().size(); k++) {
173  assert(v);
174  int dim = v->dimension();
175  for (int j = 0; j < dim; ++j){
176  maxDiagonal = std::max(fabs(v->hessian(j,j)),maxDiagonal);
177  }
178  }
179  return _tau*maxDiagonal;
180  }
181 
183  {
184  double scale = 0.;
185  for (size_t j=0; j < _solver->vectorSize(); j++){
186  scale += _solver->x()[j] * (_currentLambda * _solver->x()[j] + _solver->b()[j]);
187  }
188  return scale;
189  }
190 
192  {
193  _maxTrialsAfterFailure->setValue(max_trials);
194  }
195 
197  {
198  _userLambdaInit->setValue(lambda);
199  }
200 
201  void OptimizationAlgorithmLevenberg::printVerbose(std::ostream& os) const
202  {
203  os
204  << "\t schur= " << _solver->schur()
205  << "\t lambda= " << FIXED(_currentLambda)
206  << "\t levenbergIter= " << _levenbergIterations;
207  }
208 
209 } // end namespace
virtual void restoreDiagonal()=0
virtual bool schur()=0
should the solver perform the schur complement or not
statistics about the optimization
Definition: batch_stats.h:39
bool terminate()
if external stop flag is given, return its state. False otherwise
#define __PRETTY_FUNCTION__
Definition: macros.h:95
double _goodStepLowerScale
lower bound for lambda decrease if a good LM step
virtual const double & hessian(int i, int j) const =0
get the element from the hessian matrix
double _goodStepUpperScale
upper bound for lambda decrease if a good LM step
double timeResiduals
residuals
Definition: batch_stats.h:48
int _levenbergIterations
the numer of levenberg iterations performed to accept the last step
virtual void printVerbose(std::ostream &os) const
void pop(SparseOptimizer::VertexContainer &vlist)
pop (restore) the estimate a subset of the variables from the stack
virtual bool setLambda(double lambda, bool backup=false)=0
int levenbergIterations
number of iterations performed by LM
Definition: batch_stats.h:51
void discardTop(SparseOptimizer::VertexContainer &vlist)
ignore the latest stored element on the stack, remove it from the stack but do not restore the estima...
Base for solvers operating on the approximated Hessian, e.g., Gauss-Newton, Levenberg.
PropertyMap _properties
the properties of your solver, use this to store the parameters of your solver
int dimension() const
dimension of the estimated state belonging to this node
P * makeProperty(const std::string &name_, const typename P::ValueType &v)
Definition: property.h:118
void setValue(const T &v)
Definition: property.h:55
Generic interface for a sparse solver operating on a graph which solves one iteration of the lineariz...
Definition: solver.h:43
SparseOptimizer * _optimizer
the optimizer the solver is working on
static G2OBatchStatistics * globalStats()
Definition: batch_stats.h:72
const VertexContainer & indexMapping() const
the index mapping of the vertices
double get_monotonic_time()
Definition: timeutil.cpp:113
SparseOptimizer * optimizer() const
the optimizer (graph) on which the solver works
Definition: solver.h:105
virtual bool solve()=0
A general case Vertex for optimization.
double * x()
return x, the solution vector
Definition: solver.h:95
#define g2o_isfinite(x)
Definition: macros.h:107
void setUserLambdaInit(double lambda)
specify the initial lambda used for the first iteraion, if not given the SparseOptimizer tries to com...
double timeUpdate
time to apply the update
Definition: batch_stats.h:61
double * b()
return b, the right hand side of the system
Definition: solver.h:98
virtual bool buildSystem()=0
size_t vectorSize() const
return the size of the solution vector (x) and b
Definition: solver.h:102
double activeRobustChi2() const
const T & value() const
Definition: property.h:56
double timeQuadraticForm
construct the quadratic form in the graph
Definition: batch_stats.h:50
void setMaxTrialsAfterFailure(int max_trials)
the number of internal iteration if an update step increases chi^2 within Levenberg-Marquardt ...
void push(SparseOptimizer::VertexContainer &vlist)
push the estimate of a subset of the variables onto a stack
double timeLinearSolution
total time for solving Ax=b (including detup for schur)
Definition: batch_stats.h:58
virtual SolverResult solve(int iteration, bool online=false)
virtual bool buildStructure(bool zeroBlocks=false)=0


orb_slam2_with_maps_odom
Author(s): teng zhang
autogenerated on Fri Sep 25 2020 03:24:47