| 
									
										
										
										
											2015-02-22 13:14:19 +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    SFMExample_SmartFactorPCG.cpp | 
					
						
							|  |  |  |  * @brief   Version of SFMExample_SmartFactor that uses Preconditioned Conjugate Gradient | 
					
						
							|  |  |  |  * @author  Frank Dellaert | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // For an explanation of these headers, see SFMExample_SmartFactor.cpp
 | 
					
						
							|  |  |  | #include "SFMdata.h"
 | 
					
						
							|  |  |  | #include <gtsam/slam/SmartProjectionPoseFactor.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // These extra headers allow us a LM outer loop with PCG linear solver (inner loop)
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/Preconditioner.h>
 | 
					
						
							|  |  |  | #include <gtsam/linear/PCGSolver.h>
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | // Make the typename short so it looks much cleaner
 | 
					
						
							|  |  |  | typedef SmartProjectionPoseFactor<Cal3_S2> SmartFactor; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-26 20:55:16 +08:00
										 |  |  | // create a typedef to the camera type
 | 
					
						
							|  |  |  | typedef PinholePose<Cal3_S2> Camera; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | int main(int argc, char* argv[]) { | 
					
						
							|  |  |  |   // Define the camera calibration parameters
 | 
					
						
							|  |  |  |   Cal3_S2::shared_ptr K(new Cal3_S2(50.0, 50.0, 0.0, 50.0, 50.0)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Define the camera observation noise model
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto measurementNoise = | 
					
						
							|  |  |  |       noiseModel::Isotropic::Sigma(2, 1.0);  // one pixel in u and v
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Create the set of ground-truth landmarks and poses
 | 
					
						
							|  |  |  |   vector<Point3> points = createPoints(); | 
					
						
							|  |  |  |   vector<Pose3> poses = createPoses(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Create a factor graph
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Simulated measurements from each camera pose, adding them to the factor graph
 | 
					
						
							|  |  |  |   for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |     // every landmark represent a single landmark, we use shared pointer to init
 | 
					
						
							|  |  |  |     // the factor, and then insert measurements.
 | 
					
						
							| 
									
										
										
										
											2015-08-27 01:25:12 +08:00
										 |  |  |     SmartFactor::shared_ptr smartfactor(new SmartFactor(measurementNoise, K)); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |     for (size_t i = 0; i < poses.size(); ++i) { | 
					
						
							|  |  |  |       // generate the 2D measurement
 | 
					
						
							| 
									
										
										
										
											2015-02-26 20:55:16 +08:00
										 |  |  |       Camera camera(poses[i], K); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |       Point2 measurement = camera.project(points[j]); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |       // call add() function to add measurement into a single factor
 | 
					
						
							| 
									
										
										
										
											2015-08-27 01:25:12 +08:00
										 |  |  |       smartfactor->add(measurement, i); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |     } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |     // insert the smart factor in the graph
 | 
					
						
							|  |  |  |     graph.push_back(smartfactor); | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Add a prior on pose x0. This indirectly specifies where the origin is.
 | 
					
						
							|  |  |  |   // 30cm std on x,y,z 0.1 rad on roll,pitch,yaw
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto noise = noiseModel::Diagonal::Sigmas( | 
					
						
							| 
									
										
										
										
											2020-01-05 08:57:22 +08:00
										 |  |  |       (Vector(6) << Vector3::Constant(0.1), Vector3::Constant(0.3)).finished()); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(0, poses[0], noise); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // Fix the scale ambiguity by adding a prior
 | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(1, poses[0], noise); | 
					
						
							| 
									
										
										
										
											2016-06-06 23:11:57 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   // Create the initial estimate to the solution
 | 
					
						
							|  |  |  |   Values initialEstimate; | 
					
						
							| 
									
										
										
										
											2015-07-06 07:11:04 +08:00
										 |  |  |   Pose3 delta(Rot3::Rodrigues(-0.1, 0.2, 0.25), Point3(0.05, -0.10, 0.20)); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   for (size_t i = 0; i < poses.size(); ++i) | 
					
						
							| 
									
										
										
										
											2016-06-06 23:09:49 +08:00
										 |  |  |     initialEstimate.insert(i, poses[i].compose(delta)); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // We will use LM in the outer optimization loop, but by specifying
 | 
					
						
							|  |  |  |   // "Iterative" below We indicate that an iterative linear solver should be
 | 
					
						
							|  |  |  |   // used. In addition, the *type* of the iterativeParams decides on the type of
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   // iterative solver, in this case the SPCG (subgraph PCG)
 | 
					
						
							|  |  |  |   LevenbergMarquardtParams parameters; | 
					
						
							|  |  |  |   parameters.linearSolverType = NonlinearOptimizerParams::Iterative; | 
					
						
							|  |  |  |   parameters.absoluteErrorTol = 1e-10; | 
					
						
							|  |  |  |   parameters.relativeErrorTol = 1e-10; | 
					
						
							|  |  |  |   parameters.maxIterations = 500; | 
					
						
							|  |  |  |   PCGSolverParameters::shared_ptr pcg = | 
					
						
							| 
									
										
										
										
											2023-01-18 06:05:12 +08:00
										 |  |  |       std::make_shared<PCGSolverParameters>(); | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:56 +08:00
										 |  |  |   pcg->preconditioner = std::make_shared<BlockJacobiPreconditionerParameters>(); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   // Following is crucial:
 | 
					
						
							| 
									
										
										
										
											2024-10-16 11:43:56 +08:00
										 |  |  |   pcg->epsilon_abs = 1e-10; | 
					
						
							|  |  |  |   pcg->epsilon_rel = 1e-10; | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   parameters.iterativeParams = pcg; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   // Display result as in SFMExample_SmartFactor.run
 | 
					
						
							|  |  |  |   result.print("Final results:\n"); | 
					
						
							|  |  |  |   Values landmark_result; | 
					
						
							|  |  |  |   for (size_t j = 0; j < points.size(); ++j) { | 
					
						
							| 
									
										
										
										
											2023-01-18 06:39:55 +08:00
										 |  |  |     auto smart = std::dynamic_pointer_cast<SmartFactor>(graph[j]); | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |     if (smart) { | 
					
						
							| 
									
										
										
										
											2023-01-13 05:11:55 +08:00
										 |  |  |       std::optional<Point3> point = smart->point(result); | 
					
						
							|  |  |  |       if (point)  // ignore if std::optional return nullptr
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |         landmark_result.insert(j, *point); | 
					
						
							|  |  |  |     } | 
					
						
							|  |  |  |   } | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   landmark_result.print("Landmark results:\n"); | 
					
						
							|  |  |  |   cout << "final error: " << graph.error(result) << endl; | 
					
						
							|  |  |  |   cout << "number of iterations: " << optimizer.iterations() << endl; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |   return 0; | 
					
						
							|  |  |  | } | 
					
						
							|  |  |  | /* ************************************************************************* */ | 
					
						
							|  |  |  | 
 |