iterative-inl.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 
21 #include <gtsam/linear/iterative.h>
23 
24 namespace gtsam {
25 
26  /* ************************************************************************* */
27  // state for CG method
28  template<class S, class V, class E>
29  struct CGState {
30 
33 
34  int k;
35  bool steepest;
36  V g, d;
37  double gamma, threshold;
38  E Ad;
39 
40  /* ************************************************************************* */
41  // Constructor
42  CGState(const S& Ab, const V& x, const Parameters &parameters, bool steep):
43  parameters_(parameters),k(0),steepest(steep) {
44 
45  // Start with g0 = A'*(A*x0-b), d0 = - g0
46  // i.e., first step is in direction of negative gradient
47  g = Ab.gradient(x);
48  d = g; // instead of negating gradient, alpha will be negated
49 
50  // init gamma and calculate threshold
51  gamma = dot(g,g);
52  threshold =
55 
56  // Allocate and calculate A*d for first iteration
57  if (gamma > parameters_.epsilon_abs) Ad = Ab * d;
58  }
59 
60  /* ************************************************************************* */
61  // print
62  void print(const V& x) {
63  std::cout << "iteration = " << k << std::endl;
64  gtsam::print(x,"x");
65  gtsam::print(g, "g");
66  std::cout << "dotg = " << gamma << std::endl;
67  gtsam::print(d, "d");
68  gtsam::print(Ad, "Ad");
69  }
70 
71  /* ************************************************************************* */
72  // step the solution
73  double takeOptimalStep(V& x) {
74  // TODO: can we use gamma instead of dot(d,g) ????? Answer not trivial
75  double alpha = -dot(d, g) / dot(Ad, Ad); // calculate optimal step-size
76  x += alpha * d; // do step in new search direction, x += alpha*d
77  return alpha;
78  }
79 
80  /* ************************************************************************* */
81  // take a step, return true if converged
82  bool step(const S& Ab, V& x) {
83 
84  if ((++k) >= ((int)parameters_.maxIterations)) return true;
85 
86  //---------------------------------->
87  double alpha = takeOptimalStep(x);
88 
89  // update gradient (or re-calculate at reset time)
90  if (k % parameters_.reset == 0) g = Ab.gradient(x);
91  // axpy(alpha, Ab ^ Ad, g); // g += alpha*(Ab^Ad)
92  else Ab.transposeMultiplyAdd(alpha, Ad, g);
93 
94  // check for convergence
95  double new_gamma = dot(g, g);
96 
98  std::cout << "iteration " << k << ": alpha = " << alpha
99  << ", dotg = " << new_gamma
100  << std::endl;
101 
102  if (new_gamma < threshold) return true;
103 
104  // calculate new search direction
105  if (steepest) d = g;
106  else {
107  double beta = new_gamma / gamma;
108  // d = g + d*beta;
109  d *= beta;
110  d += 1.0 * g;
111  }
112 
113  gamma = new_gamma;
114 
115  // In-place recalculation Ad <- A*d to avoid re-allocating Ad
116  Ab.multiplyInPlace(d, Ad);
117  return false;
118  }
119 
120  }; // CGState Class
121 
122  /* ************************************************************************* */
123  // conjugate gradient method.
124  // S: linear system, V: step vector, E: errors
125  template<class S, class V, class E>
126  V conjugateGradients(const S& Ab, V x, const ConjugateGradientParameters &parameters, bool steepest) {
127 
128  CGState<S, V, E> state(Ab, x, parameters, steepest);
129 
131  std::cout << "CG: epsilon = " << parameters.epsilon_rel
132  << ", maxIterations = " << parameters.maxIterations
133  << ", ||g0||^2 = " << state.gamma
134  << ", threshold = " << state.threshold << std::endl;
135 
136  if ( state.gamma < state.threshold ) {
138  std::cout << "||g0||^2 < threshold, exiting immediately !" << std::endl;
139 
140  return x;
141  }
142 
143  // loop maxIterations times
144  while (!state.step(Ab, x)) {}
145  return x;
146  }
147 /* ************************************************************************* */
148 
149 } // namespace gtsam
gtsam::CGState::print
void print(const V &x)
Definition: iterative-inl.h:62
alpha
RealScalar alpha
Definition: level1_cplx_impl.h:147
x
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Definition: gnuplot_common_settings.hh:12
gtsam::IterativeOptimizationParameters::verbosity
Verbosity verbosity() const
Definition: IterativeSolver.h:61
beta
double beta(double a, double b)
Definition: beta.c:61
gtsam::CGState::CGState
CGState(const S &Ab, const V &x, const Parameters &parameters, bool steep)
Definition: iterative-inl.h:42
gtsam::print
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
ConjugateGradientSolver.h
Implementation of Conjugate Gradient solver for a linear system.
gtsam::conjugateGradients
V conjugateGradients(const S &Ab, V x, const ConjugateGradientParameters &parameters, bool steepest)
Definition: iterative-inl.h:126
gtsam::CGState::k
int k
iteration
Definition: iterative-inl.h:34
gtsam::CGState
Definition: iterative-inl.h:29
parameters
static ConjugateGradientParameters parameters
Definition: testIterative.cpp:33
gtsam::CGState::g
V g
Definition: iterative-inl.h:36
gtsam::IterativeOptimizationParameters::SILENT
@ SILENT
Definition: IterativeSolver.h:46
gtsam::dot
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
gtsam::CGState::step
bool step(const S &Ab, V &x)
Definition: iterative-inl.h:82
gtsam::CGState::steepest
bool steepest
flag to indicate we are doing steepest descent
Definition: iterative-inl.h:35
iterative.h
Iterative methods, implementation.
gtsam::CGState::Parameters
ConjugateGradientParameters Parameters
Definition: iterative-inl.h:31
E
DiscreteKey E(5, 2)
gtsam::ConjugateGradientParameters::epsilon_rel
double epsilon_rel
threshold for relative error decrease
Definition: ConjugateGradientSolver.h:37
gtsam::CGState::parameters_
const Parameters & parameters_
Definition: iterative-inl.h:32
gtsam
traits
Definition: SFMdata.h:40
gtsam::ConjugateGradientParameters
Definition: ConjugateGradientSolver.h:29
gtsam::ConjugateGradientParameters::maxIterations
size_t maxIterations
maximum number of cg iterations
Definition: ConjugateGradientSolver.h:35
gtsam::CGState::threshold
double threshold
gamma (squared L2 norm of g) and convergence threshold
Definition: iterative-inl.h:37
gtsam::CGState::gamma
double gamma
Definition: iterative-inl.h:37
exampleQR::Ab
Matrix Ab
Definition: testNoiseModel.cpp:207
gtsam::CGState::d
V d
gradient g and search direction d for CG
Definition: iterative-inl.h:36
gtsam::CGState::takeOptimalStep
double takeOptimalStep(V &x)
Definition: iterative-inl.h:73
V
MatrixXcd V
Definition: EigenSolver_EigenSolver_MatrixType.cpp:15
gtsam::ConjugateGradientParameters::reset
size_t reset
number of iterations before reset
Definition: ConjugateGradientSolver.h:36
max
#define max(a, b)
Definition: datatypes.h:20
gtsam::ConjugateGradientParameters::epsilon_abs
double epsilon_abs
threshold for absolute error decrease
Definition: ConjugateGradientSolver.h:38
gtsam::CGState::Ad
E Ad
Definition: iterative-inl.h:38
S
DiscreteKey S(1, 2)
make_changelog.state
state
Definition: make_changelog.py:29


gtsam
Author(s):
autogenerated on Sat Nov 16 2024 04:02:33