testPreconditioner.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 
20 
21 #include <gtsam/nonlinear/Values.h>
25 #include <gtsam/linear/PCGSolver.h>
26 #include <gtsam/geometry/Point2.h>
27 
28 using namespace std;
29 using namespace gtsam;
30 
31 /* ************************************************************************* */
32 TEST( PCGsolver, verySimpleLinearSystem) {
33 
34  // Ax = [4 1][u] = [1] x0 = [2]
35  // [1 3][v] [2] [1]
36  //
37  // exact solution x = [1/11, 7/11]';
38  //
39 
40  // Create a Gaussian Factor Graph
41  GaussianFactorGraph simpleGFG;
42  simpleGFG += JacobianFactor(0, (Matrix(2,2)<< 4, 1, 1, 3).finished(), (Vector(2) << 1,2 ).finished(), noiseModel::Unit::Create(2));
43 
44  // Exact solution already known
45  VectorValues exactSolution;
46  exactSolution.insert(0, (Vector(2) << 1./11., 7./11.).finished());
47  //exactSolution.print("Exact");
48 
49  // Solve the system using direct method
50  VectorValues deltaDirect = simpleGFG.optimize();
51  EXPECT(assert_equal(exactSolution, deltaDirect, 1e-7));
52  //deltaDirect.print("Direct");
53 
54  // Solve the system using Preconditioned Conjugate Gradient solver
55  // Common PCG parameters
56  gtsam::PCGSolverParameters::shared_ptr pcg = boost::make_shared<gtsam::PCGSolverParameters>();
57  pcg->setMaxIterations(500);
58  pcg->setEpsilon_abs(0.0);
59  pcg->setEpsilon_rel(0.0);
60  //pcg->setVerbosity("ERROR");
61 
62  // With Dummy preconditioner
63  pcg->preconditioner_ = boost::make_shared<gtsam::DummyPreconditionerParameters>();
64  VectorValues deltaPCGDummy = PCGSolver(*pcg).optimize(simpleGFG);
65  EXPECT(assert_equal(exactSolution, deltaPCGDummy, 1e-7));
66  //deltaPCGDummy.print("PCG Dummy");
67 
68  // With Block-Jacobi preconditioner
69  pcg->preconditioner_ = boost::make_shared<gtsam::BlockJacobiPreconditionerParameters>();
70  // It takes more than 1000 iterations for this test
71  pcg->setMaxIterations(1500);
72  VectorValues deltaPCGJacobi = PCGSolver(*pcg).optimize(simpleGFG);
73 
74  EXPECT(assert_equal(exactSolution, deltaPCGJacobi, 1e-5));
75  //deltaPCGJacobi.print("PCG Jacobi");
76 }
77 
78 /* ************************************************************************* */
79 TEST(PCGSolver, simpleLinearSystem) {
80  // Create a Gaussian Factor Graph
81  GaussianFactorGraph simpleGFG;
82  //SharedDiagonal unit2 = noiseModel::Unit::Create(2);
83  SharedDiagonal unit2 = noiseModel::Diagonal::Sigmas(Vector2(0.5, 0.3));
84  simpleGFG += JacobianFactor(2, (Matrix(2,2)<< 10, 0, 0, 10).finished(), (Vector(2) << -1, -1).finished(), unit2);
85  simpleGFG += 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);
86  simpleGFG += 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);
87  simpleGFG += 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);
88  simpleGFG += JacobianFactor(0, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
89  simpleGFG += JacobianFactor(1, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
90  simpleGFG += JacobianFactor(2, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2);
91  //simpleGFG.print("system");
92 
93  // Expected solution
94  VectorValues expectedSolution;
95  expectedSolution.insert(0, (Vector(2) << 0.100498, -0.196756).finished());
96  expectedSolution.insert(2, (Vector(2) << -0.0990413, -0.0980577).finished());
97  expectedSolution.insert(1, (Vector(2) << -0.0973252, 0.100582).finished());
98  //expectedSolution.print("Expected");
99 
100  // Solve the system using direct method
101  VectorValues deltaDirect = simpleGFG.optimize();
102  EXPECT(assert_equal(expectedSolution, deltaDirect, 1e-5));
103  //deltaDirect.print("Direct");
104 
105  // Solve the system using Preconditioned Conjugate Gradient solver
106  // Common PCG parameters
107  gtsam::PCGSolverParameters::shared_ptr pcg = boost::make_shared<gtsam::PCGSolverParameters>();
108  pcg->setMaxIterations(500);
109  pcg->setEpsilon_abs(0.0);
110  pcg->setEpsilon_rel(0.0);
111  //pcg->setVerbosity("ERROR");
112 
113  // With Dummy preconditioner
114  pcg->preconditioner_ = boost::make_shared<gtsam::DummyPreconditionerParameters>();
115  VectorValues deltaPCGDummy = PCGSolver(*pcg).optimize(simpleGFG);
116  EXPECT(assert_equal(expectedSolution, deltaPCGDummy, 1e-5));
117  //deltaPCGDummy.print("PCG Dummy");
118 
119  // With Block-Jacobi preconditioner
120  pcg->preconditioner_ = boost::make_shared<gtsam::BlockJacobiPreconditionerParameters>();
121  VectorValues deltaPCGJacobi = PCGSolver(*pcg).optimize(simpleGFG);
122  EXPECT(assert_equal(expectedSolution, deltaPCGJacobi, 1e-5));
123  //deltaPCGJacobi.print("PCG Jacobi");
124 
125 }
126 
127 /* ************************************************************************* */
128 int main() { TestResult tr; return TestRegistry::runAllTests(tr); }
129 /* ************************************************************************* */
VectorValues optimize(const Eliminate &function=EliminationTraitsType::DefaultEliminate) const
static int runAllTests(TestResult &result)
A non-templated config holding any types of Manifold-group elements.
Definition: Half.h:150
Factor Graph Values.
#define EXPECT(condition)
Definition: Test.h:151
TEST(PCGsolver, verySimpleLinearSystem)
Array< double, 1, 3 > e(1./3., 0.5, 2.)
Linear Factor Graph where all factors are Gaussians.
static SharedNoiseModel unit2(noiseModel::Unit::Create(2))
noiseModel::Diagonal::shared_ptr SharedDiagonal
Definition: NoiseModel.h:736
traits
Definition: chartTesting.h:28
bool assert_equal(const Matrix &expected, const Matrix &actual, double tol)
Definition: Matrix.cpp:42
Eigen::Vector2d Vector2
Definition: Vector.h:42
boost::shared_ptr< PCGSolverParameters > shared_ptr
Definition: PCGSolver.h:39
VectorValues optimize(const GaussianFactorGraph &gfg, const KeyInfo &keyInfo, const std::map< Key, Vector > &lambda, const VectorValues &initial) override
Definition: PCGSolver.cpp:60
Eigen::Matrix< double, Eigen::Dynamic, Eigen::Dynamic, Eigen::RowMajor > Matrix
2D Point
Eigen::Matrix< double, Eigen::Dynamic, 1 > Vector
iterator insert(const std::pair< Key, Vector > &key_value)
int main()


gtsam
Author(s):
autogenerated on Sat May 8 2021 02:48:56