PowerMethod.h
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010-2019, 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 
20 #pragma once
21 
22 #include <gtsam/base/Matrix.h>
23 #include <gtsam/base/Vector.h>
24 
25 #include <Eigen/Core>
26 #include <Eigen/Sparse>
27 #include <random>
28 #include <vector>
29 #include <optional>
30 
31 namespace gtsam {
32 
34 
57 template <class Operator>
58 class PowerMethod {
59  protected:
64  const Operator &A_;
65 
66  const int dim_; // dimension of Matrix A
67 
68  size_t nrIterations_; // number of iterations
69 
70  double ritzValue_; // Ritz eigenvalue
71  Vector ritzVector_; // Ritz eigenvector
72 
73  public:
76 
78  explicit PowerMethod(const Operator &A,
79  const std::optional<Vector> initial = {})
80  : A_(A), dim_(A.rows()), nrIterations_(0) {
81  Vector x0;
82  x0 = initial ? *initial : Vector::Random(dim_);
83  x0.normalize();
84 
85  // initialize Ritz eigen value
86  ritzValue_ = 0.0;
87 
88  // initialize Ritz eigen vector
89  ritzVector_ = powerIteration(x0);
90  }
91 
96  Vector powerIteration(const Vector &x) const {
97  Vector y = A_ * x;
98  y.normalize();
99  return y;
100  }
101 
106  Vector powerIteration() const { return powerIteration(ritzVector_); }
107 
113  bool converged(double tol) const {
114  const Vector x = ritzVector_;
115  // store the Ritz eigen value
116  const double ritzValue = x.dot(A_ * x);
117  const double error = (A_ * x - ritzValue * x).norm();
118  return error < tol;
119  }
120 
122  size_t nrIterations() const { return nrIterations_; }
123 
130  bool compute(size_t maxIterations, double tol) {
131  // Starting
132  bool isConverged = false;
133 
134  for (size_t i = 0; i < maxIterations && !isConverged; i++) {
135  ++nrIterations_;
136  // update the ritzVector after power iteration
137  ritzVector_ = powerIteration();
138  // update the ritzValue
139  ritzValue_ = ritzVector_.dot(A_ * ritzVector_);
140  isConverged = converged(tol);
141  }
142 
143  return isConverged;
144  }
145 
147  double eigenvalue() const { return ritzValue_; }
148 
150  Vector eigenvector() const { return ritzVector_; }
151 };
152 
153 } // namespace gtsam
const Operator & A_
Definition: PowerMethod.h:64
Scalar * y
bool compute(size_t maxIterations, double tol)
Definition: PowerMethod.h:130
Values initial
Vector powerIteration(const Vector &x) const
Definition: PowerMethod.h:96
Eigen::SparseMatrix< double > Sparse
Eigen::VectorXd Vector
Definition: Vector.h:38
Compute maximum Eigenpair with power method.
Definition: PowerMethod.h:58
PowerMethod(const Operator &A, const std::optional< Vector > initial={})
Construct from the aim matrix and intial ritz vector.
Definition: PowerMethod.h:78
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
static Symbol x0('x', 0)
double eigenvalue() const
Return the eigenvalue.
Definition: PowerMethod.h:147
static double error
Definition: testRot3.cpp:37
const G double tol
Definition: Group.h:86
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
bool converged(double tol) const
Definition: PowerMethod.h:113
Vector eigenvector() const
Return the eigenvector.
Definition: PowerMethod.h:150
Vector powerIteration() const
Definition: PowerMethod.h:106
size_t nrIterations() const
Return the number of iterations.
Definition: PowerMethod.h:122


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:35:15