| 
									
										
										
										
											2012-06-05 04:14:41 +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 | 
					
						
							|  |  |  | % | 
					
						
							|  |  |  | % @brief Simple 2D robotics example using the SimpleSPCGSolver | 
					
						
							|  |  |  | % @author Yong-Dian Jian | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | import gtsam.* | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | %% Assumptions | 
					
						
							|  |  |  | %  - All values are axis aligned | 
					
						
							|  |  |  | %  - Robot poses are facing along the X axis (horizontal, to the right in images) | 
					
						
							|  |  |  | %  - We have full odometry for measurements | 
					
						
							|  |  |  | %  - The robot is on a grid, moving 2 meters each step | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Create graph container and add factors to it | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | graph = NonlinearFactorGraph; | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add prior | 
					
						
							|  |  |  | % gaussian for prior | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin | 
					
						
							|  |  |  | priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | graph.add(PriorFactorPose2(1, priorMean, priorNoise)); % add directly to graph | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add odometry | 
					
						
							|  |  |  | % general noisemodel for odometry | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | graph.add(BetweenFactorPose2(1, 2, Pose2(2.0, 0.0, 0.0 ), odometryNoise)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(2, 3, Pose2(2.0, 0.0, pi/2), odometryNoise)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(3, 4, Pose2(2.0, 0.0, pi/2), odometryNoise)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(4, 5, Pose2(2.0, 0.0, pi/2), odometryNoise)); | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add pose constraint | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | graph.add(BetweenFactorPose2(5, 2, Pose2(2.0, 0.0, pi/2), model)); | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | % print | 
					
						
							|  |  |  | graph.print(sprintf('\nFactor graph:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Initialize to noisy points | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | initialEstimate = Values; | 
					
						
							|  |  |  | initialEstimate.insert(1, Pose2(0.5, 0.0, 0.2 )); | 
					
						
							|  |  |  | initialEstimate.insert(2, Pose2(2.3, 0.1,-0.2 )); | 
					
						
							|  |  |  | initialEstimate.insert(3, Pose2(4.1, 0.1, pi/2)); | 
					
						
							|  |  |  | initialEstimate.insert(4, Pose2(4.0, 2.0, pi  )); | 
					
						
							|  |  |  | initialEstimate.insert(5, Pose2(2.1, 2.1,-pi/2)); | 
					
						
							| 
									
										
										
										
											2012-06-05 04:14:41 +08:00
										 |  |  | initialEstimate.print(sprintf('\nInitial estimate:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-09-04 05:50:22 +08:00
										 |  |  | %% Optimize using Levenberg-Marquardt optimization with SubgraphSolver | 
					
						
							|  |  |  | params = gtsam.LevenbergMarquardtParams; | 
					
						
							|  |  |  | subgraphParams = gtsam.SubgraphSolverParameters; | 
					
						
							| 
									
										
										
										
											2020-08-18 02:37:12 +08:00
										 |  |  | params.setLinearSolverType('ITERATIVE'); | 
					
						
							| 
									
										
										
										
											2012-09-04 05:50:22 +08:00
										 |  |  | params.setIterativeParams(subgraphParams); | 
					
						
							|  |  |  | optimizer = gtsam.LevenbergMarquardtOptimizer(graph, initialEstimate); | 
					
						
							|  |  |  | result = optimizer.optimize(); | 
					
						
							|  |  |  | result.print(sprintf('\nFinal result:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | 
 |