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 
30 namespace gtsam {
31 
33 
56 template <class Operator>
57 class PowerMethod {
58  protected:
63  const Operator &A_;
64 
65  const int dim_; // dimension of Matrix A
66 
67  size_t nrIterations_; // number of iterations
68 
69  double ritzValue_; // Ritz eigenvalue
70  Vector ritzVector_; // Ritz eigenvector
71 
72  public:
75 
77  explicit PowerMethod(const Operator &A,
78  const boost::optional<Vector> initial = boost::none)
79  : A_(A), dim_(A.rows()), nrIterations_(0) {
80  Vector x0;
81  x0 = initial ? initial.get() : Vector::Random(dim_);
82  x0.normalize();
83 
84  // initialize Ritz eigen value
85  ritzValue_ = 0.0;
86 
87  // initialize Ritz eigen vector
88  ritzVector_ = powerIteration(x0);
89  }
90 
95  Vector powerIteration(const Vector &x) const {
96  Vector y = A_ * x;
97  y.normalize();
98  return y;
99  }
100 
105  Vector powerIteration() const { return powerIteration(ritzVector_); }
106 
112  bool converged(double tol) const {
113  const Vector x = ritzVector_;
114  // store the Ritz eigen value
115  const double ritzValue = x.dot(A_ * x);
116  const double error = (A_ * x - ritzValue * x).norm();
117  return error < tol;
118  }
119 
121  size_t nrIterations() const { return nrIterations_; }
122 
129  bool compute(size_t maxIterations, double tol) {
130  // Starting
131  bool isConverged = false;
132 
133  for (size_t i = 0; i < maxIterations && !isConverged; i++) {
134  ++nrIterations_;
135  // update the ritzVector after power iteration
136  ritzVector_ = powerIteration();
137  // update the ritzValue
138  ritzValue_ = ritzVector_.dot(A_ * ritzVector_);
139  isConverged = converged(tol);
140  }
141 
142  return isConverged;
143  }
144 
146  double eigenvalue() const { return ritzValue_; }
147 
149  Vector eigenvector() const { return ritzVector_; }
150 };
151 
152 } // namespace gtsam
const Operator & A_
Definition: PowerMethod.h:63
Scalar * y
Vector eigenvector() const
Return the eigenvector.
Definition: PowerMethod.h:149
PowerMethod(const Operator &A, const boost::optional< Vector > initial=boost::none)
Construct from the aim matrix and intial ritz vector.
Definition: PowerMethod.h:77
size_t nrIterations() const
Return the number of iterations.
Definition: PowerMethod.h:121
bool compute(size_t maxIterations, double tol)
Definition: PowerMethod.h:129
Eigen::SparseMatrix< double > Sparse
Vector powerIteration(const Vector &x) const
Definition: PowerMethod.h:95
Eigen::VectorXd Vector
Definition: Vector.h:38
Compute maximum Eigenpair with power method.
Definition: PowerMethod.h:57
bool converged(double tol) const
Definition: PowerMethod.h:112
static Symbol x0('x', 0)
traits
Definition: chartTesting.h:28
typedef and functions to augment Eigen&#39;s VectorXd
Vector powerIteration() const
Definition: PowerMethod.h:105
static double error
Definition: testRot3.cpp:39
const G double tol
Definition: Group.h:83
double eigenvalue() const
Return the eigenvalue.
Definition: PowerMethod.h:146
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


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:43:28