IterativeSolver.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 
19 #pragma once
20 
22 #include <gtsam/base/Vector.h>
23 
24 #include <memory>
25 
26 #include <iosfwd>
27 #include <string>
28 #include <map>
29 #include <optional>
30 
31 namespace gtsam {
32 
33 // Forward declarations
34 struct KeyInfoEntry;
35 class KeyInfo;
36 class GaussianFactorGraph;
37 class Values;
38 class VectorValues;
39 
44 
45 public:
46 
47  typedef std::shared_ptr<IterativeOptimizationParameters> shared_ptr;
48  enum Verbosity {
50  } verbosity_;
51 
52 public:
53 
55  verbosity_(v) {
56  }
57 
59  }
60 
61  /* utility */
62  inline Verbosity verbosity() const {
63  return verbosity_;
64  }
65  GTSAM_EXPORT std::string getVerbosity() const;
66  GTSAM_EXPORT void setVerbosity(const std::string &s);
67 
68  /* matlab interface */
69  GTSAM_EXPORT void print() const;
70 
71  /* virtual print function */
72  GTSAM_EXPORT virtual void print(std::ostream &os) const;
73 
74  /* for serialization */
75  friend std::ostream& operator<<(std::ostream &os,
77 
78  GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s);
79  GTSAM_EXPORT static std::string verbosityTranslator(Verbosity v);
80 };
81 
86 public:
87  typedef std::shared_ptr<IterativeSolver> shared_ptr;
89  }
90  virtual ~IterativeSolver() {
91  }
92 
93  /* interface to the nonlinear optimizer, without metadata, damping and initial estimate */
94  GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg,
95  const KeyInfo* = nullptr,
96  const std::map<Key, Vector>* lambda = nullptr);
97 
98  /* interface to the nonlinear optimizer, without initial estimate */
99  GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo,
100  const std::map<Key, Vector> &lambda);
101 
102  /* interface to the nonlinear optimizer that the subclasses have to implement */
103  virtual VectorValues optimize(const GaussianFactorGraph &gfg,
104  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda,
105  const VectorValues &initial) = 0;
106 
107 };
108 
113 struct GTSAM_EXPORT KeyInfoEntry {
114  size_t index, dim, start;
116  }
117  KeyInfoEntry(size_t idx, size_t d, Key start) :
118  index(idx), dim(d), start(start) {
119  }
120 };
121 
125 class GTSAM_EXPORT KeyInfo: public std::map<Key, KeyInfoEntry> {
126 
127 public:
128 
129  typedef std::map<Key, KeyInfoEntry> Base;
130 
131 protected:
132 
134  size_t numCols_;
135 
136  void initialize(const GaussianFactorGraph &fg);
137 
138 public:
139 
142  numCols_(0) {
143  }
144 
146  KeyInfo(const GaussianFactorGraph &fg);
147 
149  KeyInfo(const GaussianFactorGraph &fg, const Ordering &ordering);
150 
152  inline size_t numCols() const {
153  return numCols_;
154  }
155 
157  inline const Ordering & ordering() const {
158  return ordering_;
159  }
160 
162  std::vector<size_t> colSpec() const;
163 
165  VectorValues x0() const;
166 
168  Vector x0vector() const;
169 
170 };
171 
172 } // \ namespace gtsam
static GTSAM_EXPORT Verbosity verbosityTranslator(const std::string &s)
static enum @1107 ordering
std::shared_ptr< IterativeSolver > shared_ptr
KeyInfoEntry(size_t idx, size_t d, Key start)
friend std::ostream & operator<<(std::ostream &os, const IterativeOptimizationParameters &p)
std::map< Key, KeyInfoEntry > Base
IterativeOptimizationParameters(Verbosity v=SILENT)
Eigen::VectorXd Vector
Definition: Vector.h:38
enum gtsam::IterativeOptimizationParameters::Verbosity verbosity_
Array< int, Dynamic, 1 > v
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
RealScalar s
GTSAM_EXPORT std::string getVerbosity() const
const Ordering & ordering() const
Return the ordering.
KeyInfo()
Default Constructor.
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
typedef and functions to augment Eigen&#39;s VectorXd
static Symbol x0('x', 0)
ofstream os("timeSchurFactors.csv")
std::shared_ptr< IterativeOptimizationParameters > shared_ptr
float * p
GTSAM_EXPORT void setVerbosity(const std::string &s)
size_t numCols() const
Return the total number of columns (scalar variables = sum of dimensions)
Values initialize(const NonlinearFactorGraph &graph, bool useOdometricPath)
Definition: lago.cpp:375
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:102


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