NonlinearOptimizerParams.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 
22 #pragma once
23 
26 #include <boost/optional.hpp>
27 #include <string>
28 
29 namespace gtsam {
30 
34 class GTSAM_EXPORT NonlinearOptimizerParams {
35 public:
37  enum Verbosity {
38  SILENT, TERMINATION, ERROR, VALUES, DELTA, LINEAR
39  };
40 
41  size_t maxIterations = 100;
42  double relativeErrorTol = 1e-5;
43  double absoluteErrorTol = 1e-5;
44  double errorTol = 0.0;
45  Verbosity verbosity = SILENT;
47 
48  size_t getMaxIterations() const { return maxIterations; }
49  double getRelativeErrorTol() const { return relativeErrorTol; }
50  double getAbsoluteErrorTol() const { return absoluteErrorTol; }
51  double getErrorTol() const { return errorTol; }
52  std::string getVerbosity() const { return verbosityTranslator(verbosity); }
53 
54  void setMaxIterations(int value) { maxIterations = value; }
55  void setRelativeErrorTol(double value) { relativeErrorTol = value; }
56  void setAbsoluteErrorTol(double value) { absoluteErrorTol = value; }
57  void setErrorTol(double value) { errorTol = value; }
58  void setVerbosity(const std::string& src) {
59  verbosity = verbosityTranslator(src);
60  }
61 
62  static Verbosity verbosityTranslator(const std::string &s) ;
63  static std::string verbosityTranslator(Verbosity value) ;
64 
67  using IterationHook = std::function<
68  void(size_t /*iteration*/, double/*errorBefore*/, double/*errorAfter*/)>;
69 
95 
102  Iterative, /* Experimental Flag */
103  CHOLMOD, /* Experimental Flag */
104  };
105 
106  LinearSolverType linearSolverType = MULTIFRONTAL_CHOLESKY;
107  boost::optional<Ordering> ordering;
109 
110  NonlinearOptimizerParams() = default;
112  }
113 
114  virtual void print(const std::string& str = "") const;
115 
116  bool equals(const NonlinearOptimizerParams& other, double tol = 1e-9) const {
117  return maxIterations == other.getMaxIterations()
118  && std::abs(relativeErrorTol - other.getRelativeErrorTol()) <= tol
119  && std::abs(absoluteErrorTol - other.getAbsoluteErrorTol()) <= tol
120  && std::abs(errorTol - other.getErrorTol()) <= tol
121  && verbosityTranslator(verbosity) == other.getVerbosity();
122  // && orderingType.equals(other.getOrderingType()_;
123  // && linearSolverType == other.getLinearSolverType();
124  // TODO: check ordering, iterativeParams, and iterationsHook
125  }
126 
127  inline bool isMultifrontal() const {
128  return (linearSolverType == MULTIFRONTAL_CHOLESKY)
129  || (linearSolverType == MULTIFRONTAL_QR);
130  }
131 
132  inline bool isSequential() const {
133  return (linearSolverType == SEQUENTIAL_CHOLESKY)
134  || (linearSolverType == SEQUENTIAL_QR);
135  }
136 
137  inline bool isCholmod() const {
138  return (linearSolverType == CHOLMOD);
139  }
140 
141  inline bool isIterative() const {
142  return (linearSolverType == Iterative);
143  }
144 
146  switch (linearSolverType) {
147  case MULTIFRONTAL_CHOLESKY:
148  case SEQUENTIAL_CHOLESKY:
150 
151  case MULTIFRONTAL_QR:
152  case SEQUENTIAL_QR:
153  return EliminateQR;
154 
155  default:
156  throw std::runtime_error(
157  "Nonlinear optimization parameter \"factorization\" is invalid");
158  }
159  }
160 
161  std::string getLinearSolverType() const {
162  return linearSolverTranslator(linearSolverType);
163  }
164 
165  void setLinearSolverType(const std::string& solver) {
166  linearSolverType = linearSolverTranslator(solver);
167  }
168 
169  void setIterativeParams(const boost::shared_ptr<IterativeOptimizationParameters> params);
170 
171  void setOrdering(const Ordering& ordering) {
172  this->ordering = ordering;
173  this->orderingType = Ordering::CUSTOM;
174  }
175 
176  std::string getOrderingType() const {
177  return orderingTypeTranslator(orderingType);
178  }
179 
180  // Note that if you want to use a custom ordering, you must set the ordering directly, this will switch to custom type
181  void setOrderingType(const std::string& ordering){
182  orderingType = orderingTypeTranslator(ordering);
183  }
184 
185 private:
186  std::string linearSolverTranslator(LinearSolverType linearSolverType) const;
187  LinearSolverType linearSolverTranslator(const std::string& linearSolverType) const;
188  std::string orderingTypeTranslator(Ordering::OrderingType type) const;
189  Ordering::OrderingType orderingTypeTranslator(const std::string& type) const;
190 };
191 
192 // For backward compatibility:
194 
195 } /* namespace gtsam */
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
void setLinearSolverType(const std::string &solver)
NonlinearOptimizerParams SuccessiveLinearizationParams
static enum @843 ordering
Subgraph Solver from IROS 2010.
std::function< void(size_t, double, double)> IterationHook
BiCGSTAB< SparseMatrix< double > > solver
std::pair< boost::shared_ptr< GaussianConditional >, boost::shared_ptr< GaussianFactor > > EliminatePreferCholesky(const GaussianFactorGraph &factors, const Ordering &keys)
bool equals(const NonlinearOptimizerParams &other, double tol=1e-9) const
void setVerbosity(const std::string &src)
Definition: pytypes.h:928
void setOrderingType(const std::string &ordering)
void setOrdering(const Ordering &ordering)
GaussianFactorGraph::Eliminate getEliminationFunction() const
Array< double, 1, 3 > e(1./3., 0.5, 2.)
RealScalar s
boost::optional< Ordering > ordering
The optional variable elimination ordering, or empty to use COLAMD (default: empty) ...
Linear Factor Graph where all factors are Gaussians.
IterativeOptimizationParameters::shared_ptr iterativeParams
The container for iterativeOptimization parameters. used in CG Solvers.
OrderingType
Type of ordering to use.
static SmartStereoProjectionParams params
boost::shared_ptr< IterativeOptimizationParameters > shared_ptr
traits
Definition: chartTesting.h:28
boost::function< EliminationResult(const FactorGraphType &, const Ordering &)> Eliminate
The function type that does a single dense elimination step on a subgraph.
const G double tol
Definition: Group.h:83
#define abs(x)
Definition: datatypes.h:17
std::pair< GaussianConditional::shared_ptr, JacobianFactor::shared_ptr > EliminateQR(const GaussianFactorGraph &factors, const Ordering &keys)
Definition: pytypes.h:897


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:04