testPowerMethod.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(PowerMethod, powerIteration) {
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  PowerMethod<Sparse> pf(A, initial);
51  pf.compute(100, 1e-5);
52  EXPECT_LONGS_EQUAL(6, pf.eigenvector().rows());
53 
54  Vector6 actual1 = pf.eigenvector();
55  const double ritzValue = actual1.dot(A * actual1);
56  const double ritzResidual = (A * actual1 - ritzValue * actual1).norm();
57  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
58 
59  const double ev1 = 6.0;
60  EXPECT_DOUBLES_EQUAL(ev1, pf.eigenvalue(), 1e-5);
61 }
62 
63 /* ************************************************************************* */
64 TEST(PowerMethod, useFactorGraphSparse) {
65  // Let's make a scalar synchronization graph with 4 nodes
67 
68  // Get eigenvalues and eigenvectors with Eigen
69  auto L = fg.hessian();
71 
72  // find the index of the max eigenvalue
73  size_t maxIdx = 0;
74  for (auto i = 0; i < solver.eigenvalues().rows(); ++i) {
75  if (solver.eigenvalues()(i).real() >= solver.eigenvalues()(maxIdx).real())
76  maxIdx = i;
77  }
78  // Store the max eigenvalue and its according eigenvector
79  const auto ev1 = solver.eigenvalues()(maxIdx).real();
80 
81  Vector initial = Vector4::Random();
82  PowerMethod<Matrix> pf(L.first, initial);
83  pf.compute(100, 1e-5);
84  EXPECT_DOUBLES_EQUAL(ev1, pf.eigenvalue(), 1e-8);
85  auto actual2 = pf.eigenvector();
86  const double ritzValue = actual2.dot(L.first * actual2);
87  const double ritzResidual = (L.first * actual2 - ritzValue * actual2).norm();
88  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
89 }
90 
91 /* ************************************************************************* */
92 TEST(PowerMethod, useFactorGraphDense) {
93  // Let's make a scalar synchronization graph with 10 nodes
95 
96  // Get eigenvalues and eigenvectors with Eigen
97  auto L = fg.hessian();
99 
100  // find the index of the max eigenvalue
101  size_t maxIdx = 0;
102  for (auto i = 0; i < solver.eigenvalues().rows(); ++i) {
103  if (solver.eigenvalues()(i).real() >= solver.eigenvalues()(maxIdx).real())
104  maxIdx = i;
105  }
106  // Store the max eigenvalue and its according eigenvector
107  const auto ev1 = solver.eigenvalues()(maxIdx).real();
108 
109  Vector initial = Vector10::Random();
110  PowerMethod<Matrix> pf(L.first, initial);
111  pf.compute(100, 1e-5);
112  EXPECT_DOUBLES_EQUAL(ev1, pf.eigenvalue(), 1e-8);
113  auto actual2 = pf.eigenvector();
114  const double ritzValue = actual2.dot(L.first * actual2);
115  const double ritzResidual = (L.first * actual2 - ritzValue * actual2).norm();
116  EXPECT_DOUBLES_EQUAL(0, ritzResidual, 1e-5);
117 }
118 
119 /* ************************************************************************* */
120 int main() {
121  TestResult tr;
122  return TestRegistry::runAllTests(tr);
123 }
124 /* ************************************************************************* */
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.
bool compute(size_t maxIterations, double tol)
Definition: PowerMethod.h:129
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
Eigen::VectorXd Vector
Definition: Vector.h:38
Power method for fast eigenvalue and eigenvector computation.
Compute maximum Eigenpair with power method.
Definition: PowerMethod.h:57
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
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
int main()
TEST(PowerMethod, powerIteration)
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:48:52