2012-01-31 06:00: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 Simple robotics example using the pre-built planar SLAM domain
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Alex Cunningham
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Frank Dellaert
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Chris Beall
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Vadim Indelman
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Can Erdogan
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +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-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add prior
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% gaussian for prior
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								priorNoise = noiseModel.Diagonal.Sigmas([0.3; 0.3; 0.1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								priorMean = Pose2(0.0, 0.0, 0.0); % prior at origin
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(PriorFactorPose2(1, priorMean, priorNoise)); % add directly to graph
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add odometry
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% general noisemodel for odometry
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								odometryNoise = noiseModel.Diagonal.Sigmas([0.2; 0.2; 0.1]);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								odometry = Pose2(2.0, 0.0, 0.0); % create a measurement for both factors (the same in this case)
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BetweenFactorPose2(1, 2, odometry, odometryNoise));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(BetweenFactorPose2(2, 3, odometry, odometryNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add measurements
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% general noisemodel for measurements
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								measurementNoise = noiseModel.Diagonal.Sigmas([0.1; 0.2]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% print
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.print('full graph');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Initialize to noisy points
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +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-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.print('initial estimate');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% set up solver, choose ordering and optimize
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								params = DoglegParams;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								params.setAbsoluteErrorTol(1e-15);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								params.setRelativeErrorTol(1e-15);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								params.setVerbosity('ERROR');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								params.setVerbosityDL('VERBOSE');
							 | 
						
					
						
							
								
									
										
										
										
											2014-05-26 05:46:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								params.setOrdering(graph.orderingCOLAMD());
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								optimizer = DoglegOptimizer(graph, initialEstimate, params);                      
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 11:33:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = optimizer.optimizeSafely();
							 | 
						
					
						
							
								
									
										
										
										
											2012-02-06 11:33:40 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result.print('final result');
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Get the corresponding dense matrix
							 | 
						
					
						
							
								
									
										
										
										
											2014-05-26 05:46:47 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								ord = graph.orderingCOLAMD();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								gfg = graph.linearize(result);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								denseAb = gfg.augmentedJacobian;
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Get sparse matrix A and RHS b
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								IJS = gfg.sparseJacobian_();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								Ab=sparse(IJS(1,:),IJS(2,:),IJS(3,:));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								A = Ab(:,1:end-1);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								b = full(Ab(:,end));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								clf
							 | 
						
					
						
							
								
									
										
										
										
											2012-01-31 06:00:13 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								spy(A);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 03:21:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								title('Non-zero entries in measurement Jacobian');
							 |