Go to the documentation of this file.
   30 #include <Eigen/Dense> 
   31 #include <Eigen/Eigenvalues> 
   36 using namespace gtsam;
 
   49        0.2465342).finished();
 
   50   const double ev1 = 6.0;
 
   58   const double ritzValue = actual1.dot(
A * actual1);
 
   59   const double ritzResidual = (
A * actual1 - ritzValue * actual1).norm();
 
   77     if (
solver.eigenvalues()(
i).real() >= 
solver.eigenvalues()(maxIdx).real())
 
   81   const auto ev1 = 
solver.eigenvalues()(maxIdx).
real();
 
   83   Vector disturb = Vector4::Random();
 
   86   double magnitude = 
initial.norm();
 
   87   initial += 0.03 * magnitude * disturb;
 
   95   const double ritzValue = actual1.dot(
L.first * actual1);
 
   96   const double ritzResidual = (
L.first * actual1 - ritzValue * actual1).norm();
 
  112     if (
solver.eigenvalues()(
i).real() >= 
solver.eigenvalues()(maxIdx).real())
 
  116   const auto ev1 = 
solver.eigenvalues()(maxIdx).
real();
 
  118   Vector disturb = Vector10::Random();
 
  121   double magnitude = 
initial.norm();
 
  122   initial += 0.03 * magnitude * disturb;
 
  130   const double ritzValue = actual1.dot(
L.first * actual1);
 
  131   const double ritzResidual = (
L.first * actual1 - ritzValue * actual1).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)
typedef and functions to augment Eigen's MatrixXd
std::pair< Matrix, Vector > hessian(const Ordering &ordering) const
TEST(AcceleratedPowerMethod, acceleratedPowerIteration)
GaussianFactorGraph createSparseGraph()
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
accelerated power method for fast eigenvalue and eigenvector computation
bool compute(size_t maxIterations, double tol)
Compute maximum Eigenpair with accelerated power method.
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
gtsam
Author(s): 
autogenerated on Wed May 28 2025 03:06:04