| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							| 
									
										
										
										
											2012-06-04 04:12:12 +08:00
										 |  |  | % GTSAM Copyright 2010, Georgia Tech Research Corporation, | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | % Atlanta, Georgia 30332-0415 | 
					
						
							|  |  |  | % All Rights Reserved | 
					
						
							|  |  |  | % Authors: Frank Dellaert, et al. (see THANKS for the full author list) | 
					
						
							| 
									
										
										
										
											2012-06-04 04:12:12 +08:00
										 |  |  | % | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | % See LICENSE for the license information | 
					
						
							|  |  |  | % | 
					
						
							|  |  |  | % @brief Simple robotics example using the pre-built planar SLAM domain | 
					
						
							|  |  |  | % @author Alex Cunningham | 
					
						
							|  |  |  | % @author Frank Dellaert | 
					
						
							|  |  |  | % @author Chris Beall | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | import gtsam.* | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +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-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add prior | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | graph.add(PriorFactorPose2(1, Pose2(0, 0, 0), priorNoise)); % add directly to graph | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add odometry | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | model = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(1, 2, Pose2(2, 0, 0   ), model)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(2, 3, Pose2(2, 0, pi/2), model)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(3, 4, Pose2(2, 0, pi/2), model)); | 
					
						
							|  |  |  | graph.add(BetweenFactorPose2(4, 5, Pose2(2, 0, pi/2), model)); | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-04 04:12:12 +08:00
										 |  |  | %% Add pose constraint | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | graph.add(BetweenFactorPose2(5, 2, Pose2(2, 0, pi/2), model)); | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | % print | 
					
						
							| 
									
										
										
										
											2012-06-04 04:14:23 +08:00
										 |  |  | graph.print(sprintf('\nFactor graph:\n')); | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Initialize to noisy points | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | initialEstimate = Values; | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | 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-04 04:12:12 +08:00
										 |  |  | initialEstimate.print(sprintf('\nInitial estimate:\n')); | 
					
						
							| 
									
										
										
										
											2012-01-28 10:51:35 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); | 
					
						
							|  |  |  | result = optimizer.optimizeSafely(); | 
					
						
							| 
									
										
										
										
											2012-06-04 04:12:12 +08:00
										 |  |  | result.print(sprintf('\nFinal result:\n')); | 
					
						
							| 
									
										
										
										
											2012-06-05 11:51:21 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Plot Covariance Ellipses | 
					
						
							| 
									
										
										
										
											2012-06-12 12:38:05 +08:00
										 |  |  | cla; | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | hold on | 
					
						
							| 
									
										
										
										
											2014-11-14 07:51:11 +08:00
										 |  |  | plot([result.atPose2(5).x;result.atPose2(2).x],[result.atPose2(5).y;result.atPose2(2).y],'r-'); | 
					
						
							| 
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 |  |  | marginals = Marginals(graph, result); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 |  |  | plot2DTrajectory(result, [], marginals); | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | for i=1:5,marginals.marginalCovariance(i),end | 
					
						
							| 
									
										
										
										
											2012-06-05 11:51:21 +08:00
										 |  |  | axis equal | 
					
						
							| 
									
										
										
										
											2012-08-06 02:44:36 +08:00
										 |  |  | axis tight | 
					
						
							| 
									
										
										
										
											2012-06-13 20:22:31 +08:00
										 |  |  | view(2) |