LevenbergMarquardtState.h
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 
20 
21 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/base/Matrix.h>
26 #include <gtsam/base/Vector.h>
27 
28 #include <boost/shared_ptr.hpp>
29 
30 #include <algorithm>
31 #include <cmath>
32 #include <stdexcept>
33 #include <vector>
34 
35 namespace gtsam {
36 
37 namespace internal {
38 
39 // TODO(frank): once Values supports move, we can make State completely functional.
40 // As it is now, increaseLambda is non-const or otherwise we make a Values copy every time
41 // decreaseLambda would also benefit from a working Values move constructor
44 
45  // TODO(frank): make these const once increaseLambda can be made const
46  double lambda;
47  double currentFactor;
49  // optimization (for each iteration, LM tries multiple
50  // inner iterations with different lambdas)
51 
52  LevenbergMarquardtState(const Values& initialValues, double error, double lambda,
53  double currentFactor, unsigned int iterations = 0,
54  unsigned int totalNumberInnerIterations = 0)
55  : NonlinearOptimizerState(initialValues, error, iterations),
56  lambda(lambda),
57  currentFactor(currentFactor),
58  totalNumberInnerIterations(totalNumberInnerIterations) {}
59 
60  // Constructor version that takes ownership of values
61  LevenbergMarquardtState(Values&& initialValues, double error, double lambda, double currentFactor,
62  unsigned int iterations = 0, unsigned int totalNumberInnerIterations = 0)
63  : NonlinearOptimizerState(initialValues, error, iterations),
64  lambda(lambda),
65  currentFactor(currentFactor),
66  totalNumberInnerIterations(totalNumberInnerIterations) {}
67 
68  // Applies policy to *increase* lambda: should be used if the current update was NOT successful
69  // TODO(frank): non-const method until Values properly support std::move
71  lambda *= currentFactor;
72  totalNumberInnerIterations += 1;
73  if (!params.useFixedLambdaFactor) {
74  currentFactor *= 2.0;
75  }
76  }
77 
78  // Apply policy to decrease lambda if the current update was successful
79  // stepQuality not used in the naive policy)
80  // Take ownsership of newValues, must be passed an rvalue
81  std::unique_ptr<This> decreaseLambda(const LevenbergMarquardtParams& params, double stepQuality,
82  Values&& newValues, double newError) const {
83  double newLambda = lambda, newFactor = currentFactor;
84  if (params.useFixedLambdaFactor) {
85  newLambda /= currentFactor;
86  } else {
87  // TODO(frank): odd that currentFactor is not used to change lambda here...
88  newLambda *= std::max(1.0 / 3.0, 1.0 - pow(2.0 * stepQuality - 1.0, 3));
89  newFactor = 2.0 * currentFactor;
90  }
91  newLambda = std::max(params.lambdaLowerBound, newLambda);
92  return std::unique_ptr<This>(new This(std::move(newValues), newError, newLambda, newFactor,
93  iterations + 1, totalNumberInnerIterations + 1));
94  }
95 
98  struct CachedModel {
99  CachedModel() {} // default int makes zero-size matrices
100  CachedModel(int dim, double sigma)
101  : A(Matrix::Identity(dim, dim)),
102  b(Vector::Zero(dim)),
103  model(noiseModel::Isotropic::Sigma(dim, sigma)) {}
104  CachedModel(int dim, double sigma, const Vector& diagonal)
105  : A(Eigen::DiagonalMatrix<double, Eigen::Dynamic>(diagonal)),
106  b(Vector::Zero(dim)),
107  model(noiseModel::Isotropic::Sigma(dim, sigma)) {}
111  };
112 
113  // Small cache of A|b|model indexed by dimension. Can save many mallocs.
114  mutable std::vector<CachedModel> noiseModelCache;
115  CachedModel* getCachedModel(size_t dim) const {
116  if (dim >= noiseModelCache.size())
117  noiseModelCache.resize(dim+1);
118  CachedModel* item = &noiseModelCache[dim];
119  if (!item->model)
120  *item = CachedModel(dim, 1.0 / std::sqrt(lambda));
121  return item;
122  };
123 
126  noiseModelCache.resize(0);
127  // for each of the variables, add a prior
128  damped.reserve(damped.size() + values.size());
129  for (const auto key_value : values) {
130  const Key key = key_value.key;
131  const size_t dim = key_value.value.dim();
132  const CachedModel* item = getCachedModel(dim);
133  damped += boost::make_shared<JacobianFactor>(key, item->A, item->b, item->model);
134  }
135  return damped;
136  }
137 
140  const VectorValues& sqrtHessianDiagonal) const {
141  noiseModelCache.resize(0);
142  damped.reserve(damped.size() + values.size());
143  for (const auto& key_vector : sqrtHessianDiagonal) {
144  try {
145  const Key key = key_vector.first;
146  const size_t dim = key_vector.second.size();
147  CachedModel* item = getCachedModel(dim);
148  item->A.diagonal() = sqrtHessianDiagonal.at(key); // use diag(hessian)
149  damped += boost::make_shared<JacobianFactor>(key, item->A, item->b, item->model);
150  } catch (const std::out_of_range&) {
151  continue; // Don't attempt any damping if no key found in diagonal
152  }
153  }
154  return damped;
155  }
156 };
157 
158 } // namespace internal
159 
160 } /* namespace gtsam */
size_t size() const
Definition: FactorGraph.h:306
LevenbergMarquardtState(Values &&initialValues, double error, double lambda, double currentFactor, unsigned int iterations=0, unsigned int totalNumberInnerIterations=0)
#define max(a, b)
Definition: datatypes.h:20
CachedModel * getCachedModel(size_t dim) const
A non-templated config holding any types of Manifold-group elements.
GaussianFactorGraph buildDampedSystem(GaussianFactorGraph damped) const
Build a damped system for a specific lambda, vanilla version.
static const double sigma
void diagonal(const MatrixType &m)
Definition: diagonal.cpp:12
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:43
EIGEN_DEVICE_FUNC const SqrtReturnType sqrt() const
Namespace containing all symbols from the Eigen library.
Definition: jet.h:637
GaussianFactorGraph buildDampedSystem(GaussianFactorGraph damped, const VectorValues &sqrtHessianDiagonal) const
Build a damped system, use hessianDiagonal per variable (more expensive)
std::unique_ptr< This > decreaseLambda(const LevenbergMarquardtParams &params, double stepQuality, Values &&newValues, double newError) const
Eigen::VectorXd Vector
Definition: Vector.h:38
size_t size() const
Definition: Values.h:236
CachedModel(int dim, double sigma, const Vector &diagonal)
bool useFixedLambdaFactor
if true applies constant increase (or decrease) to lambda according to lambdaFactor ...
Linear Factor Graph where all factors are Gaussians.
static SmartStereoProjectionParams params
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
double lambdaLowerBound
The minimum lambda used in LM (default: 0)
LevenbergMarquardtState(const Values &initialValues, double error, double lambda, double currentFactor, unsigned int iterations=0, unsigned int totalNumberInnerIterations=0)
Private class for NonlinearOptimizer state.
void resize(size_t size)
Definition: FactorGraph.h:358
int totalNumberInnerIterations
The total number of inner iterations in the.
void reserve(size_t size)
Definition: FactorGraph.h:162
const int Dynamic
Definition: Constants.h:21
Jet< T, N > pow(const Jet< T, N > &f, double g)
Definition: jet.h:570
friend const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t rnd_mode)
Definition: mpreal.h:2201
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
void increaseLambda(const LevenbergMarquardtParams &params)


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