| 
									
										
										
										
											2012-05-22 05:53:26 +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 Example of a simple 2D localization example | 
					
						
							|  |  |  | % @author Frank Dellaert | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | import gtsam.* | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | %% Assumptions | 
					
						
							|  |  |  | %  - Robot poses are facing along the X axis (horizontal, to the right in 2D) | 
					
						
							|  |  |  | %  - The robot moves 2 meters each step | 
					
						
							|  |  |  | %  - The robot is on a grid, moving 2 meters each step | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Create the graph (defined in pose2SLAM.h, derived from NonlinearFactorGraph) | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | graph = NonlinearFactorGraph; | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add a Gaussian prior on pose x_1 | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | priorMean = Pose2(0.0, 0.0, 0.0); % prior mean is at origin | 
					
						
							|  |  |  | priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); % 30cm std on x,y, 0.1 rad on theta | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | graph.add(PriorFactorPose2(1, priorMean, priorNoise)); % add directly to graph | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add two odometry factors | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | odometry = Pose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) | 
					
						
							|  |  |  | odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); % 20cm std on x,y, 0.1 rad on theta | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | graph.add(BetweenFactorPose2(1, 2, odometry, odometryNoise)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(2, 3, odometry, odometryNoise)); | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% print | 
					
						
							|  |  |  | graph.print(sprintf('\nFactor graph:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Initialize to noisy points | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +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, 0.1)); | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | initialEstimate.print(sprintf('\nInitial estimate:\n  ')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); | 
					
						
							|  |  |  | result = optimizer.optimizeSafely(); | 
					
						
							| 
									
										
										
										
											2012-05-22 05:53:26 +08:00
										 |  |  | result.print(sprintf('\nFinal result:\n  ')); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | %% Plot trajectory and covariance ellipses | 
					
						
							| 
									
										
										
										
											2012-06-12 12:38:05 +08:00
										 |  |  | cla; | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | hold on; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | plot2DTrajectory(result, [], Marginals(graph, result)); | 
					
						
							| 
									
										
										
										
											2012-07-22 08:57:54 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-12 13:29:25 +08:00
										 |  |  | axis([-0.6 4.8 -1 1]) | 
					
						
							| 
									
										
										
										
											2012-06-05 11:51:21 +08:00
										 |  |  | axis equal | 
					
						
							| 
									
										
										
										
											2012-06-27 02:52:27 +08:00
										 |  |  | view(2) |