| 
									
										
										
										
											2011-10-22 00:56:50 +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 Simple robotics example using the pre-built planar SLAM domain | 
					
						
							|  |  |  | % @author Alex Cunningham | 
					
						
							|  |  |  | % @author Frank Dellaert | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% 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 | 
					
						
							|  |  |  | x1 = 1; x2 = 2; x3 = 3; | 
					
						
							|  |  |  | l1 = 1; l2 = 2; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Create graph container and add factors to it | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  | graph = planarSLAMGraph; | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add prior | 
					
						
							|  |  |  | % gaussian for prior | 
					
						
							| 
									
										
										
										
											2012-02-13 01:41:57 +08:00
										 |  |  | prior_model = gtsamSharedNoiseModel_Sigmas([0.3; 0.3; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | prior_measurement = gtsamPose2(0.0, 0.0, 0.0); % prior at origin | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | graph.addPrior(x1, prior_measurement, prior_model); % add directly to graph | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Add odometry | 
					
						
							|  |  |  | % general noisemodel for odometry | 
					
						
							| 
									
										
										
										
											2012-02-13 01:41:57 +08:00
										 |  |  | odom_model = gtsamSharedNoiseModel_Sigmas([0.2; 0.2; 0.1]); | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | odom_measurement = gtsamPose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case) | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | graph.addOdometry(x1, x2, odom_measurement, odom_model); | 
					
						
							|  |  |  | graph.addOdometry(x2, x3, odom_measurement, odom_model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Add measurements | 
					
						
							|  |  |  | % general noisemodel for measurements | 
					
						
							| 
									
										
										
										
											2012-02-13 01:41:57 +08:00
										 |  |  | meas_model = gtsamSharedNoiseModel_Sigmas([0.1; 0.2]); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | % create the measurement values - indices are (pose id, landmark id) | 
					
						
							|  |  |  | degrees = pi/180; | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | bearing11 = gtsamRot2(45*degrees); | 
					
						
							|  |  |  | bearing21 = gtsamRot2(90*degrees); | 
					
						
							|  |  |  | bearing32 = gtsamRot2(90*degrees); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | range11 = sqrt(4+4); | 
					
						
							|  |  |  | range21 = 2.0; | 
					
						
							|  |  |  | range32 = 2.0; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | % % create bearing/range factors and add them | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | graph.addBearingRange(x1, l1, bearing11, range11, meas_model); | 
					
						
							|  |  |  | graph.addBearingRange(x2, l1, bearing21, range21, meas_model); | 
					
						
							|  |  |  | graph.addBearingRange(x3, l2, bearing32, range32, meas_model); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | % print | 
					
						
							|  |  |  | graph.print('full graph'); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Initialize to noisy points | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  | initialEstimate = planarSLAMValues; | 
					
						
							| 
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 |  |  | initialEstimate.insertPose(x1, gtsamPose2(0.5, 0.0, 0.2)); | 
					
						
							|  |  |  | initialEstimate.insertPose(x2, gtsamPose2(2.3, 0.1,-0.2)); | 
					
						
							|  |  |  | initialEstimate.insertPose(x3, gtsamPose2(4.1, 0.1, 0.1)); | 
					
						
							|  |  |  | initialEstimate.insertPoint(l1, gtsamPoint2(1.8, 2.1)); | 
					
						
							|  |  |  | initialEstimate.insertPoint(l2, gtsamPoint2(4.1, 1.8)); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | initialEstimate.print('initial estimate'); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd | 
					
						
							| 
									
										
										
										
											2012-01-05 00:18:38 +08:00
										 |  |  | result = graph.optimize(initialEstimate); | 
					
						
							| 
									
										
										
										
											2011-10-22 00:56:50 +08:00
										 |  |  | result.print('final result'); |