| 
									
										
										
										
											2012-08-25 06:03:24 +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 | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | clear | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | import gtsam.* | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Find data file | 
					
						
							| 
									
										
										
										
											2012-09-03 08:13:35 +08:00
										 |  |  | datafile = findExampleDataFile('example.graph'); | 
					
						
							| 
									
										
										
										
											2012-08-25 06:03:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Initialize graph, initial estimate, and odometry noise | 
					
						
							|  |  |  | model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 2*pi/180]); | 
					
						
							|  |  |  | [graph,initial] = load2D(datafile, model); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-25 22:26:02 +08:00
										 |  |  | %% Add a Gaussian prior on a pose in the middle | 
					
						
							|  |  |  | priorMean = initial.at(40); | 
					
						
							|  |  |  | priorNoise = noiseModel.Diagonal.Sigmas([0.1; 0.1; 2*pi/180]); | 
					
						
							|  |  |  | graph.add(PriorFactorPose2(40, priorMean, priorNoise)); % add directly to graph | 
					
						
							| 
									
										
										
										
											2012-08-25 06:03:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Plot Initial Estimate | 
					
						
							|  |  |  | cla | 
					
						
							| 
									
										
										
										
											2012-08-25 22:26:02 +08:00
										 |  |  | plot2DTrajectory(initial, 'r-'); axis equal | 
					
						
							| 
									
										
										
										
											2012-08-25 06:03:24 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd | 
					
						
							|  |  |  | optimizer = LevenbergMarquardtOptimizer(graph, initial); | 
					
						
							|  |  |  | tic | 
					
						
							|  |  |  | result = optimizer.optimizeSafely; | 
					
						
							|  |  |  | toc | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Plot Covariance Ellipses | 
					
						
							| 
									
										
										
										
											2012-08-25 22:26:02 +08:00
										 |  |  | cla;hold on | 
					
						
							| 
									
										
										
										
											2012-08-25 06:03:24 +08:00
										 |  |  | marginals = Marginals(graph, result); | 
					
						
							| 
									
										
										
										
											2012-08-25 22:26:02 +08:00
										 |  |  | plot2DTrajectory(result, 'g', marginals); | 
					
						
							|  |  |  | plot2DPoints(result, 'b', marginals); | 
					
						
							|  |  |  | axis tight | 
					
						
							|  |  |  | axis equal | 
					
						
							| 
									
										
										
										
											2012-08-25 06:03:24 +08:00
										 |  |  | view(2) | 
					
						
							| 
									
										
										
										
											2012-08-25 22:26:02 +08:00
										 |  |  | 
 |