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 }
void print(const std::string &str="") const override
Parameters for Levenberg-Marquardt trust-region scheme.
static enum @843 ordering
boost::shared_ptr< This > shared_ptr
shared_ptr to this class
NonlinearFactorGraph graph
const NonlinearOptimizerParams & _params() const override
boost::shared_ptr< LevenbergMarquardtOptimizer > shared_ptr
void print(const std::string &str="") const
print
Factor Graph Values.
Definition: pytypes.h:928
const LevenbergMarquardtParams params_
LM parameters.
const LevenbergMarquardtParams & params() const
static SmartStereoProjectionParams params
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
traits
Definition: chartTesting.h:28
Base class and parameters for nonlinear optimization algorithms.


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