gtsam  4.0.0
gtsam
LevenbergMarquardtOptimizer.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 
21 #pragma once
22 
26 #include <boost/date_time/posix_time/posix_time.hpp>
27 
28 class NonlinearOptimizerMoreOptimizationTest;
29 
30 namespace gtsam {
31 
35 class GTSAM_EXPORT LevenbergMarquardtOptimizer: public NonlinearOptimizer {
36 
37 protected:
39  boost::posix_time::ptime startTime_;
40 
41  void initTime();
42 
43 public:
44  typedef boost::shared_ptr<LevenbergMarquardtOptimizer> shared_ptr;
45 
48 
57  LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues,
59 
67  LevenbergMarquardtOptimizer(const NonlinearFactorGraph& graph, const Values& initialValues,
68  const Ordering& ordering,
70 
73  }
74 
76 
79 
81  double lambda() const;
82 
84  int getInnerIterations() const;
85 
87  void print(const std::string& str = "") const {
88  std::cout << str << "LevenbergMarquardtOptimizer" << std::endl;
89  this->params_.print(" parameters:\n");
90  }
91 
93 
96 
101  GaussianFactorGraph::shared_ptr iterate() override;
102 
105  return params_;
106  }
107 
108  void writeLogFile(double currentError);
109 
111  virtual GaussianFactorGraph::shared_ptr linearize() const;
112 
114  GaussianFactorGraph buildDampedSystem(const GaussianFactorGraph& linear,
115  const VectorValues& sqrtHessianDiagonal) const;
116 
118  bool tryLambda(const GaussianFactorGraph& linear, const VectorValues& sqrtHessianDiagonal);
119 
121 
122 protected:
123 
125  const NonlinearOptimizerParams& _params() const override {
126  return params_;
127  }
128 };
129 
130 }
A non-templated config holding any types of Manifold-group elements.
Definition: Values.h:70
This is the abstract interface for classes that can optimize for the maximum-likelihood estimate of a...
Definition: NonlinearOptimizer.h:75
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
Definition: GaussianFactorGraph.h:74
A Linear Factor Graph is a factor graph where all factors are Gaussian, i.e.
Definition: GaussianFactorGraph.h:65
Base class and parameters for nonlinear optimization algorithms.
const LevenbergMarquardtParams params_
LM parameters.
Definition: LevenbergMarquardtOptimizer.h:38
This class represents a collection of vector-valued variables associated each with a unique integer i...
Definition: VectorValues.h:73
Parameters for Levenberg-Marquardt optimization.
Definition: LevenbergMarquardtParams.h:33
const LevenbergMarquardtParams & params() const
Read-only access the parameters.
Definition: LevenbergMarquardtOptimizer.h:104
void print(const std::string &str="") const
print
Definition: LevenbergMarquardtOptimizer.h:87
A non-linear factor graph is a graph of non-Gaussian, i.e.
Definition: NonlinearFactorGraph.h:77
This class performs Levenberg-Marquardt nonlinear optimization.
Definition: LevenbergMarquardtOptimizer.h:35
Global functions in a separate testing namespace.
Definition: chartTesting.h:28
The common parameters for Nonlinear optimizers.
Definition: NonlinearOptimizerParams.h:34
Definition: Ordering.h:34
const NonlinearOptimizerParams & _params() const override
Access the parameters (base class version)
Definition: LevenbergMarquardtOptimizer.h:125
virtual ~LevenbergMarquardtOptimizer()
Virtual destructor.
Definition: LevenbergMarquardtOptimizer.h:72
Factor Graph Values.
Parameters for Levenberg-Marquardt trust-region scheme.