| 
									
										
										
										
											2012-06-04 08:41:13 +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 | 
					
						
							| 
									
										
										
										
											2012-06-04 13:53:51 +08:00
										 |  |  | N = 2500; | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | % dataset = 'sphere_smallnoise.graph'; | 
					
						
							|  |  |  | % dataset = 'sphere2500_groundtruth.txt'; | 
					
						
							|  |  |  | dataset = 'sphere2500.txt'; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | datafile = findExampleDataFile(dataset); | 
					
						
							| 
									
										
										
										
											2012-06-04 13:53:51 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-04 08:41:13 +08:00
										 |  |  | %% Initialize graph, initial estimate, and odometry noise | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 0.05; 5*pi/180; 5*pi/180; 5*pi/180]); | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | [graph,initial]=load3D(datafile,model,true,N); | 
					
						
							| 
									
										
										
										
											2012-06-04 08:41:13 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Plot Initial Estimate | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | cla | 
					
						
							|  |  |  | first = initial.at(0); | 
					
						
							| 
									
										
										
										
											2012-06-04 13:53:51 +08:00
										 |  |  | plot3(first.x(),first.y(),first.z(),'r*'); hold on | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | plot3DTrajectory(initial,'g-',false); | 
					
						
							| 
									
										
										
										
											2012-07-24 06:15:05 +08:00
										 |  |  | drawnow; | 
					
						
							| 
									
										
										
										
											2012-06-04 08:41:13 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-05 12:01:37 +08:00
										 |  |  | %% Read again, now with all constraints, and optimize | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | graph = load3D(datafile, model, false, N); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | graph.add(NonlinearEqualityPose3(0, first)); | 
					
						
							| 
									
										
										
										
											2012-07-24 06:15:05 +08:00
										 |  |  | optimizer = LevenbergMarquardtOptimizer(graph, initial); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | result = optimizer.optimizeSafely(); | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | plot3DTrajectory(result, 'r-', false); axis equal; | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-24 06:15:05 +08:00
										 |  |  | view(3); axis equal; |