2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% GTSAM Copyright 2010, Georgia Tech Research Corporation,
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% Atlanta, Georgia 30332-0415
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% All Rights Reserved
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% Authors: Frank Dellaert, et al. (see THANKS for the full author list)
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Assumptions
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - All values are axis aligned
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Robot poses are facing along the X axis (horizontal, to the right in images)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - We have bearing and range information for measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - We have full odometry for measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - The robot and landmarks are on a grid, moving 2 meters each step
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Landmarks are 2 meters away from the robot trajectory
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create keys for variables
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								i1 = symbol('x',1); i2 = symbol('x',2); i3 = symbol('x',3);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								j1 = symbol('l',1); j2 = symbol('l',2);
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create graph container and add factors to it
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								graph = NonlinearFactorGraph;
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add prior
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								graph.add(PriorFactorPose2(i1, priorMean, priorNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add odometry
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								odometry = Pose2(2.0, 0.0, 0.0);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BetweenFactorPose2(i1, i2, odometry, odometryNoise));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BetweenFactorPose2(i2, i3, odometry, odometryNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add bearing/range measurement factors
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								degrees = pi/180;
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								brNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								graph.add(BearingRangeFactor2D(i1, j1, Rot2(45*degrees), sqrt(8), brNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BearingRangeFactor2D(i2, j1, Rot2(90*degrees), 2, brNoise));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BearingRangeFactor2D(i3, j2, Rot2(90*degrees), 2, brNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% print
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.print(sprintf('\nFull graph:\n'));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Initialize to noisy points
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate = Values;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(i1, Pose2(0.5, 0.0, 0.2));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(i2, Pose2(2.3, 0.1,-0.2));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(i3, Pose2(4.1, 0.1, 0.1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(j1, Point2(1.8, 2.1));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.insert(j2, Point2(4.1, 1.8));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.print(sprintf('\nInitial estimate:\n'));
							 | 
						
					
						
							
								
									
										
										
										
											2011-10-22 00:56:50 +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-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result.print(sprintf('\nFinal result:\n'));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Plot Covariance Ellipses
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-12 12:38:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								cla;hold on
							 | 
						
					
						
							
								
									
										
										
										
											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 21:12:03 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								plot2DPoints(result, 'b', marginals);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 07:51:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								plot([result.atPose2(i1).x; result.atPoint2(j1).x],[result.atPose2(i1).y; result.atPoint2(j1).y], 'c-');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								plot([result.atPose2(i2).x; result.atPoint2(j1).x],[result.atPose2(i2).y; result.atPoint2(j1).y], 'c-');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								plot([result.atPose2(i3).x; result.atPoint2(j2).x],[result.atPose2(i3).y; result.atPoint2(j2).y], 'c-');
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-13 20:22:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								axis([-0.6 4.8 -1 1])
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								axis equal
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-13 20:22:31 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								view(2)
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-05 21:29:26 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 |