testAcceleratedPowerMethod.cpp
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 
22 #include <gtsam/base/Matrix.h>
23 #include <gtsam/base/VectorSpace.h>
24 #include <gtsam/inference/Symbol.h>
28 
29 #include <Eigen/Core>
30 #include <Eigen/Dense>
31 #include <Eigen/Eigenvalues>
32 #include <iostream>
33 #include <random>
34 
35 using namespace std;
36 using namespace gtsam;
37 
38 /* ************************************************************************* */
39 TEST(AcceleratedPowerMethod, acceleratedPowerIteration) {
40  // test power iteration, beta is set to 0
41  Sparse A(6, 6);
42  A.coeffRef(0, 0) = 6;
43  A.coeffRef(1, 1) = 5;
44  A.coeffRef(2, 2) = 4;
45  A.coeffRef(3, 3) = 3;
46  A.coeffRef(4, 4) = 2;
47  A.coeffRef(5, 5) = 1;
48  Vector initial = (Vector(6) << 0.24434602, 0.22829942, 0.70094486, 0.15463092, 0.55871359,
49  0.2465342).finished();
50  const double ev1 = 6.0;
51 
52  // test accelerated power iteration
53  AcceleratedPowerMethod<Sparse> apf(A, initial);
54  apf.compute(100, 1e-5);
55  EXPECT_LONGS_EQUAL(6, apf.eigenvector().rows());
56 
57  Vector6 actual1 = apf.eigenvector();
58  const double ritzValue = actual1.dot(A * actual1);
59  const double ritzResidual = (A * actual1 - ritzValue * actual1).norm();
60  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
61 
62  EXPECT_DOUBLES_EQUAL(ev1, apf.eigenvalue(), 1e-5);
63 }
64 
65 /* ************************************************************************* */
66 TEST(AcceleratedPowerMethod, useFactorGraphSparse) {
67  // Let's make a scalar synchronization graph with 4 nodes
69 
70  // Get eigenvalues and eigenvectors with Eigen
71  auto L = fg.hessian();
73 
74  // find the index of the max eigenvalue
75  size_t maxIdx = 0;
76  for (auto i = 0; i < solver.eigenvalues().rows(); ++i) {
77  if (solver.eigenvalues()(i).real() >= solver.eigenvalues()(maxIdx).real())
78  maxIdx = i;
79  }
80  // Store the max eigenvalue and its according eigenvector
81  const auto ev1 = solver.eigenvalues()(maxIdx).real();
82 
83  Vector disturb = Vector4::Random();
84  disturb.normalize();
85  Vector initial = L.first.row(0);
86  double magnitude = initial.norm();
87  initial += 0.03 * magnitude * disturb;
88  AcceleratedPowerMethod<Matrix> apf(L.first, initial);
89  apf.compute(100, 1e-5);
90  // Check if the eigenvalue is the maximum eigen value
91  EXPECT_DOUBLES_EQUAL(ev1, apf.eigenvalue(), 1e-8);
92 
93  // Check if the according ritz residual converged to the threshold
94  Vector actual1 = apf.eigenvector();
95  const double ritzValue = actual1.dot(L.first * actual1);
96  const double ritzResidual = (L.first * actual1 - ritzValue * actual1).norm();
97  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
98 }
99 
100 /* ************************************************************************* */
101 TEST(AcceleratedPowerMethod, useFactorGraphDense) {
102  // Let's make a scalar synchronization graph with 10 nodes
104 
105  // Get eigenvalues and eigenvectors with Eigen
106  auto L = fg.hessian();
108 
109  // find the index of the max eigenvalue
110  size_t maxIdx = 0;
111  for (auto i = 0; i < solver.eigenvalues().rows(); ++i) {
112  if (solver.eigenvalues()(i).real() >= solver.eigenvalues()(maxIdx).real())
113  maxIdx = i;
114  }
115  // Store the max eigenvalue and its according eigenvector
116  const auto ev1 = solver.eigenvalues()(maxIdx).real();
117 
118  Vector disturb = Vector10::Random();
119  disturb.normalize();
120  Vector initial = L.first.row(0);
121  double magnitude = initial.norm();
122  initial += 0.03 * magnitude * disturb;
123  AcceleratedPowerMethod<Matrix> apf(L.first, initial);
124  apf.compute(100, 1e-5);
125  // Check if the eigenvalue is the maximum eigen value
126  EXPECT_DOUBLES_EQUAL(ev1, apf.eigenvalue(), 1e-8);
127 
128  // Check if the according ritz residual converged to the threshold
129  Vector actual1 = apf.eigenvector();
130  const double ritzValue = actual1.dot(L.first * actual1);
131  const double ritzResidual = (L.first * actual1 - ritzValue * actual1).norm();
132  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
133 }
134 
135 /* ************************************************************************* */
136 int main() {
137  TestResult tr;
138  return TestRegistry::runAllTests(tr);
139 }
140 /* ************************************************************************* */
float real
Definition: datatypes.h:10
Vector eigenvector() const
Return the eigenvector.
Definition: PowerMethod.h:149
static int runAllTests(TestResult &result)
GaussianFactorGraph createSparseGraph()
Create sparse and dense factor graph for PowerMethod/AcceleratedPowerMethod.
Compute maximum Eigenpair with accelerated power method.
MatrixXd L
Definition: LLT_example.cpp:6
Definition: Half.h:150
BiCGSTAB< SparseMatrix< double > > solver
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:162
accelerated power method for fast eigenvalue and eigenvector computation
Eigen::VectorXd Vector
Definition: Vector.h:38
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
bool compute(size_t maxIterations, double tol)
std::pair< Matrix, Vector > hessian(const Ordering &ordering) const
traits
Definition: chartTesting.h:28
Scalar & coeffRef(Index row, Index col)
Definition: SparseMatrix.h:206
#define EXPECT_LONGS_EQUAL(expected, actual)
Definition: Test.h:155
TEST(AcceleratedPowerMethod, acceleratedPowerIteration)
GaussianFactorGraph createDenseGraph()
Computes eigenvalues and eigenvectors of general matrices.
Definition: EigenSolver.h:64
double eigenvalue() const
Return the eigenvalue.
Definition: PowerMethod.h:146
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
const EigenvalueType & eigenvalues() const
Returns the eigenvalues of given matrix.
Definition: EigenSolver.h:244


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:46:04