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();
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();
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 createSparseGraph()
Create sparse and dense factor graph for PowerMethod/AcceleratedPowerMethod.
Compute maximum Eigenpair with accelerated power method.
BiCGSTAB< SparseMatrix< double > > solver
Matrix< SCALARA, Dynamic, Dynamic, opt_A > A
#define EXPECT_DOUBLES_EQUAL(expected, actual, threshold)
accelerated power method for fast eigenvalue and eigenvector computation
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
double eigenvalue() const
Return the eigenvalue.
Scalar & coeffRef(Index row, Index col)
#define EXPECT_LONGS_EQUAL(expected, actual)
TEST(AcceleratedPowerMethod, acceleratedPowerIteration)
GaussianFactorGraph createDenseGraph()
const EigenvalueType & eigenvalues() const
Returns the eigenvalues of given matrix.
Computes eigenvalues and eigenvectors of general matrices.
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
Vector eigenvector() const
Return the eigenvector.