| 
									
										
										
										
											2012-06-23 03:36:49 +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 A structure from motion example | 
					
						
							|  |  |  | % @author Duy-Nguyen Ta | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | import gtsam.* | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | options.triangle = false; | 
					
						
							|  |  |  | options.nrCameras = 10; | 
					
						
							|  |  |  | options.showImages = false; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | [data,truth] = VisualISAMGenerateData(options); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | measurementNoiseSigma = 1.0; | 
					
						
							|  |  |  | pointNoiseSigma = 0.1; | 
					
						
							|  |  |  | poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]'; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | graph = NonlinearFactorGraph; | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add factors for all measurements | 
					
						
							| 
									
										
										
										
											2021-12-14 00:18:52 +08:00
										 |  |  | measurementNoise = noiseModel.Isotropic.Sigma(2,measurementNoiseSigma); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | for i=1:length(data.Z) | 
					
						
							|  |  |  |     for k=1:length(data.Z{i}) | 
					
						
							|  |  |  |         j = data.J{i}{k}; | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  |         graph.add(GenericProjectionFactorCal3_S2(data.Z{i}{k}, measurementNoise, symbol('x',i), symbol('p',j), data.K)); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  |     end | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2021-12-14 00:18:52 +08:00
										 |  |  | posePriorNoise  = noiseModel.Diagonal.Sigmas(poseNoiseSigmas); | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | graph.add(PriorFactorPose3(symbol('x',1), truth.cameras{1}.pose, posePriorNoise)); | 
					
						
							| 
									
										
										
										
											2021-12-14 00:18:52 +08:00
										 |  |  | pointPriorNoise  = noiseModel.Isotropic.Sigma(3,pointNoiseSigma); | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | graph.add(PriorFactorPoint3(symbol('p',1), truth.points{1}, pointPriorNoise)); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Initial estimate | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | initialEstimate = Values; | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | for i=1:size(truth.cameras,2) | 
					
						
							|  |  |  |     pose_i = truth.cameras{i}.pose; | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  |     initialEstimate.insert(symbol('x',i), pose_i); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | end | 
					
						
							|  |  |  | for j=1:size(truth.points,2) | 
					
						
							|  |  |  |     point_j = truth.points{j}; | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  |     initialEstimate.insert(symbol('p',j), point_j); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Optimization | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | optimizer = LevenbergMarquardtOptimizer(graph, initialEstimate); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | for i=1:5 | 
					
						
							|  |  |  |     optimizer.iterate(); | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | result = optimizer.values(); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Marginalization | 
					
						
							| 
									
										
										
										
											2012-07-24 23:48:39 +08:00
										 |  |  | marginals = Marginals(graph, result); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | marginals.marginalCovariance(symbol('p',1)); | 
					
						
							|  |  |  | marginals.marginalCovariance(symbol('x',1)); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Check optimized results, should be equal to ground truth | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | for i=1:size(truth.cameras,2) | 
					
						
							| 
									
										
										
										
											2014-11-14 06:59:51 +08:00
										 |  |  |     pose_i = result.atPose3(symbol('x',i)); | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |     CHECK('pose_i.equals(truth.cameras{i}.pose,1e-5)',pose_i.equals(truth.cameras{i}.pose,1e-5)) | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | for j=1:size(truth.points,2) | 
					
						
							| 
									
										
										
										
											2014-11-14 06:59:51 +08:00
										 |  |  |     point_j = result.atPoint3(symbol('p',j)); | 
					
						
							| 
									
										
										
										
											2020-08-18 02:37:12 +08:00
										 |  |  |     CHECK('point_j.equals(truth.points{j},1e-5)',norm(point_j - truth.points{j}) < 1e-5) | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | end |