testPCGSolver.cpp
Go to the documentation of this file.
1 /* ----------------------------------------------------------------------------
2 
3  * GTSAM Copyright 2010, 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 
19 #include <tests/smallExample.h>
22 #include <gtsam/linear/PCGSolver.h>
24 #include <gtsam/inference/Symbol.h>
25 #include <gtsam/base/Matrix.h>
26 
28 
29 #include <iostream>
30 #include <fstream>
31 
32 using namespace std;
33 using namespace gtsam;
34 
35 const double tol = 1e-3;
36 
39 
40 /* ************************************************************************* */
41 // Test cholesky decomposition
43  Matrix R = (Matrix(3,3) <<
44  1., -1., -1.,
45  0., 2., -1.,
46  0., 0., 1.).finished();
47  Matrix AtA = R.transpose() * R;
48 
49  Vector Rvector = (Vector(9) << 1., -1., -1.,
50  0., 2., -1.,
51  0., 0., 1.).finished();
52 // Vector Rvector = (Vector(6) << 1., -1., -1.,
53 // 2., -1.,
54 // 1.).finished();
55 
56  Vector b = Vector3(1., 2., 3.);
57 
58  Vector x = Vector3(6.5, 2.5, 3.) ;
59 
60  /* test cholesky */
61  Matrix Rhat = AtA.llt().matrixL().transpose();
62  EXPECT(assert_equal(R, Rhat, 1e-5));
63 
64  /* test backward substitution */
65  Vector xhat = Rhat.triangularView<Eigen::Upper>().solve(b);
66  EXPECT(assert_equal(x, xhat, 1e-5));
67 
68  /* test in-place back substitution */
69  xhat = b;
70  Rhat.triangularView<Eigen::Upper>().solveInPlace(xhat);
71  EXPECT(assert_equal(x, xhat, 1e-5));
72 
73  /* test triangular matrix map */
74  Eigen::Map<Eigen::MatrixXd> Radapter(Rvector.data(), 3, 3);
75  xhat = Radapter.transpose().triangularView<Eigen::Upper>().solve(b);
76  EXPECT(assert_equal(x, xhat, 1e-5));
77 
78 }
79 
80 /* ************************************************************************* */
81 // Test GaussianFactorGraphSystem::multiply and getb
83 {
84  // Create a Gaussian Factor Graph
85  GaussianFactorGraph simpleGFG;
86  SharedDiagonal unit2 = noiseModel::Diagonal::Sigmas(Vector2(0.5, 0.3));
87  simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< 10, 0, 0, 10).finished(), (Vector(2) << -1, -1).finished(), unit2);
88  simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< -10, 0, 0, -10).finished(), 0, (Matrix(2,2)<< 10, 0, 0, 10).finished(), (Vector(2) << 2, -1).finished(), unit2);
89  simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< -5, 0, 0, -5).finished(), 1, (Matrix(2,2)<< 5, 0, 0, 5).finished(), (Vector(2) << 0, 1).finished(), unit2);
90  simpleGFG.emplace_shared<JacobianFactor>(0, (Matrix(2,2)<< -5, 0, 0, -5).finished(), 1, (Matrix(2,2)<< 5, 0, 0, 5).finished(), (Vector(2) << -1, 1.5).finished(), unit2);
91  simpleGFG.emplace_shared<JacobianFactor>(0, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
92  simpleGFG.emplace_shared<JacobianFactor>(1, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
93  simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
94 
95  // Create a dummy-preconditioner and a GaussianFactorGraphSystem
96  DummyPreconditioner dummyPreconditioner;
97  KeyInfo keyInfo(simpleGFG);
98  std::map<Key,Vector> lambda;
99  dummyPreconditioner.build(simpleGFG, keyInfo, lambda);
100  GaussianFactorGraphSystem gfgs(simpleGFG, dummyPreconditioner, keyInfo, lambda);
101 
102  // Prepare container for each variable
103  Vector initial, residual, preconditionedResidual, p, actualAp;
104  initial = (Vector(6) << 0., 0., 0., 0., 0., 0.).finished();
105 
106  // Calculate values using GaussianFactorGraphSystem same as inside of PCGSolver
107  gfgs.residual(initial, residual); /* r = b-Ax */
108  gfgs.leftPrecondition(residual, preconditionedResidual); /* pr = L^{-1} (b-Ax) */
109  gfgs.rightPrecondition(preconditionedResidual, p); /* p = L^{-T} pr */
110  gfgs.multiply(p, actualAp); /* A p */
111 
112  // Expected value of Ap for the first iteration of this example problem
113  Vector expectedAp = (Vector(6) << 100400, -249074.074, -2080, 148148.148, -146480, 37962.963).finished();
114  EXPECT(assert_equal(expectedAp, actualAp, 1e-3));
115 
116  // Expected value of getb
117  Vector expectedb = (Vector(6) << 100.0, -194.444, -20.0, 138.889, -120.0, -55.556).finished();
118  Vector actualb;
119  gfgs.getb(actualb);
120  EXPECT(assert_equal(expectedb, actualb, 1e-3));
121 }
122 
123 /* ************************************************************************* */
124 // Test Dummy Preconditioner
127  params.linearSolverType = LevenbergMarquardtParams::Iterative;
128  auto pcg = std::make_shared<PCGSolverParameters>();
129  pcg->preconditioner_ = std::make_shared<DummyPreconditionerParameters>();
130  params.iterativeParams = pcg;
131 
133 
134  Point2 x0(10, 10);
135  Values c0;
136  c0.insert(X(1), x0);
137 
138  Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize();
139 
140  DOUBLES_EQUAL(0, fg.error(actualPCG), tol);
141 }
142 
143 /* ************************************************************************* */
144 // Test Block-Jacobi Precondioner
145 TEST(PCGSolver, blockjacobi) {
147  params.linearSolverType = LevenbergMarquardtParams::Iterative;
148  auto pcg = std::make_shared<PCGSolverParameters>();
149  pcg->preconditioner_ =
150  std::make_shared<BlockJacobiPreconditionerParameters>();
151  params.iterativeParams = pcg;
152 
154 
155  Point2 x0(10, 10);
156  Values c0;
157  c0.insert(X(1), x0);
158 
159  Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize();
160 
161  DOUBLES_EQUAL(0, fg.error(actualPCG), tol);
162 }
163 
164 /* ************************************************************************* */
165 // Test Incremental Subgraph PCG Solver
166 TEST(PCGSolver, subgraph) {
168  params.linearSolverType = LevenbergMarquardtParams::Iterative;
169  auto pcg = std::make_shared<PCGSolverParameters>();
170  pcg->preconditioner_ = std::make_shared<SubgraphPreconditionerParameters>();
171  params.iterativeParams = pcg;
172 
174 
175  Point2 x0(10, 10);
176  Values c0;
177  c0.insert(X(1), x0);
178 
179  Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize();
180 
181  DOUBLES_EQUAL(0, fg.error(actualPCG), tol);
182 }
183 
184 /* ************************************************************************* */
185 int main() {
186  TestResult tr;
187  return TestRegistry::runAllTests(tr);
188 }
189 
TEST(PCGSolver, llt)
void rightPrecondition(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:130
virtual const Values & optimize()
Scalar * b
Definition: benchVecAdd.cpp:17
IsDerived< DERIVEDFACTOR > emplace_shared(Args &&... args)
Emplace a shared pointer to factor of given type.
Definition: FactorGraph.h:196
static int runAllTests(TestResult &result)
Eigen::Vector3d Vector3
Definition: Vector.h:43
void multiply(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:94
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
Matrix2 transpose() const
Definition: Rot2.cpp:92
#define DOUBLES_EQUAL(expected, actual, threshold)
Definition: Test.h:141
Vector2 Point2
Definition: Point2.h:32
NonlinearFactorGraph createReallyNonlinearFactorGraph()
Definition: smallExample.h:378
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:40
Eigen::MatrixXd Matrix
Definition: base/Matrix.h:39
Rot2 R(Rot2::fromAngle(0.1))
Values initial
MatrixXd L
Definition: LLT_example.cpp:6
Definition: BFloat16.h:88
static const SmartProjectionParams params
EIGEN_DONT_INLINE void llt(const Mat &A, const Mat &B, Mat &C)
Definition: llt.cpp:5
Eigen::VectorXd Vector
Definition: Vector.h:38
#define EXPECT(condition)
Definition: Test.h:150
const double tol
A nonlinear optimizer that uses the Levenberg-Marquardt trust-region scheme.
Array< double, 1, 3 > e(1./3., 0.5, 2.)
void leftPrecondition(const Vector &x, Vector &y) const
Definition: PCGSolver.cpp:122
Linear Factor Graph where all factors are Gaussians.
IterativeOptimizationParameters::shared_ptr iterativeParams
The container for iterativeOptimization parameters. used in CG Solvers.
double error(const Values &values) const
int main()
cout<< "The eigenvalues of A are:"<< endl<< ces.eigenvalues()<< endl;cout<< "The matrix of eigenvectors, V, is:"<< endl<< ces.eigenvectors()<< endl<< endl;complex< float > lambda
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:743
traits
Definition: chartTesting.h:28
static Symbol x0('x', 0)
Eigen::Vector2d Vector2
Definition: Vector.h:42
float * p
Create small example with two poses and one landmark.
void insert(Key j, const Value &val)
Definition: Values.cpp:155
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
#define X
Definition: icosphere.cpp:20
set noclip points set clip one set noclip two set bar set border lt lw set xdata set ydata set zdata set x2data set y2data set boxwidth set dummy x
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
void residual(const Vector &x, Vector &r) const
Definition: PCGSolver.cpp:81
LinearSolverType linearSolverType
The type of linear solver to use in the nonlinear optimizer.
void getb(Vector &b) const
Definition: PCGSolver.cpp:111


gtsam
Author(s):
autogenerated on Tue Jul 4 2023 02:38:55