2012-07-07 01:38:32 +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 An SFM example (adapted from SFMExample.m) optimizing calibration
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Yong-Dian Jian
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Assumptions
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Landmarks as 8 vertices of a cube: (10,10,10) (-10,10,10) etc...
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Cameras are on a circle around the cube, pointing at the world origin
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Each camera sees all landmarks. 
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%  - Visual measurements as 2D points are given, corrupted by Gaussian noise.
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% Data Options
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								options.triangle = false;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								options.nrCameras = 10;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								options.showImages = false;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Generate data
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								[data,truth] = VisualISAMGenerateData(options);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								measurementNoiseSigma = 1.0;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								pointNoiseSigma = 0.1;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								cameraNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1 ...
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								                     0.001*ones(1,5)]';
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Create the graph (defined in visualSLAM.h, derived from NonlinearFactorGraph)
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph = NonlinearFactorGraph;
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								 
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add factors for all measurements
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								measurementNoise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:length(data.Z)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    for k=1:length(data.Z{i})
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        j = data.J{i}{k};
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        graph.add(GeneralSFMFactorCal3_S2(data.Z{i}{k}, measurementNoise, symbol('c',i), symbol('p',j)));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Add Gaussian priors for a pose and a landmark to constrain the system
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								cameraPriorNoise  = noiseModel.Diagonal.Sigmas(cameraNoiseSigmas);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								firstCamera = SimpleCamera(truth.cameras{1}.pose, truth.K);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(PriorFactorSimpleCamera(symbol('c',1), firstCamera, cameraPriorNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								pointPriorNoise  = noiseModel.Isotropic.Sigma(3,pointNoiseSigma);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(PriorFactorPoint3(symbol('p',1), truth.points{1}, pointPriorNoise));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Print the graph
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.print(sprintf('\nFactor graph:\n'));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Initialize cameras and points close to ground truth in this example
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate = Values;
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:size(truth.cameras,2)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    pose_i = truth.cameras{i}.pose.retract(0.1*randn(6,1));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    camera_i = SimpleCamera(pose_i, truth.K);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initialEstimate.insert(symbol('c',i), camera_i);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for j=1:size(truth.points,2)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    point_j = truth.points{j}.retract(0.1*randn(3,1));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initialEstimate.insert(symbol('p',j), point_j);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimate.print(sprintf('\nInitial estimate:\n  '));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Fine grain optimization, allowing user to iterate step by step
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								parameters = LevenbergMarquardtParams;
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								parameters.setlambdaInitial(1.0);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								parameters.setVerbosityLM('trylambda');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 05:27:44 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate, parameters);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-07 01:38:32 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:5
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    optimizer.iterate();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = optimizer.values();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result.print(sprintf('\nFinal result:\n  '));
							 |