| 
									
										
										
										
											2010-10-22 05:38:38 +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 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  |  * -------------------------------------------------------------------------- */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-04 04:24:58 +08:00
										 |  |  | /**
 | 
					
						
							|  |  |  |  * @file Pose2SLAMwSPCG.cpp | 
					
						
							|  |  |  |  * @brief A 2D Pose SLAM example using the SimpleSPCGSolver. | 
					
						
							|  |  |  |  * @author Yong-Dian Jian | 
					
						
							|  |  |  |  * @date June 2, 2012 | 
					
						
							|  |  |  |  */ | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | // For an explanation of headers below, please see Pose2SLAMExample.cpp
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  | #include <gtsam/slam/BetweenFactor.h>
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | #include <gtsam/geometry/Pose2.h>
 | 
					
						
							|  |  |  | #include <gtsam/nonlinear/LevenbergMarquardtOptimizer.h>
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | // In contrast to that example, however, we will use a PCG solver here
 | 
					
						
							| 
									
										
										
										
											2012-06-09 10:42:45 +08:00
										 |  |  | #include <gtsam/linear/SubgraphSolver.h>
 | 
					
						
							| 
									
										
										
										
											2010-10-26 06:26:18 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2010-10-22 05:38:38 +08:00
										 |  |  | using namespace std; | 
					
						
							|  |  |  | using namespace gtsam; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  | int main(int argc, char** argv) { | 
					
						
							|  |  |  |   // 1. Create a factor graph container and add factors to it
 | 
					
						
							|  |  |  |   NonlinearFactorGraph graph; | 
					
						
							| 
									
										
										
										
											2012-06-03 22:52:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  |   // 2a. Add a prior on the first pose, setting it to the origin
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   Pose2 prior(0.0, 0.0, 0.0);  // prior at origin
 | 
					
						
							|  |  |  |   auto priorNoise = noiseModel::Diagonal::Sigmas(Vector3(0.3, 0.3, 0.1)); | 
					
						
							| 
									
										
										
										
											2020-04-13 01:10:09 +08:00
										 |  |  |   graph.addPrior(1, prior, priorNoise); | 
					
						
							| 
									
										
										
										
											2012-06-03 22:52:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2b. Add odometry factors
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto odometryNoise = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); | 
					
						
							| 
									
										
										
										
											2016-09-09 20:33:51 +08:00
										 |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(1, 2, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(2, 3, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(3, 4, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(4, 5, Pose2(2.0, 0.0, M_PI_2), odometryNoise); | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 2c. Add the loop closure constraint
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   auto model = noiseModel::Diagonal::Sigmas(Vector3(0.2, 0.2, 0.1)); | 
					
						
							|  |  |  |   graph.emplace_shared<BetweenFactor<Pose2> >(5, 1, Pose2(0.0, 0.0, 0.0), | 
					
						
							|  |  |  |                                               model); | 
					
						
							|  |  |  |   graph.print("\nFactor Graph:\n");  // print
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // 3. Create the data structure to hold the initialEstimate estimate to the
 | 
					
						
							|  |  |  |   // solution
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  |   Values initialEstimate; | 
					
						
							|  |  |  |   initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2)); | 
					
						
							|  |  |  |   initialEstimate.insert(2, Pose2(2.3, 0.1, 1.1)); | 
					
						
							|  |  |  |   initialEstimate.insert(3, Pose2(2.1, 1.9, 2.8)); | 
					
						
							|  |  |  |   initialEstimate.insert(4, Pose2(-.3, 2.5, 4.2)); | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   initialEstimate.insert(5, Pose2(0.1, -0.7, 5.8)); | 
					
						
							|  |  |  |   initialEstimate.print("\nInitial Estimate:\n");  // print
 | 
					
						
							| 
									
										
										
										
											2012-06-03 22:52:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  |   // 4. Single Step Optimization using Levenberg-Marquardt
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  |   LevenbergMarquardtParams parameters; | 
					
						
							|  |  |  |   parameters.verbosity = NonlinearOptimizerParams::ERROR; | 
					
						
							|  |  |  |   parameters.verbosityLM = LevenbergMarquardtParams::LAMBDA; | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2020-05-10 07:08:31 +08:00
										 |  |  |   // LM is still 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)
 | 
					
						
							| 
									
										
										
										
											2014-06-04 11:52:35 +08:00
										 |  |  |   parameters.linearSolverType = NonlinearOptimizerParams::Iterative; | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   parameters.iterativeParams = boost::make_shared<SubgraphSolverParameters>(); | 
					
						
							| 
									
										
										
										
											2012-06-09 10:42:45 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2015-02-22 13:14:19 +08:00
										 |  |  |   LevenbergMarquardtOptimizer optimizer(graph, initialEstimate, parameters); | 
					
						
							|  |  |  |   Values result = optimizer.optimize(); | 
					
						
							|  |  |  |   result.print("Final Result:\n"); | 
					
						
							|  |  |  |   cout << "subgraph solver final error = " << graph.error(result) << endl; | 
					
						
							| 
									
										
										
										
											2010-10-26 06:21:53 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 13:34:22 +08:00
										 |  |  |   return 0; | 
					
						
							| 
									
										
										
										
											2012-01-28 00:43:31 +08:00
										 |  |  | } |