| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | /* ----------------------------------------------------------------------------
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							|  |  |  |  * Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  |  * All Rights Reserved | 
					
						
							|  |  |  |  * Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * See LICENSE for the license information | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /**
 | 
					
						
							|  |  |  |  *  @file   testPreconditioner.cpp | 
					
						
							|  |  |  |  *  @brief  Unit tests for Preconditioners | 
					
						
							|  |  |  |  *  @author Sungtae An | 
					
						
							|  |  |  |  *  @date   Nov 6, 2014 | 
					
						
							|  |  |  |  **/ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | #include <gtsam/nonlinear/Values.h>
 | 
					
						
							| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | #include <gtsam/linear/VectorValues.h>
 | 
					
						
							| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | #include <gtsam/linear/Preconditioner.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/PCGSolver.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | #include <gtsam/geometry/Point2.h>
 | 
					
						
							| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | TEST( PCGsolver, verySimpleLinearSystem) { | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Ax = [4 1][u] = [1]  x0 = [2]
 | 
					
						
							|  |  |  |   //      [1 3][v]   [2]       [1]
 | 
					
						
							|  |  |  |   //
 | 
					
						
							|  |  |  |   // exact solution x = [1/11, 7/11]';
 | 
					
						
							|  |  |  |   //
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a Gaussian Factor Graph
 | 
					
						
							|  |  |  |   GaussianFactorGraph simpleGFG; | 
					
						
							| 
									
										
										
										
											2023-02-06 16:40:32 +08:00
										 |  |  |   simpleGFG.emplace_shared<JacobianFactor>(0, (Matrix(2,2)<< 4, 1, 1, 3).finished(), (Vector(2) << 1,2 ).finished(), noiseModel::Unit::Create(2)); | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Exact solution already known
 | 
					
						
							|  |  |  |   VectorValues exactSolution; | 
					
						
							| 
									
										
										
										
											2014-12-01 18:07:43 +08:00
										 |  |  |   exactSolution.insert(0, (Vector(2) << 1./11., 7./11.).finished()); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   //exactSolution.print("Exact");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Solve the system using direct method
 | 
					
						
							|  |  |  |   VectorValues deltaDirect = simpleGFG.optimize(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(exactSolution, deltaDirect, 1e-7)); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   //deltaDirect.print("Direct");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   // Solve the system using Preconditioned Conjugate Gradient solver
 | 
					
						
							|  |  |  |   // Common PCG parameters
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   gtsam::PCGSolverParameters::shared_ptr pcg = std::make_shared<gtsam::PCGSolverParameters>(); | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->maxIterations = 500; | 
					
						
							|  |  |  |   pcg->epsilon_abs = 0.0; | 
					
						
							|  |  |  |   pcg->epsilon_rel = 0.0; | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  |   //pcg->setVerbosity("ERROR");
 | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // With Dummy preconditioner
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->preconditioner = | 
					
						
							|  |  |  |       std::make_shared<gtsam::DummyPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  |   VectorValues deltaPCGDummy = PCGSolver(*pcg).optimize(simpleGFG); | 
					
						
							|  |  |  |   EXPECT(assert_equal(exactSolution, deltaPCGDummy, 1e-7)); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   //deltaPCGDummy.print("PCG Dummy");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // With Block-Jacobi preconditioner
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->preconditioner = | 
					
						
							|  |  |  |       std::make_shared<gtsam::BlockJacobiPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   // It takes more than 1000 iterations for this test
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:56:52 +08:00
										 |  |  |   pcg->maxIterations = 1500; | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   VectorValues deltaPCGJacobi = PCGSolver(*pcg).optimize(simpleGFG); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  |   EXPECT(assert_equal(exactSolution, deltaPCGJacobi, 1e-5)); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   //deltaPCGJacobi.print("PCG Jacobi");
 | 
					
						
							| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-15 03:09:42 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | TEST(PCGSolver, simpleLinearSystem) { | 
					
						
							|  |  |  |   // Create a Gaussian Factor Graph
 | 
					
						
							|  |  |  |   GaussianFactorGraph simpleGFG; | 
					
						
							| 
									
										
										
										
											2014-12-05 11:14:46 +08:00
										 |  |  |   //SharedDiagonal unit2 = noiseModel::Unit::Create(2);
 | 
					
						
							|  |  |  |   SharedDiagonal unit2 = noiseModel::Diagonal::Sigmas(Vector2(0.5, 0.3)); | 
					
						
							| 
									
										
										
										
											2023-02-06 16:40:32 +08:00
										 |  |  |   simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< 10, 0, 0, 10).finished(), (Vector(2) << -1, -1).finished(), unit2); | 
					
						
							|  |  |  |   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); | 
					
						
							|  |  |  |   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); | 
					
						
							|  |  |  |   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); | 
					
						
							|  |  |  |   simpleGFG.emplace_shared<JacobianFactor>(0, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2); | 
					
						
							|  |  |  |   simpleGFG.emplace_shared<JacobianFactor>(1, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2); | 
					
						
							|  |  |  |   simpleGFG.emplace_shared<JacobianFactor>(2, (Matrix(2,2)<< 1, 0, 0, 1).finished(), (Vector(2) << 0, 0).finished(), unit2); | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //simpleGFG.print("system");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Expected solution
 | 
					
						
							|  |  |  |   VectorValues expectedSolution; | 
					
						
							| 
									
										
										
										
											2014-12-01 18:07:43 +08:00
										 |  |  |   expectedSolution.insert(0, (Vector(2) << 0.100498, -0.196756).finished()); | 
					
						
							|  |  |  |   expectedSolution.insert(2, (Vector(2) << -0.0990413, -0.0980577).finished()); | 
					
						
							|  |  |  |   expectedSolution.insert(1, (Vector(2) << -0.0973252, 0.100582).finished()); | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //expectedSolution.print("Expected");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Solve the system using direct method
 | 
					
						
							|  |  |  |   VectorValues deltaDirect = simpleGFG.optimize(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expectedSolution, deltaDirect, 1e-5)); | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //deltaDirect.print("Direct");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   // Solve the system using Preconditioned Conjugate Gradient solver
 | 
					
						
							|  |  |  |   // Common PCG parameters
 | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   gtsam::PCGSolverParameters::shared_ptr pcg = std::make_shared<gtsam::PCGSolverParameters>(); | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->maxIterations = 500; | 
					
						
							|  |  |  |   pcg->epsilon_abs = 0.0; | 
					
						
							|  |  |  |   pcg->epsilon_rel = 0.0; | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //pcg->setVerbosity("ERROR");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   // With Dummy preconditioner
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->preconditioner = | 
					
						
							|  |  |  |       std::make_shared<gtsam::DummyPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   VectorValues deltaPCGDummy = PCGSolver(*pcg).optimize(simpleGFG); | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  |   EXPECT(assert_equal(expectedSolution, deltaPCGDummy, 1e-5)); | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //deltaPCGDummy.print("PCG Dummy");
 | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   // With Block-Jacobi preconditioner
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:52 +08:00
										 |  |  |   pcg->preconditioner = | 
					
						
							|  |  |  |       std::make_shared<gtsam::BlockJacobiPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2014-12-05 12:30:27 +08:00
										 |  |  |   VectorValues deltaPCGJacobi = PCGSolver(*pcg).optimize(simpleGFG); | 
					
						
							| 
									
										
										
										
											2014-12-01 18:02:02 +08:00
										 |  |  |   EXPECT(assert_equal(expectedSolution, deltaPCGJacobi, 1e-5)); | 
					
						
							| 
									
										
										
										
											2015-01-02 06:50:27 +08:00
										 |  |  |   //deltaPCGJacobi.print("PCG Jacobi");
 | 
					
						
							| 
									
										
										
										
											2014-11-15 03:09:42 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-07 12:14:52 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { TestResult tr; return TestRegistry::runAllTests(tr); } | 
					
						
							|  |  |  | /* ************************************************************************* */ |