LevenbergMarquardtOptimizer.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, Georgia Tech Research Corporation,
4  * Atlanta, Georgia 30332-0415
5  * All Rights Reserved
6  * Authors: Frank Dellaert, et al. (see THANKS for the full author list)
7 
8  * See LICENSE for the license information
9 
10  * -------------------------------------------------------------------------- */
11 
24 #include <gtsam/nonlinear/Values.h>
28 #include <gtsam/base/Vector.h>
29 #include <gtsam/base/timing.h>
30 
31 #include <boost/format.hpp>
32 #include <boost/optional.hpp>
33 #include <boost/range/adaptor/map.hpp>
34 
35 #include <cmath>
36 #include <fstream>
37 #include <iostream>
38 #include <limits>
39 #include <string>
40 
41 using namespace std;
42 
43 namespace gtsam {
44 
45 using boost::adaptors::map_values;
46 typedef internal::LevenbergMarquardtState State;
47 
48 /* ************************************************************************* */
49 LevenbergMarquardtOptimizer::LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph,
50  const Values& initialValues,
53  graph, std::unique_ptr<State>(new State(initialValues, graph.error(initialValues),
54  params.lambdaInitial, params.lambdaFactor))),
55  params_(LevenbergMarquardtParams::EnsureHasOrdering(params, graph)) {}
56 
58  const Values& initialValues,
59  const Ordering& ordering,
62  graph, std::unique_ptr<State>(new State(initialValues, graph.error(initialValues),
63  params.lambdaInitial, params.lambdaFactor))),
64  params_(LevenbergMarquardtParams::ReplaceOrdering(params, ordering)) {}
65 
66 /* ************************************************************************* */
68  startTime_ = boost::posix_time::microsec_clock::universal_time();
69 }
70 
71 /* ************************************************************************* */
73  auto currentState = static_cast<const State*>(state_.get());
74  return currentState->lambda;
75 }
76 
77 /* ************************************************************************* */
79  auto currentState = static_cast<const State*>(state_.get());
80  return currentState->totalNumberInnerIterations;
81 }
82 
83 /* ************************************************************************* */
85  return graph_.linearize(state_->values);
86 }
87 
88 /* ************************************************************************* */
90  const GaussianFactorGraph& linear, const VectorValues& sqrtHessianDiagonal) const {
91  gttic(damp);
92  auto currentState = static_cast<const State*>(state_.get());
93 
95  std::cout << "building damped system with lambda " << currentState->lambda << std::endl;
96 
98  return currentState->buildDampedSystem(linear, sqrtHessianDiagonal);
99  else
100  return currentState->buildDampedSystem(linear);
101 }
102 
103 /* ************************************************************************* */
104 // Log current error/lambda to file
105 inline void LevenbergMarquardtOptimizer::writeLogFile(double currentError){
106  auto currentState = static_cast<const State*>(state_.get());
107 
108  if (!params_.logFile.empty()) {
109  ofstream os(params_.logFile.c_str(), ios::app);
110  boost::posix_time::ptime currentTime = boost::posix_time::microsec_clock::universal_time();
111  os << /*inner iterations*/ currentState->totalNumberInnerIterations << ","
112  << 1e-6 * (currentTime - startTime_).total_microseconds() << ","
113  << /*current error*/ currentError << "," << currentState->lambda << ","
114  << /*outer iterations*/ currentState->iterations << endl;
115  }
116 }
117 
118 /* ************************************************************************* */
120  const VectorValues& sqrtHessianDiagonal) {
121  auto currentState = static_cast<const State*>(state_.get());
123 
124 #ifdef GTSAM_USING_NEW_BOOST_TIMERS
125  boost::timer::cpu_timer lamda_iteration_timer;
126  lamda_iteration_timer.start();
127 #else
128  boost::timer lamda_iteration_timer;
129  lamda_iteration_timer.restart();
130 #endif
131 
132  if (verbose)
133  cout << "trying lambda = " << currentState->lambda << endl;
134 
135  // Build damped system for this lambda (adds prior factors that make it like gradient descent)
136  auto dampedSystem = buildDampedSystem(linear, sqrtHessianDiagonal);
137 
138  // Try solving
139  double modelFidelity = 0.0;
140  bool step_is_successful = false;
141  bool stopSearchingLambda = false;
142  double newError = numeric_limits<double>::infinity(), costChange;
143  Values newValues;
145 
146  bool systemSolvedSuccessfully;
147  try {
148  // ============ Solve is where most computation happens !! =================
149  delta = solve(dampedSystem, params_);
150  systemSolvedSuccessfully = true;
151  } catch (const IndeterminantLinearSystemException&) {
152  systemSolvedSuccessfully = false;
153  }
154 
155  if (systemSolvedSuccessfully) {
156  if (verbose)
157  cout << "linear delta norm = " << delta.norm() << endl;
159  delta.print("delta");
160 
161  // Compute the old linearized error as it is not the same
162  // as the nonlinear error when robust noise models are used.
163  double oldLinearizedError = linear.error(VectorValues::Zero(delta));
164  double newlinearizedError = linear.error(delta);
165 
166  // cost change in the linearized system (old - new)
167  double linearizedCostChange = oldLinearizedError - newlinearizedError;
168  if (verbose)
169  cout << "newlinearizedError = " << newlinearizedError
170  << " linearizedCostChange = " << linearizedCostChange << endl;
171 
172  if (linearizedCostChange >= 0) { // step is valid
173  // update values
174  gttic(retract);
175  // ============ This is where the solution is updated ====================
176  newValues = currentState->values.retract(delta);
177  // =======================================================================
178  gttoc(retract);
179 
180  // compute new error
181  gttic(compute_error);
182  if (verbose)
183  cout << "calculating error:" << endl;
184  newError = graph_.error(newValues);
185  gttoc(compute_error);
186 
187  if (verbose)
188  cout << "old error (" << currentState->error << ") new (tentative) error (" << newError
189  << ")" << endl;
190 
191  // cost change in the original, nonlinear system (old - new)
192  costChange = currentState->error - newError;
193 
194  if (linearizedCostChange > std::numeric_limits<double>::epsilon() * oldLinearizedError) {
195  // the (linear) error has to decrease to satisfy this condition
196  // fidelity of linearized model VS original system between
197  modelFidelity = costChange / linearizedCostChange;
198  // if we decrease the error in the nonlinear system and modelFidelity is above threshold
199  step_is_successful = modelFidelity > params_.minModelFidelity;
200  if (verbose)
201  cout << "modelFidelity: " << modelFidelity << endl;
202  } // else we consider the step non successful and we either increase lambda or stop if error
203  // change is small
204 
205  double minAbsoluteTolerance = params_.relativeErrorTol * currentState->error;
206  // if the change is small we terminate
207  if (std::abs(costChange) < minAbsoluteTolerance) {
208  if (verbose)
209  cout << "abs(costChange)=" << std::abs(costChange)
210  << " minAbsoluteTolerance=" << minAbsoluteTolerance
211  << " (relativeErrorTol=" << params_.relativeErrorTol << ")" << endl;
212  stopSearchingLambda = true;
213  }
214  }
215  } // if (systemSolvedSuccessfully)
216 
218 // do timing
219 #ifdef GTSAM_USING_NEW_BOOST_TIMERS
220  double iterationTime = 1e-9 * lamda_iteration_timer.elapsed().wall;
221 #else
222  double iterationTime = lamda_iteration_timer.elapsed();
223 #endif
224  if (currentState->iterations == 0)
225  cout << "iter cost cost_change lambda success iter_time" << endl;
226 
227  cout << boost::format("% 4d % 8e % 3.2e % 3.2e % 4d % 3.2e") % currentState->iterations %
228  newError % costChange % currentState->lambda % systemSolvedSuccessfully %
229  iterationTime << endl;
230  }
231 
232  if (step_is_successful) {
233  // we have successfully decreased the cost and we have good modelFidelity
234  // NOTE(frank): As we return immediately after this, we move the newValues
235  // TODO(frank): make Values actually support move. Does not seem to happen now.
236  state_ = currentState->decreaseLambda(params_, modelFidelity, std::move(newValues), newError);
237  return true;
238  } else if (!stopSearchingLambda) { // we failed to solved the system or had no decrease in cost
239  if (verbose)
240  cout << "increasing lambda" << endl;
241  State* modifiedState = static_cast<State*>(state_.get());
242  modifiedState->increaseLambda(params_); // TODO(frank): make this functional with Values move
243 
244  // check if lambda is too big
245  if (modifiedState->lambda >= params_.lambdaUpperBound) {
248  cout << "Warning: Levenberg-Marquardt giving up because "
249  "cannot decrease error with maximum lambda" << endl;
250  return true;
251  } else {
252  return false; // only case where we will keep trying
253  }
254  } else { // the change in the cost is very small and it is not worth trying bigger lambdas
255  if (verbose)
256  cout << "Levenberg-Marquardt: stopping as relative cost reduction is small" << endl;
257  return true;
258  }
259 }
260 
261 /* ************************************************************************* */
263  auto currentState = static_cast<const State*>(state_.get());
264 
265  gttic(LM_iterate);
266 
267  // Linearize graph
269  cout << "linearizing = " << endl;
271 
272  if(currentState->totalNumberInnerIterations==0) { // write initial error
273  writeLogFile(currentState->error);
274 
276  cout << "Initial error: " << currentState->error
277  << ", values: " << currentState->values.size() << std::endl;
278  }
279  }
280 
281  // Only calculate diagonal of Hessian (expensive) once per outer iteration, if we need it
282  VectorValues sqrtHessianDiagonal;
283  if (params_.diagonalDamping) {
284  sqrtHessianDiagonal = linear->hessianDiagonal();
285  for (Vector& v : sqrtHessianDiagonal | map_values) {
286  v = v.cwiseMax(params_.minDiagonal).cwiseMin(params_.maxDiagonal).cwiseSqrt();
287  }
288  }
289 
290  // Keep increasing lambda until we make make progress
291  while (!tryLambda(*linear, sqrtHessianDiagonal)) {
292  auto newState = static_cast<const State*>(state_.get());
293  writeLogFile(newState->error);
294  }
295 
296  return linear;
297 }
298 
299 } /* namespace gtsam */
300 
double norm() const
A non-templated config holding any types of Manifold-group elements.
Factor Graph consisting of non-linear factors.
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
bool tryLambda(const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal)
ArrayXcf v
Definition: Cwise_arg.cpp:1
const NonlinearFactorGraph & graph() const
return the graph with nonlinear factors
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: Half.h:150
double maxDiagonal
when using diagonal damping saturates the maximum diagonal entries (default: 1e32) ...
A LevenbergMarquardtState class containing most of the logic for Levenberg-Marquardt.
Values retract(const VectorValues &delta) const
Definition: Values.cpp:109
double minModelFidelity
Lower bound for the modelFidelity to accept the result of an LM iteration.
NonlinearFactorGraph graph
static double epsilon
Definition: testRot3.cpp:39
double error(const VectorValues &x) const
const bool verbose
double relativeErrorTol
The maximum relative error decrease to stop iterating (default 1e-5)
static VectorValues Zero(const VectorValues &other)
std::unique_ptr< internal::NonlinearOptimizerState > state_
PIMPL&#39;d state.
LevenbergMarquardtOptimizer(const NonlinearFactorGraph &graph, const Values &initialValues, const LevenbergMarquardtParams &params=LevenbergMarquardtParams())
#define gttic(label)
Definition: timing.h:280
Eigen::VectorXd Vector
Definition: Vector.h:38
std::string logFile
an optional CSV log file, with [iteration, time, error, lambda]
const LevenbergMarquardtParams params_
LM parameters.
const LevenbergMarquardtParams & params() const
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
double lambda() const
Access the current damping value.
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
double error() const
return error in current optimizer state
GaussianFactorGraph buildDampedSystem(const GaussianFactorGraph &linear, const VectorValues &sqrtHessianDiagonal) const
Exceptions that may be thrown by linear solver components.
int getInnerIterations() const
Access the current number of inner iterations.
internal::DoglegState State
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
bool diagonalDamping
if true, use diagonal of Hessian
virtual GaussianFactorGraph::shared_ptr linearize() const
ofstream os("timeSchurFactors.csv")
#define gttoc(label)
Definition: timing.h:281
double minDiagonal
when using diagonal damping saturates the minimum diagonal entries (default: 1e-6) ...
NonlinearFactorGraph graph_
The graph with nonlinear factors.
virtual VectorValues solve(const GaussianFactorGraph &gfg, const NonlinearOptimizerParams &params) const
GaussianFactorGraph::shared_ptr iterate() override
static double error
Definition: testRot3.cpp:39
double error(const Values &values) const
void print(const std::string &str="VectorValues", const KeyFormatter &formatter=DefaultKeyFormatter) const
double lambdaUpperBound
The maximum lambda to try before assuming the optimization has failed (default: 1e5) ...
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
boost::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
#define abs(x)
Definition: datatypes.h:17
static BenchTimer timer
Timing utilities.


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:31