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 <boost/tuple/tuple.hpp>
25 #include <boost/shared_ptr.hpp>
26 #include <boost/optional.hpp>
27 
28 #include <iosfwd>
29 #include <string>
30 #include <map>
31 
32 namespace gtsam {
33 
34 // Forward declarations
35 struct KeyInfoEntry;
36 class KeyInfo;
37 class GaussianFactorGraph;
38 class Values;
39 class VectorValues;
40 
45 
46 public:
47 
48  typedef boost::shared_ptr<IterativeOptimizationParameters> shared_ptr;
49  enum Verbosity {
51  } verbosity_;
52 
53 public:
54 
56  verbosity_(v) {
57  }
58 
60  }
61 
62  /* utility */
63  inline Verbosity verbosity() const {
64  return verbosity_;
65  }
66  GTSAM_EXPORT std::string getVerbosity() const;
67  GTSAM_EXPORT void setVerbosity(const std::string &s);
68 
69  /* matlab interface */
70  GTSAM_EXPORT void print() const;
71 
72  /* virtual print function */
73  GTSAM_EXPORT virtual void print(std::ostream &os) const;
74 
75  /* for serialization */
76  friend std::ostream& operator<<(std::ostream &os,
78 
79  GTSAM_EXPORT static Verbosity verbosityTranslator(const std::string &s);
80  GTSAM_EXPORT static std::string verbosityTranslator(Verbosity v);
81 };
82 
87 public:
88  typedef boost::shared_ptr<IterativeSolver> shared_ptr;
90  }
91  virtual ~IterativeSolver() {
92  }
93 
94  /* interface to the nonlinear optimizer, without metadata, damping and initial estimate */
95  GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg,
96  boost::optional<const KeyInfo&> = boost::none,
97  boost::optional<const std::map<Key, Vector>&> lambda = boost::none);
98 
99  /* interface to the nonlinear optimizer, without initial estimate */
100  GTSAM_EXPORT VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo,
101  const std::map<Key, Vector> &lambda);
102 
103  /* interface to the nonlinear optimizer that the subclasses have to implement */
104  virtual VectorValues optimize(const GaussianFactorGraph &gfg,
105  const KeyInfo &keyInfo, const std::map<Key, Vector> &lambda,
106  const VectorValues &initial) = 0;
107 
108 };
109 
114 struct GTSAM_EXPORT KeyInfoEntry {
115  size_t index, dim, start;
117  }
118  KeyInfoEntry(size_t idx, size_t d, Key start) :
119  index(idx), dim(d), start(start) {
120  }
121 };
122 
126 class GTSAM_EXPORT KeyInfo: public std::map<Key, KeyInfoEntry> {
127 
128 public:
129 
130  typedef std::map<Key, KeyInfoEntry> Base;
131 
132 protected:
133 
135  size_t numCols_;
136 
137  void initialize(const GaussianFactorGraph &fg);
138 
139 public:
140 
143  numCols_(0) {
144  }
145 
147  KeyInfo(const GaussianFactorGraph &fg);
148 
150  KeyInfo(const GaussianFactorGraph &fg, const Ordering &ordering);
151 
153  inline size_t numCols() const {
154  return numCols_;
155  }
156 
158  inline const Ordering & ordering() const {
159  return ordering_;
160  }
161 
163  std::vector<size_t> colSpec() const;
164 
166  VectorValues x0() const;
167 
169  Vector x0vector() const;
170 
171 };
172 
173 } // \ namespace gtsam
static GTSAM_EXPORT Verbosity verbosityTranslator(const std::string &s)
static enum @843 ordering
ArrayXcf v
Definition: Cwise_arg.cpp:1
const Ordering & ordering() const
Return the ordering.
GTSAM_EXPORT std::string getVerbosity() const
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)
Point3 optimize(const NonlinearFactorGraph &graph, const Values &values, Key landmarkKey)
Eigen::VectorXd Vector
Definition: Vector.h:38
enum gtsam::IterativeOptimizationParameters::Verbosity verbosity_
RealScalar s
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
static Symbol x0('x', 0)
const mpreal dim(const mpreal &a, const mpreal &b, mp_rnd_t r=mpreal::get_default_rnd())
Definition: mpreal.h:2201
boost::shared_ptr< IterativeOptimizationParameters > shared_ptr
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
std::vector< float > Values
ofstream os("timeSchurFactors.csv")
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:338
std::uint64_t Key
Integer nonlinear key type.
Definition: types.h:61
boost::shared_ptr< IterativeSolver > shared_ptr


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:42:22