Go to the documentation of this file.
30 #include <Eigen/Dense>
31 #include <Eigen/Eigenvalues>
36 using namespace gtsam;
49 0.2465342).finished();
55 const double ritzValue = actual1.dot(
A * actual1);
56 const double ritzResidual = (
A * actual1 - ritzValue * actual1).norm();
59 const double ev1 = 6.0;
75 if (
solver.eigenvalues()(
i).real() >=
solver.eigenvalues()(maxIdx).real())
79 const auto ev1 =
solver.eigenvalues()(maxIdx).
real();
86 const double ritzValue = actual2.dot(
L.first * actual2);
87 const double ritzResidual = (
L.first * actual2 - ritzValue * actual2).norm();
103 if (
solver.eigenvalues()(
i).real() >=
solver.eigenvalues()(maxIdx).real())
107 const auto ev1 =
solver.eigenvalues()(maxIdx).
real();
114 const double ritzValue = actual2.dot(
L.first * actual2);
115 const double ritzResidual = (
L.first * actual2 - ritzValue * actual2).norm();
static int runAllTests(TestResult &result)
GaussianFactorGraph createDenseGraph()
Linear Factor Graph where all factors are Gaussians.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
#define EXPECT_LONGS_EQUAL(expected, actual)
Compute maximum Eigenpair with power method.
typedef and functions to augment Eigen's MatrixXd
std::pair< Matrix, Vector > hessian(const Ordering &ordering) const
GaussianFactorGraph createSparseGraph()
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
Power method for fast eigenvalue and eigenvector computation.
TEST(PowerMethod, powerIteration)
double eigenvalue() const
Return the eigenvalue.
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
Vector eigenvector() const
Return the eigenvector.
Computes eigenvalues and eigenvectors of general matrices.
Create sparse and dense factor graph for PowerMethod/AcceleratedPowerMethod.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
bool compute(size_t maxIterations, double tol)
gtsam
Author(s):
autogenerated on Fri Nov 1 2024 03:41:02