LevenbergMarquardtParams.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 
25 
26 namespace gtsam {
27 
28 class LevenbergMarquardtOptimizer;
29 
36 
37 public:
39  enum VerbosityLM {
40  SILENT = 0, SUMMARY, TERMINATION, LAMBDA, TRYLAMBDA, TRYCONFIG, DAMPED, TRYDELTA
41  };
42 
43  static VerbosityLM verbosityLMTranslator(const std::string &s);
44  static std::string verbosityLMTranslator(VerbosityLM value);
46 
47 public:
48 
49  double lambdaInitial;
50  double lambdaFactor;
55  std::string logFile;
58  double minDiagonal;
59  double maxDiagonal;
60 
62  : verbosityLM(SILENT),
63  diagonalDamping(false),
64  minDiagonal(1e-6),
65  maxDiagonal(1e32) {
66  SetLegacyDefaults(this);
67  }
68 
70  // Relevant NonlinearOptimizerParams:
71  p->maxIterations = 100;
72  p->relativeErrorTol = 1e-5;
73  p->absoluteErrorTol = 1e-5;
74  // LM-specific:
75  p->lambdaInitial = 1e-5;
76  p->lambdaFactor = 10.0;
77  p->lambdaUpperBound = 1e5;
78  p->lambdaLowerBound = 0.0;
79  p->minModelFidelity = 1e-3;
80  p->diagonalDamping = false;
81  p->useFixedLambdaFactor = true;
82  }
83 
84  // these do seem to work better for SFM
86  // Relevant NonlinearOptimizerParams:
87  p->maxIterations = 50;
88  p->absoluteErrorTol = 0; // No corresponding option in CERES
89  p->relativeErrorTol = 1e-6; // This is function_tolerance
90  // LM-specific:
91  p->lambdaUpperBound = 1e32;
92  p->lambdaLowerBound = 1e-16;
93  p->lambdaInitial = 1e-04;
94  p->lambdaFactor = 2.0;
95  p->minModelFidelity = 1e-3; // options.min_relative_decrease in CERES
96  p->diagonalDamping = true;
97  p->useFixedLambdaFactor = false; // This is important
98  }
99 
102  SetLegacyDefaults(&p);
103  return p;
104  }
105 
108  SetCeresDefaults(&p);
109  return p;
110  }
111 
113  const NonlinearFactorGraph& graph) {
114  if (!params.ordering)
115  params.ordering = Ordering::Create(params.orderingType, graph);
116  return params;
117  }
118 
120  const Ordering& ord) {
121  params.ordering = ord;
122  return params;
123  }
124 
126  void print(const std::string& str = "") const override;
127 
130  bool getDiagonalDamping() const { return diagonalDamping; }
131  double getlambdaFactor() const { return lambdaFactor; }
132  double getlambdaInitial() const { return lambdaInitial; }
133  double getlambdaLowerBound() const { return lambdaLowerBound; }
134  double getlambdaUpperBound() const { return lambdaUpperBound; }
135  bool getUseFixedLambdaFactor() { return useFixedLambdaFactor; }
136  std::string getLogFile() const { return logFile; }
137  std::string getVerbosityLM() const { return verbosityLMTranslator(verbosityLM);}
138 
139  void setDiagonalDamping(bool flag) { diagonalDamping = flag; }
140  void setlambdaFactor(double value) { lambdaFactor = value; }
141  void setlambdaInitial(double value) { lambdaInitial = value; }
142  void setlambdaLowerBound(double value) { lambdaLowerBound = value; }
143  void setlambdaUpperBound(double value) { lambdaUpperBound = value; }
144  void setUseFixedLambdaFactor(bool flag) { useFixedLambdaFactor = flag;}
145  void setLogFile(const std::string& s) { logFile = s; }
146  void setVerbosityLM(const std::string& s) { verbosityLM = verbosityLMTranslator(s);}
147  // @}
150 
152  std::shared_ptr<NonlinearOptimizerParams> clone() const {
153  return std::shared_ptr<NonlinearOptimizerParams>(new LevenbergMarquardtParams(*this));
154  }
155 
157 };
158 
159 }
gtsam::LevenbergMarquardtParams::setlambdaUpperBound
void setlambdaUpperBound(double value)
Definition: LevenbergMarquardtParams.h:143
gtsam::LevenbergMarquardtParams::ReplaceOrdering
static LevenbergMarquardtParams ReplaceOrdering(LevenbergMarquardtParams params, const Ordering &ord)
Definition: LevenbergMarquardtParams.h:119
s
RealScalar s
Definition: level1_cplx_impl.h:126
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::LevenbergMarquardtParams::setVerbosityLM
void setVerbosityLM(const std::string &s)
Definition: LevenbergMarquardtParams.h:146
gtsam::LevenbergMarquardtParams::setLogFile
void setLogFile(const std::string &s)
Definition: LevenbergMarquardtParams.h:145
gtsam::Ordering::Create
static Ordering Create(OrderingType orderingType, const FACTOR_GRAPH &graph)
Definition: inference/Ordering.h:217
gtsam::LevenbergMarquardtParams::minDiagonal
double minDiagonal
when using diagonal damping saturates the minimum diagonal entries (default: 1e-6)
Definition: LevenbergMarquardtParams.h:58
gtsam::LevenbergMarquardtParams::LevenbergMarquardtParams
LevenbergMarquardtParams()
Definition: LevenbergMarquardtParams.h:61
gtsam::LevenbergMarquardtParams::setlambdaInitial
void setlambdaInitial(double value)
Definition: LevenbergMarquardtParams.h:141
vanilla::params
static const SmartProjectionParams params
Definition: smartFactorScenarios.h:69
gtsam::LevenbergMarquardtParams::diagonalDamping
bool diagonalDamping
if true, use diagonal of Hessian
Definition: LevenbergMarquardtParams.h:56
gtsam::LevenbergMarquardtParams::logFile
std::string logFile
an optional CSV log file, with [iteration, time, error, lambda]
Definition: LevenbergMarquardtParams.h:55
gtsam::LevenbergMarquardtParams::getLogFile
std::string getLogFile() const
Definition: LevenbergMarquardtParams.h:136
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
gtsam::LevenbergMarquardtParams::EnsureHasOrdering
static LevenbergMarquardtParams EnsureHasOrdering(LevenbergMarquardtParams params, const NonlinearFactorGraph &graph)
Definition: LevenbergMarquardtParams.h:112
gtsam::LevenbergMarquardtParams::SetCeresDefaults
static void SetCeresDefaults(LevenbergMarquardtParams *p)
Definition: LevenbergMarquardtParams.h:85
gtsam::NonlinearOptimizerParams
Definition: NonlinearOptimizerParams.h:35
gtsam::LevenbergMarquardtParams::lambdaLowerBound
double lambdaLowerBound
The minimum lambda used in LM (default: 0)
Definition: LevenbergMarquardtParams.h:52
gtsam::LevenbergMarquardtParams::getlambdaFactor
double getlambdaFactor() const
Definition: LevenbergMarquardtParams.h:131
gtsam::NonlinearFactorGraph
Definition: NonlinearFactorGraph.h:55
gtsam::LevenbergMarquardtParams::TRYLAMBDA
@ TRYLAMBDA
Definition: LevenbergMarquardtParams.h:40
gtsam::LevenbergMarquardtParams::lambdaUpperBound
double lambdaUpperBound
The maximum lambda to try before assuming the optimization has failed (default: 1e5)
Definition: LevenbergMarquardtParams.h:51
gtsam::LevenbergMarquardtOptimizer
Definition: LevenbergMarquardtOptimizer.h:35
gtsam::LevenbergMarquardtParams::lambdaInitial
double lambdaInitial
The initial Levenberg-Marquardt damping term (default: 1e-5)
Definition: LevenbergMarquardtParams.h:49
gtsam::LevenbergMarquardtParams::getUseFixedLambdaFactor
bool getUseFixedLambdaFactor()
Definition: LevenbergMarquardtParams.h:135
gtsam::LevenbergMarquardtParams::getDiagonalDamping
bool getDiagonalDamping() const
Definition: LevenbergMarquardtParams.h:130
gtsam::LevenbergMarquardtParams::getVerbosityLM
std::string getVerbosityLM() const
Definition: LevenbergMarquardtParams.h:137
gtsam::LevenbergMarquardtParams::minModelFidelity
double minModelFidelity
Lower bound for the modelFidelity to accept the result of an LM iteration.
Definition: LevenbergMarquardtParams.h:54
gtsam::LevenbergMarquardtParams::setlambdaFactor
void setlambdaFactor(double value)
Definition: LevenbergMarquardtParams.h:140
str
Definition: pytypes.h:1524
gtsam
traits
Definition: chartTesting.h:28
gtsam::LevenbergMarquardtParams::CeresDefaults
static LevenbergMarquardtParams CeresDefaults()
Definition: LevenbergMarquardtParams.h:106
NonlinearFactorGraph.h
Factor Graph consisting of non-linear factors.
gtsam::LevenbergMarquardtParams::setlambdaLowerBound
void setlambdaLowerBound(double value)
Definition: LevenbergMarquardtParams.h:142
gtsam::LevenbergMarquardtParams::VerbosityLM
VerbosityLM
Definition: LevenbergMarquardtParams.h:39
gtsam::LevenbergMarquardtParams::getlambdaInitial
double getlambdaInitial() const
Definition: LevenbergMarquardtParams.h:132
p
float * p
Definition: Tutorial_Map_using.cpp:9
gtsam::LevenbergMarquardtParams
Definition: LevenbergMarquardtParams.h:35
gtsam::LevenbergMarquardtParams::LegacyDefaults
static LevenbergMarquardtParams LegacyDefaults()
Definition: LevenbergMarquardtParams.h:100
gtsam::LevenbergMarquardtParams::getlambdaLowerBound
double getlambdaLowerBound() const
Definition: LevenbergMarquardtParams.h:133
gtsam::LevenbergMarquardtParams::lambdaFactor
double lambdaFactor
The amount by which to multiply or divide lambda when adjusting lambda (default: 10....
Definition: LevenbergMarquardtParams.h:50
gtsam::LevenbergMarquardtParams::clone
std::shared_ptr< NonlinearOptimizerParams > clone() const
Definition: LevenbergMarquardtParams.h:152
gtsam::LevenbergMarquardtParams::useFixedLambdaFactor
bool useFixedLambdaFactor
if true applies constant increase (or decrease) to lambda according to lambdaFactor
Definition: LevenbergMarquardtParams.h:57
graph
NonlinearFactorGraph graph
Definition: doc/Code/OdometryExample.cpp:2
gtsam::LevenbergMarquardtParams::verbosityLM
VerbosityLM verbosityLM
The verbosity level for Levenberg-Marquardt (default: SILENT), see also NonlinearOptimizerParams::ver...
Definition: LevenbergMarquardtParams.h:53
NonlinearOptimizerParams.h
Parameters for nonlinear optimization.
gtsam::LevenbergMarquardtParams::getlambdaUpperBound
double getlambdaUpperBound() const
Definition: LevenbergMarquardtParams.h:134
gtsam::LevenbergMarquardtParams::maxDiagonal
double maxDiagonal
when using diagonal damping saturates the maximum diagonal entries (default: 1e32)
Definition: LevenbergMarquardtParams.h:59
gtsam::LevenbergMarquardtParams::setDiagonalDamping
void setDiagonalDamping(bool flag)
Definition: LevenbergMarquardtParams.h:139
gtsam::Ordering
Definition: inference/Ordering.h:33
gtsam::LevenbergMarquardtParams::~LevenbergMarquardtParams
~LevenbergMarquardtParams() override
Definition: LevenbergMarquardtParams.h:125
test_callbacks.value
value
Definition: test_callbacks.py:158
gtsam::LevenbergMarquardtParams::SetLegacyDefaults
static void SetLegacyDefaults(LevenbergMarquardtParams *p)
Definition: LevenbergMarquardtParams.h:69
gtsam::LevenbergMarquardtParams::setUseFixedLambdaFactor
void setUseFixedLambdaFactor(bool flag)
Definition: LevenbergMarquardtParams.h:144


gtsam
Author(s):
autogenerated on Thu Jun 13 2024 03:03:00