2012-06-03 13:26:30 +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 Read graph from file and perform GraphSLAM
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Frank Dellaert
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Find data file
							 | 
						
					
						
							
								
									
										
										
										
											2013-08-28 01:22:33 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								datafile = findExampleDataFile('w100.graph');
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-04 02:20:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Initialize graph, initial estimate, and odometry noise
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								[graph,initial] = load2D(datafile, model);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 13:26:30 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add a Gaussian prior on pose x_1
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								priorMean = Pose2(0, 0, 0); % prior mean is at origin
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								priorNoise = noiseModel.Diagonal.Sigmas([0.01; 0.01; 0.01]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(PriorFactorPose2(0, priorMean, priorNoise)); % add directly to graph
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 13:26:30 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Plot Initial Estimate
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								cla
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								plot2DTrajectory(initial, 'g-*'); axis equal
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 13:26:30 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								optimizer = LevenbergMarquardtOptimizer(graph, initial);
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								tic
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = optimizer.optimizeSafely;
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								toc
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								hold on; plot2DTrajectory(result, 'b-*');
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-03 13:26:30 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Plot Covariance Ellipses
							 | 
						
					
						
							
								
									
										
										
										
											2014-05-26 05:47:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								tic
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								marginals = Marginals(graph, result);
							 | 
						
					
						
							
								
									
										
										
										
											2014-05-26 05:47:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								toc
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								P={};
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-04 02:20:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:result.size()-1
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 07:51:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    pose_i = result.atPose2(i);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-04 02:20:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    P{i}=marginals.marginalCovariance(i);
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    plotPose2(pose_i,'b',P{i})
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-04 02:20:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								view(2)
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								axis tight; axis equal;
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								% fprintf(1,'%.5f %.5f %.5f\n',P{99})
							 |