DoglegOptimizer.cpp
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 
26 
27 namespace gtsam {
28 
29 /* ************************************************************************* */
30 DoglegParams::VerbosityDL DoglegParams::verbosityDLTranslator(const std::string &verbosityDL) const {
31  std::string s = verbosityDL;
32  // convert to upper case
33  std::transform(s.begin(), s.end(), s.begin(), ::toupper);
34  if (s == "SILENT") return DoglegParams::SILENT;
35  if (s == "VERBOSE") return DoglegParams::VERBOSE;
36 
37  /* default is silent */
38  return DoglegParams::SILENT;
39 }
40 
41 /* ************************************************************************* */
43  std::string s;
44  switch (verbosityDL) {
45  case DoglegParams::SILENT: s = "SILENT"; break;
46  case DoglegParams::VERBOSE: s = "VERBOSE"; break;
47  default: s = "UNDEFINED"; break;
48  }
49  return s;
50 }
51 
52 /* ************************************************************************* */
53 namespace internal {
55  const double delta;
56 
57  DoglegState(const Values& _values, double _error, double _delta, unsigned int _iterations = 0)
58  : NonlinearOptimizerState(_values, _error, _iterations), delta(_delta) {}
59 };
60 }
61 
63 
64 /* ************************************************************************* */
66  const DoglegParams& params)
68  graph, std::unique_ptr<State>(
69  new State(initialValues, graph.error(initialValues), params.deltaInitial))),
70  params_(ensureHasOrdering(params, graph)) {}
71 
73  const Ordering& ordering)
74  : NonlinearOptimizer(graph, std::unique_ptr<State>(
75  new State(initialValues, graph.error(initialValues), 1.0))) {
77 }
78 
79 double DoglegOptimizer::getDelta() const {
80  return static_cast<const State*>(state_.get())->delta;
81 }
82 
83 /* ************************************************************************* */
85 
86  // Linearize graph
88 
89  // Pull out parameters we'll use
90  const bool dlVerbose = (params_.verbosityDL > DoglegParams::SILENT);
91 
92  // Do Dogleg iteration with either Multifrontal or Sequential elimination
94 
95  if ( params_.isMultifrontal() ) {
96  GaussianBayesTree bt = *linear->eliminateMultifrontal(*params_.ordering, params_.getEliminationFunction());
98  VectorValues dx_n = bt.optimize();
100  dx_u, dx_n, bt, graph_, state_->values, state_->error, dlVerbose);
101  }
102  else if ( params_.isSequential() ) {
103  GaussianBayesNet bn = *linear->eliminateSequential(*params_.ordering, params_.getEliminationFunction());
105  VectorValues dx_n = bn.optimize();
107  dx_u, dx_n, bn, graph_, state_->values, state_->error, dlVerbose);
108  }
109  else if ( params_.isIterative() ) {
110  throw std::runtime_error("Dogleg is not currently compatible with the linear conjugate gradient solver");
111  }
112  else {
113  throw std::runtime_error("Optimization parameter is invalid: DoglegParams::elimination");
114  }
115 
116  // Maybe show output
118 
119  // Create new state with new values and new error
120  state_.reset(new State(state_->values.retract(result.dx_d), result.f_error, result.delta,
121  state_->iterations + 1));
122  return linear;
123 }
124 
125 /* ************************************************************************* */
127  if (!params.ordering)
128  params.ordering = Ordering::Create(params.orderingType, graph);
129  return params;
130 }
131 
132 } /* namespace gtsam */
VerbosityDL verbosityDLTranslator(const std::string &verbosityDL) const
DoglegState(const Values &_values, double _error, double _delta, unsigned int _iterations=0)
const NonlinearFactorGraph & graph() const
return the graph with nonlinear factors
static Ordering Create(OrderingType orderingType, const FACTOR_GRAPH &graph)
void print(const std::string &str="VectorValues", const KeyFormatter &formatter=DefaultKeyFormatter) const
DoglegOptimizer(const NonlinearFactorGraph &graph, const Values &initialValues, const DoglegParams &params=DoglegParams())
VerbosityDL verbosityDL
The verbosity level for Dogleg (default: SILENT), see also NonlinearOptimizerParams::verbosity.
static IterationResult Iterate(double delta, TrustRegionAdaptationMode mode, const VectorValues &dx_u, const VectorValues &dx_n, const M &Rd, const F &f, const VALUES &x0, const double f_error, const bool verbose=false)
Verbosity verbosity
The printing verbosity during optimization (default SILENT)
Definition: BFloat16.h:88
GaussianFactorGraph::shared_ptr iterate() override
NonlinearFactorGraph graph
static enum @1107 ordering
static const SmartProjectionParams params
std::shared_ptr< GaussianFactorGraph > linearize(const Values &linearizationPoint) const
Linearize a nonlinear factor graph.
std::unique_ptr< internal::NonlinearOptimizerState > state_
PIMPL&#39;d state.
VectorValues optimize() const
Factor Graph Values.
Nonlinear factor graph optimizer using Powell&#39;s Dogleg algorithm (detail implementation) ...
Values result
VectorValues optimize() const
VectorValues optimizeGradientSearch() const
RealScalar s
double deltaInitial
The initial trust region radius (default: 10.0)
Linear Factor Graph where all factors are Gaussians.
EIGEN_DONT_INLINE void transform(const Transformation &t, Data &data)
Definition: geometry.cpp:25
std::shared_ptr< This > shared_ptr
shared_ptr to this class
GaussianFactorGraph::Eliminate getEliminationFunction() const
internal::DoglegState State
traits
Definition: chartTesting.h:28
const DoglegParams & params() const
DoglegParams ensureHasOrdering(DoglegParams params, const NonlinearFactorGraph &graph) const
NonlinearFactorGraph graph_
The graph with nonlinear factors.
Private class for NonlinearOptimizer state.
VectorValues optimizeGradientSearch() const
Chordal Bayes Net, the result of eliminating a factor graph.
static double error
Definition: testRot3.cpp:37
Ordering::OrderingType orderingType
The method of ordering use during variable elimination (default COLAMD)
std::optional< Ordering > ordering
The optional variable elimination ordering, or empty to use COLAMD (default: empty) ...
double error() const
return error in current optimizer state
Gaussian Bayes Tree, the result of eliminating a GaussianJunctionTree.


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:34:10