ISAM2Params.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 
18 // \callgraph
19 
20 #pragma once
21 
24 
25 #include <string>
26 #include <variant>
27 
28 namespace gtsam {
29 
36 struct GTSAM_EXPORT ISAM2GaussNewtonParams {
37  double
39 
43  double _wildfireThreshold =
44  0.001
45  )
47  : wildfireThreshold(_wildfireThreshold) {}
48 
49  void print(const std::string str = "") const {
50  using std::cout;
51  cout << str << "type: ISAM2GaussNewtonParams\n";
52  cout << str << "wildfireThreshold: " << wildfireThreshold << "\n";
53  cout.flush();
54  }
55 
56  double getWildfireThreshold() const { return wildfireThreshold; }
57  void setWildfireThreshold(double wildfireThreshold) {
58  this->wildfireThreshold = wildfireThreshold;
59  }
60 };
61 
68 struct GTSAM_EXPORT ISAM2DoglegParams {
69  double initialDelta;
70  double
75  bool
78 
81  double _initialDelta = 1.0,
82  double _wildfireThreshold =
83  1e-5,
86  SEARCH_EACH_ITERATION,
87  bool _verbose = false
88  )
89  : initialDelta(_initialDelta),
90  wildfireThreshold(_wildfireThreshold),
91  adaptationMode(_adaptationMode),
92  verbose(_verbose) {}
93 
94  void print(const std::string str = "") const {
95  using std::cout;
96  cout << str << "type: ISAM2DoglegParams\n";
97  cout << str << "initialDelta: " << initialDelta << "\n";
98  cout << str << "wildfireThreshold: " << wildfireThreshold << "\n";
99  cout << str
100  << "adaptationMode: " << adaptationModeTranslator(adaptationMode)
101  << "\n";
102  cout.flush();
103  }
104 
105  double getInitialDelta() const { return initialDelta; }
106  double getWildfireThreshold() const { return wildfireThreshold; }
107  std::string getAdaptationMode() const {
108  return adaptationModeTranslator(adaptationMode);
109  }
110  bool isVerbose() const { return verbose; }
111  void setInitialDelta(double initialDelta) {
112  this->initialDelta = initialDelta;
113  }
114  void setWildfireThreshold(double wildfireThreshold) {
115  this->wildfireThreshold = wildfireThreshold;
116  }
117  void setAdaptationMode(const std::string& adaptationMode) {
118  this->adaptationMode = adaptationModeTranslator(adaptationMode);
119  }
120  void setVerbose(bool verbose) { this->verbose = verbose; }
121 
122  std::string adaptationModeTranslator(
124  const;
125  DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationModeTranslator(
126  const std::string& adaptationMode) const;
127 };
128 
135 typedef ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue;
136 struct GTSAM_EXPORT ISAM2Params {
137  typedef std::variant<ISAM2GaussNewtonParams, ISAM2DoglegParams>
139  typedef std::variant<double, FastMap<char, Vector> >
142 
152 
170 
172 
176 
179 
182  enum Factorization { CHOLESKY, QR };
195 
202 
205 
208 
220 
226 
232  RelinearizationThreshold _relinearizeThreshold = 0.1,
233  int _relinearizeSkip = 10, bool _enableRelinearization = true,
234  bool _evaluateNonlinearError = false,
235  Factorization _factorization = ISAM2Params::CHOLESKY,
236  bool _cacheLinearizedFactors = true,
237  const KeyFormatter& _keyFormatter =
239  bool _enableDetailedResults = false)
240  : optimizationParams(_optimizationParams),
241  relinearizeThreshold(_relinearizeThreshold),
242  relinearizeSkip(_relinearizeSkip),
243  enableRelinearization(_enableRelinearization),
244  evaluateNonlinearError(_evaluateNonlinearError),
245  factorization(_factorization),
246  cacheLinearizedFactors(_cacheLinearizedFactors),
247  keyFormatter(_keyFormatter),
248  enableDetailedResults(_enableDetailedResults),
249  enablePartialRelinearizationCheck(false),
250  findUnusedFactorSlots(false) {}
251 
253  void print(const std::string& str = "") const {
254  using std::cout;
255  cout << str << "\n";
256 
257  static const std::string kStr("optimizationParams: ");
258  if (std::holds_alternative<ISAM2GaussNewtonParams>(optimizationParams)) {
259  std::get<ISAM2GaussNewtonParams>(optimizationParams).print();
260  } else if (std::holds_alternative<ISAM2DoglegParams>(optimizationParams)) {
261  std::get<ISAM2DoglegParams>(optimizationParams).print(kStr);
262  } else {
263  cout << kStr << "{unknown type}\n";
264  }
265 
266  cout << "relinearizeThreshold: ";
267  if (std::holds_alternative<double>(relinearizeThreshold)) {
268  cout << std::get<double>(relinearizeThreshold) << "\n";
269  } else {
270  cout << "{mapped}\n";
271  for (const ISAM2ThresholdMapValue& value :
272  std::get<ISAM2ThresholdMap>(relinearizeThreshold)) {
273  cout << " '" << value.first
274  << "' -> [" << value.second.transpose() << " ]\n";
275  }
276  }
277 
278  cout << "relinearizeSkip: " << relinearizeSkip << "\n";
279  cout << "enableRelinearization: " << enableRelinearization
280  << "\n";
281  cout << "evaluateNonlinearError: " << evaluateNonlinearError
282  << "\n";
283  cout << "factorization: "
284  << factorizationTranslator(factorization) << "\n";
285  cout << "cacheLinearizedFactors: " << cacheLinearizedFactors
286  << "\n";
287  cout << "enableDetailedResults: " << enableDetailedResults
288  << "\n";
289  cout << "enablePartialRelinearizationCheck: "
290  << enablePartialRelinearizationCheck << "\n";
291  cout << "findUnusedFactorSlots: " << findUnusedFactorSlots
292  << "\n";
293  cout.flush();
294  }
295 
298 
300  return this->optimizationParams;
301  }
303  return relinearizeThreshold;
304  }
305  std::string getFactorization() const {
306  return factorizationTranslator(factorization);
307  }
308  KeyFormatter getKeyFormatter() const { return keyFormatter; }
309 
310  void setOptimizationParams(OptimizationParams optimizationParams) {
311  this->optimizationParams = optimizationParams;
312  }
314  this->relinearizeThreshold = relinearizeThreshold;
315  }
316  void setFactorization(const std::string& factorization) {
317  this->factorization = factorizationTranslator(factorization);
318  }
319  void setKeyFormatter(KeyFormatter keyFormatter) {
320  this->keyFormatter = keyFormatter;
321  }
322 
324  return factorization == CHOLESKY
327  }
328 
330 
333 
334  static Factorization factorizationTranslator(const std::string& str);
335  static std::string factorizationTranslator(const Factorization& value);
336 
338 };
339 
340 } // namespace gtsam
gtsam::ISAM2Params::print
void print(const std::string &str="") const
print iSAM2 parameters
Definition: ISAM2Params.h:253
gtsam::ISAM2Params
Definition: ISAM2Params.h:136
GaussianFactorGraph.h
Linear Factor Graph where all factors are Gaussians.
gtsam::ISAM2Params::setKeyFormatter
void setKeyFormatter(KeyFormatter keyFormatter)
Definition: ISAM2Params.h:319
gtsam::ISAM2Params::OptimizationParams
std::variant< ISAM2GaussNewtonParams, ISAM2DoglegParams > OptimizationParams
Definition: ISAM2Params.h:138
gtsam::ISAM2Params::enableRelinearization
bool enableRelinearization
Definition: ISAM2Params.h:175
gtsam::ISAM2Params::getKeyFormatter
KeyFormatter getKeyFormatter() const
Definition: ISAM2Params.h:308
gtsam::ISAM2DoglegParams::isVerbose
bool isVerbose() const
Definition: ISAM2Params.h:110
e
Array< double, 1, 3 > e(1./3., 0.5, 2.)
gtsam::ISAM2DoglegParams::getInitialDelta
double getInitialDelta() const
Definition: ISAM2Params.h:105
gtsam::ISAM2Params::enableDetailedResults
bool enableDetailedResults
Definition: ISAM2Params.h:207
gtsam::FastMap
Definition: FastMap.h:39
gtsam::ISAM2Params::CHOLESKY
@ CHOLESKY
Definition: ISAM2Params.h:182
gtsam::ISAM2DoglegParams::getAdaptationMode
std::string getAdaptationMode() const
Definition: ISAM2Params.h:107
gtsam::DoglegOptimizerImpl
Definition: DoglegOptimizerImpl.h:32
gtsam::ISAM2DoglegParams::setInitialDelta
void setInitialDelta(double initialDelta)
Definition: ISAM2Params.h:111
gtsam::ISAM2Params::ISAM2Params
ISAM2Params(OptimizationParams _optimizationParams=ISAM2GaussNewtonParams(), RelinearizationThreshold _relinearizeThreshold=0.1, int _relinearizeSkip=10, bool _enableRelinearization=true, bool _evaluateNonlinearError=false, Factorization _factorization=ISAM2Params::CHOLESKY, bool _cacheLinearizedFactors=true, const KeyFormatter &_keyFormatter=DefaultKeyFormatter, bool _enableDetailedResults=false)
Definition: ISAM2Params.h:231
gtsam::ISAM2Params::enablePartialRelinearizationCheck
bool enablePartialRelinearizationCheck
Definition: ISAM2Params.h:219
gtsam::ISAM2Params::keyFormatter
KeyFormatter keyFormatter
Definition: ISAM2Params.h:204
gtsam::ISAM2Params::getOptimizationParams
OptimizationParams getOptimizationParams() const
Definition: ISAM2Params.h:299
gtsam::ISAM2Params::setRelinearizeThreshold
void setRelinearizeThreshold(RelinearizationThreshold relinearizeThreshold)
Definition: ISAM2Params.h:313
gtsam::ISAM2Params::getEliminationFunction
GaussianFactorGraph::Eliminate getEliminationFunction() const
Definition: ISAM2Params.h:323
gtsam::ISAM2Params::optimizationParams
OptimizationParams optimizationParams
Definition: ISAM2Params.h:151
gtsam::DefaultKeyFormatter
KeyFormatter DefaultKeyFormatter
Assign default key formatter.
Definition: Key.cpp:30
gtsam::ISAM2DoglegParams
Definition: ISAM2Params.h:68
gtsam::ISAM2GaussNewtonParams::wildfireThreshold
double wildfireThreshold
Definition: ISAM2Params.h:38
gtsam::EliminatePreferCholesky
std::pair< std::shared_ptr< GaussianConditional >, std::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: HessianFactor.cpp:540
gtsam::ISAM2DoglegParams::wildfireThreshold
double wildfireThreshold
Definition: ISAM2Params.h:71
gtsam::ISAM2GaussNewtonParams::print
void print(const std::string str="") const
Definition: ISAM2Params.h:49
gtsam::ISAM2DoglegParams::setWildfireThreshold
void setWildfireThreshold(double wildfireThreshold)
Definition: ISAM2Params.h:114
gtsam::ISAM2DoglegParams::ISAM2DoglegParams
ISAM2DoglegParams(double _initialDelta=1.0, double _wildfireThreshold=1e-5, DoglegOptimizerImpl::TrustRegionAdaptationMode _adaptationMode=DoglegOptimizerImpl::SEARCH_EACH_ITERATION, bool _verbose=false)
Definition: ISAM2Params.h:80
gtsam::ISAM2Params::relinearizeThreshold
RelinearizationThreshold relinearizeThreshold
Definition: ISAM2Params.h:169
gtsam::ISAM2GaussNewtonParams::ISAM2GaussNewtonParams
ISAM2GaussNewtonParams(double _wildfireThreshold=0.001)
Definition: ISAM2Params.h:42
gtsam::ISAM2Params::getRelinearizeThreshold
RelinearizationThreshold getRelinearizeThreshold() const
Definition: ISAM2Params.h:302
gtsam::ISAM2Params::Factorization
Factorization
Definition: ISAM2Params.h:182
gtsam::KeyFormatter
std::function< std::string(Key)> KeyFormatter
Typedef for a function to format a key, i.e. to convert it to a string.
Definition: Key.h:35
gtsam::ISAM2GaussNewtonParams::setWildfireThreshold
void setWildfireThreshold(double wildfireThreshold)
Definition: ISAM2Params.h:57
gtsam::DoglegOptimizerImpl::TrustRegionAdaptationMode
TrustRegionAdaptationMode
Definition: DoglegOptimizerImpl.h:53
gtsam::ISAM2DoglegParams::print
void print(const std::string str="") const
Definition: ISAM2Params.h:94
gtsam::ISAM2GaussNewtonParams
Definition: ISAM2Params.h:36
gtsam::ISAM2DoglegParams::initialDelta
double initialDelta
The initial trust region radius for Dogleg.
Definition: ISAM2Params.h:69
gtsam::ISAM2DoglegParams::setAdaptationMode
void setAdaptationMode(const std::string &adaptationMode)
Definition: ISAM2Params.h:117
gtsam::ISAM2Params::factorization
Factorization factorization
Definition: ISAM2Params.h:194
gtsam::ISAM2Params::getFactorization
std::string getFactorization() const
Definition: ISAM2Params.h:305
gtsam::ISAM2ThresholdMap
FastMap< char, Vector > ISAM2ThresholdMap
Definition: ISAM2Params.h:134
str
Definition: pytypes.h:1558
gtsam::ISAM2ThresholdMapValue
ISAM2ThresholdMap::value_type ISAM2ThresholdMapValue
Definition: ISAM2Params.h:135
gtsam::ISAM2Params::RelinearizationThreshold
std::variant< double, FastMap< char, Vector > > RelinearizationThreshold
Definition: ISAM2Params.h:141
gtsam
traits
Definition: SFMdata.h:40
gtsam::ISAM2Params::setOptimizationParams
void setOptimizationParams(OptimizationParams optimizationParams)
Definition: ISAM2Params.h:310
gtsam::ISAM2Params::findUnusedFactorSlots
bool findUnusedFactorSlots
Definition: ISAM2Params.h:225
gtsam::EliminateableFactorGraph< GaussianFactorGraph >::Eliminate
std::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
Definition: EliminateableFactorGraph.h:88
DoglegOptimizerImpl.h
Nonlinear factor graph optimizer using Powell's Dogleg algorithm (detail implementation)
gtsam::ISAM2DoglegParams::adaptationMode
DoglegOptimizerImpl::TrustRegionAdaptationMode adaptationMode
Definition: ISAM2Params.h:74
gtsam::ISAM2DoglegParams::verbose
bool verbose
Whether Dogleg prints iteration and convergence information.
Definition: ISAM2Params.h:77
gtsam::ISAM2Params::relinearizeSkip
int relinearizeSkip
Definition: ISAM2Params.h:171
gtsam::ISAM2Params::cacheLinearizedFactors
bool cacheLinearizedFactors
Definition: ISAM2Params.h:201
gtsam::ISAM2DoglegParams::setVerbose
void setVerbose(bool verbose)
Definition: ISAM2Params.h:120
test_callbacks.value
value
Definition: test_callbacks.py:160
gtsam::ISAM2Params::evaluateNonlinearError
bool evaluateNonlinearError
Definition: ISAM2Params.h:178
gtsam::ISAM2DoglegParams::getWildfireThreshold
double getWildfireThreshold() const
Definition: ISAM2Params.h:106
gtsam::ISAM2GaussNewtonParams::getWildfireThreshold
double getWildfireThreshold() const
Definition: ISAM2Params.h:56
gtsam::EliminateQR
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: JacobianFactor.cpp:778
gtsam::ISAM2Params::setFactorization
void setFactorization(const std::string &factorization)
Definition: ISAM2Params.h:316


gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:32:54