| 
									
										
										
										
											2014-06-08 12:34:23 +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    testPCGSolver.cpp | 
					
						
							|  |  |  |  * @brief   Unit tests for PCGSolver class | 
					
						
							|  |  |  |  * @author  Yong-Dian Jian | 
					
						
							| 
									
										
										
										
											2014-11-07 03:26:46 +08:00
										 |  |  |  * @date    Aug 06, 2014 | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <tests/smallExample.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/GaussianFactorGraph.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/PCGSolver.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  | #include <gtsam/linear/SubgraphPreconditioner.h>
 | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  | #include <gtsam/inference/Symbol.h>
 | 
					
						
							|  |  |  | #include <gtsam/base/Matrix.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <CppUnitLite/TestHarness.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | #include <iostream>
 | 
					
						
							|  |  |  | #include <fstream>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | const double tol = 1e-3; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using symbol_shorthand::X; | 
					
						
							|  |  |  | using symbol_shorthand::L; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-11-07 03:26:46 +08:00
										 |  |  | // Test cholesky decomposition
 | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | TEST( PCGSolver, llt ) { | 
					
						
							|  |  |  |   Matrix R = (Matrix(3,3) << | 
					
						
							|  |  |  |                 1., -1., -1., | 
					
						
							|  |  |  |                 0.,  2., -1., | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |                 0.,  0.,  1.).finished(); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  |   Matrix AtA = R.transpose() * R; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   Vector Rvector = (Vector(9) << 1., -1., -1., | 
					
						
							|  |  |  |                                  0.,  2., -1., | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  |                                  0.,  0.,  1.).finished(); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | //  Vector Rvector = (Vector(6) << 1., -1., -1.,
 | 
					
						
							|  |  |  | //                                      2., -1.,
 | 
					
						
							| 
									
										
										
										
											2014-11-23 08:35:27 +08:00
										 |  |  | //                                           1.).finished();
 | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector b = Vector3(1., 2., 3.); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-11-24 02:22:25 +08:00
										 |  |  |   Vector x = Vector3(6.5, 2.5, 3.) ; | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   /* test cholesky */ | 
					
						
							|  |  |  |   Matrix Rhat = AtA.llt().matrixL().transpose(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(R, Rhat, 1e-5)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* test backward substitution */ | 
					
						
							|  |  |  |   Vector xhat = Rhat.triangularView<Eigen::Upper>().solve(b); | 
					
						
							|  |  |  |   EXPECT(assert_equal(x, xhat, 1e-5)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* test in-place back substitution */ | 
					
						
							|  |  |  |   xhat = b; | 
					
						
							|  |  |  |   Rhat.triangularView<Eigen::Upper>().solveInPlace(xhat); | 
					
						
							|  |  |  |   EXPECT(assert_equal(x, xhat, 1e-5)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   /* test triangular matrix map */ | 
					
						
							|  |  |  |   Eigen::Map<Eigen::MatrixXd> Radapter(Rvector.data(), 3, 3); | 
					
						
							|  |  |  |   xhat = Radapter.transpose().triangularView<Eigen::Upper>().solve(b); | 
					
						
							|  |  |  |   EXPECT(assert_equal(x, xhat, 1e-5)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-01-31 16:33:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | // Test GaussianFactorGraphSystem::multiply and getb
 | 
					
						
							|  |  |  | TEST( GaussianFactorGraphSystem, multiply_getb) | 
					
						
							|  |  |  | { | 
					
						
							|  |  |  |   // Create a Gaussian Factor Graph
 | 
					
						
							|  |  |  |   GaussianFactorGraph simpleGFG; | 
					
						
							|  |  |  |   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-31 16:33:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create a dummy-preconditioner and a GaussianFactorGraphSystem
 | 
					
						
							|  |  |  |   DummyPreconditioner dummyPreconditioner; | 
					
						
							|  |  |  |   KeyInfo keyInfo(simpleGFG); | 
					
						
							|  |  |  |   std::map<Key,Vector> lambda; | 
					
						
							|  |  |  |   dummyPreconditioner.build(simpleGFG, keyInfo, lambda); | 
					
						
							|  |  |  |   GaussianFactorGraphSystem gfgs(simpleGFG, dummyPreconditioner, keyInfo, lambda); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Prepare container for each variable
 | 
					
						
							|  |  |  |   Vector initial, residual, preconditionedResidual, p, actualAp; | 
					
						
							|  |  |  |   initial = (Vector(6) << 0., 0., 0., 0., 0., 0.).finished(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Calculate values using GaussianFactorGraphSystem same as inside of PCGSolver
 | 
					
						
							|  |  |  |   gfgs.residual(initial, residual);                         /* r = b-Ax */ | 
					
						
							|  |  |  |   gfgs.leftPrecondition(residual, preconditionedResidual);  /* pr = L^{-1} (b-Ax) */ | 
					
						
							|  |  |  |   gfgs.rightPrecondition(preconditionedResidual, p);        /* p = L^{-T} pr */ | 
					
						
							|  |  |  |   gfgs.multiply(p, actualAp);                                     /* A p */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Expected value of Ap for the first iteration of this example problem
 | 
					
						
							|  |  |  |   Vector expectedAp = (Vector(6) << 100400, -249074.074, -2080, 148148.148, -146480, 37962.963).finished(); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expectedAp, actualAp, 1e-3)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Expected value of getb
 | 
					
						
							|  |  |  |   Vector expectedb = (Vector(6) << 100.0, -194.444, -20.0, 138.889, -120.0, -55.556).finished(); | 
					
						
							|  |  |  |   Vector actualb; | 
					
						
							|  |  |  |   gfgs.getb(actualb); | 
					
						
							|  |  |  |   EXPECT(assert_equal(expectedb, actualb, 1e-3)); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-11-07 03:26:46 +08:00
										 |  |  | // Test Dummy Preconditioner
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  | TEST(PCGSolver, dummy) { | 
					
						
							|  |  |  |   LevenbergMarquardtParams params; | 
					
						
							|  |  |  |   params.linearSolverType = LevenbergMarquardtParams::Iterative; | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   auto pcg = std::make_shared<PCGSolverParameters>(); | 
					
						
							|  |  |  |   pcg->preconditioner_ = std::make_shared<DummyPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   params.iterativeParams = pcg; | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   NonlinearFactorGraph fg = example::createReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Point2 x0(10, 10); | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  |   Values c0; | 
					
						
							|  |  |  |   c0.insert(X(1), x0); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize(); | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   DOUBLES_EQUAL(0, fg.error(actualPCG), tol); | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-11-07 03:26:46 +08:00
										 |  |  | // Test Block-Jacobi Precondioner
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  | TEST(PCGSolver, blockjacobi) { | 
					
						
							|  |  |  |   LevenbergMarquardtParams params; | 
					
						
							|  |  |  |   params.linearSolverType = LevenbergMarquardtParams::Iterative; | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   auto pcg = std::make_shared<PCGSolverParameters>(); | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   pcg->preconditioner_ = | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |       std::make_shared<BlockJacobiPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   params.iterativeParams = pcg; | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   NonlinearFactorGraph fg = example::createReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Point2 x0(10, 10); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  |   Values c0; | 
					
						
							|  |  |  |   c0.insert(X(1), x0); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize(); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   DOUBLES_EQUAL(0, fg.error(actualPCG), tol); | 
					
						
							| 
									
										
										
										
											2014-06-09 04:15:00 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							| 
									
										
										
										
											2014-11-07 03:26:46 +08:00
										 |  |  | // Test Incremental Subgraph PCG Solver
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  | TEST(PCGSolver, subgraph) { | 
					
						
							|  |  |  |   LevenbergMarquardtParams params; | 
					
						
							|  |  |  |   params.linearSolverType = LevenbergMarquardtParams::Iterative; | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |   auto pcg = std::make_shared<PCGSolverParameters>(); | 
					
						
							|  |  |  |   pcg->preconditioner_ = std::make_shared<SubgraphPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   params.iterativeParams = pcg; | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   NonlinearFactorGraph fg = example::createReallyNonlinearFactorGraph(); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Point2 x0(10, 10); | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  |   Values c0; | 
					
						
							|  |  |  |   c0.insert(X(1), x0); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   Values actualPCG = LevenbergMarquardtOptimizer(fg, c0, params).optimize(); | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-22 02:44:00 +08:00
										 |  |  |   DOUBLES_EQUAL(0, fg.error(actualPCG), tol); | 
					
						
							| 
									
										
										
										
											2014-06-16 11:14:06 +08:00
										 |  |  | } | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2014-06-08 12:34:23 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main() { | 
					
						
							|  |  |  |   TestResult tr; | 
					
						
							|  |  |  |   return TestRegistry::runAllTests(tr); | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | 
 |