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 
32  const Parameters &parameters_;
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 = std::max(parameters_.epsilon_abs(), parameters_.epsilon() * parameters_.epsilon() * gamma);
53 
54  // Allocate and calculate A*d for first iteration
55  if (gamma > parameters_.epsilon_abs()) Ad = Ab * d;
56  }
57 
58  /* ************************************************************************* */
59  // print
60  void print(const V& x) {
61  std::cout << "iteration = " << k << std::endl;
62  gtsam::print(x,"x");
63  gtsam::print(g, "g");
64  std::cout << "dotg = " << gamma << std::endl;
65  gtsam::print(d, "d");
66  gtsam::print(Ad, "Ad");
67  }
68 
69  /* ************************************************************************* */
70  // step the solution
71  double takeOptimalStep(V& x) {
72  // TODO: can we use gamma instead of dot(d,g) ????? Answer not trivial
73  double alpha = -dot(d, g) / dot(Ad, Ad); // calculate optimal step-size
74  x += alpha * d; // do step in new search direction, x += alpha*d
75  return alpha;
76  }
77 
78  /* ************************************************************************* */
79  // take a step, return true if converged
80  bool step(const S& Ab, V& x) {
81 
82  if ((++k) >= ((int)parameters_.maxIterations())) return true;
83 
84  //---------------------------------->
85  double alpha = takeOptimalStep(x);
86 
87  // update gradient (or re-calculate at reset time)
88  if (k % parameters_.reset() == 0) g = Ab.gradient(x);
89  // axpy(alpha, Ab ^ Ad, g); // g += alpha*(Ab^Ad)
90  else Ab.transposeMultiplyAdd(alpha, Ad, g);
91 
92  // check for convergence
93  double new_gamma = dot(g, g);
94 
96  std::cout << "iteration " << k << ": alpha = " << alpha
97  << ", dotg = " << new_gamma
98  << std::endl;
99 
100  if (new_gamma < threshold) return true;
101 
102  // calculate new search direction
103  if (steepest) d = g;
104  else {
105  double beta = new_gamma / gamma;
106  // d = g + d*beta;
107  d *= beta;
108  d += 1.0 * g;
109  }
110 
111  gamma = new_gamma;
112 
113  // In-place recalculation Ad <- A*d to avoid re-allocating Ad
114  Ab.multiplyInPlace(d, Ad);
115  return false;
116  }
117 
118  }; // CGState Class
119 
120  /* ************************************************************************* */
121  // conjugate gradient method.
122  // S: linear system, V: step vector, E: errors
123  template<class S, class V, class E>
125 
126  CGState<S, V, E> state(Ab, x, parameters, steepest);
127 
129  std::cout << "CG: epsilon = " << parameters.epsilon()
130  << ", maxIterations = " << parameters.maxIterations()
131  << ", ||g0||^2 = " << state.gamma
132  << ", threshold = " << state.threshold
133  << std::endl;
134 
135  if ( state.gamma < state.threshold ) {
137  std::cout << "||g0||^2 < threshold, exiting immediately !" << std::endl;
138 
139  return x;
140  }
141 
142  // loop maxIterations times
143  while (!state.step(Ab, x)) {}
144  return x;
145  }
146 /* ************************************************************************* */
147 
148 } // namespace gtsam
void print(const Matrix &A, const string &s, ostream &stream)
Definition: Matrix.cpp:155
#define max(a, b)
Definition: datatypes.h:20
double dot(const V1 &a, const V2 &b)
Definition: Vector.h:195
Iterative methods, implementation.
V conjugateGradients(const S &Ab, V x, const ConjugateGradientParameters &parameters, bool steepest)
DiscreteKey S(1, 2)
Implementation of Conjugate Gradient solver for a linear system.
int k
iteration
Definition: iterative-inl.h:34
bool steepest
flag to indicate we are doing steepest descent
Definition: iterative-inl.h:35
bool step(const S &Ab, V &x)
Definition: iterative-inl.h:80
CGState(const S &Ab, const V &x, const Parameters &parameters, bool steep)
Definition: iterative-inl.h:42
ConjugateGradientParameters Parameters
Definition: iterative-inl.h:31
RealScalar alpha
static ConjugateGradientParameters parameters
const Parameters & parameters_
Definition: iterative-inl.h:32
traits
Definition: chartTesting.h:28
double threshold
gamma (squared L2 norm of g) and convergence threshold
Definition: iterative-inl.h:37
DiscreteKey E(5, 2)
V d
gradient g and search direction d for CG
Definition: iterative-inl.h:36
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
double takeOptimalStep(V &x)
Definition: iterative-inl.h:71
void print(const V &x)
Definition: iterative-inl.h:60


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