| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | function [noiseModels,isam,result,nextPoseIndex] = VisualISAMInitialize(data,truth,options)
 | 
					
						
							| 
									
										
										
										
											2012-09-08 13:28:25 +08:00
										 |  |  | % VisualISAMInitialize initializes visualSLAM::iSAM object and noise parameters | 
					
						
							| 
									
										
										
										
											2012-06-13 10:31:32 +08:00
										 |  |  | % Authors: Duy Nguyen Ta, Frank Dellaert and Alex Cunningham | 
					
						
							| 
									
										
										
										
											2012-06-10 11:31:09 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | import gtsam.* | 
					
						
							| 
									
										
										
										
											2013-06-20 14:49:56 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Initialize iSAM | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | params = gtsam.ISAM2Params; | 
					
						
							|  |  |  | if options.alwaysRelinearize | 
					
						
							|  |  |  |     params.setRelinearizeSkip(1); | 
					
						
							|  |  |  | end | 
					
						
							| 
									
										
										
										
											2013-06-20 14:49:56 +08:00
										 |  |  | isam = ISAM2(params); | 
					
						
							| 
									
										
										
										
											2012-06-10 12:25:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Set Noise parameters | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | noiseModels.pose = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); | 
					
						
							| 
									
										
										
										
											2012-07-24 21:35:11 +08:00
										 |  |  | %noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]'); | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.05 0.05 0.05 0.2 0.2 0.2]'); | 
					
						
							| 
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 |  |  | noiseModels.point = noiseModel.Isotropic.Sigma(3, 0.1); | 
					
						
							|  |  |  | noiseModels.measurement = noiseModel.Isotropic.Sigma(2, 1.0); | 
					
						
							| 
									
										
										
										
											2012-06-10 12:25:05 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Add constraints/priors | 
					
						
							| 
									
										
										
										
											2012-06-11 06:32:24 +08:00
										 |  |  | % TODO: should not be from ground truth! | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | newFactors = NonlinearFactorGraph; | 
					
						
							|  |  |  | initialEstimates = Values; | 
					
						
							| 
									
										
										
										
											2012-06-11 06:32:24 +08:00
										 |  |  | for i=1:2 | 
					
						
							|  |  |  |     ii = symbol('x',i); | 
					
						
							| 
									
										
										
										
											2012-06-14 01:42:06 +08:00
										 |  |  |     if i==1 | 
					
						
							|  |  |  |         if options.hardConstraint % add hard constraint | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |             newFactors.add(NonlinearEqualityPose3(ii,truth.cameras{1}.pose)); | 
					
						
							| 
									
										
										
										
											2012-06-14 01:42:06 +08:00
										 |  |  |         else | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |             newFactors.add(PriorFactorPose3(ii,truth.cameras{i}.pose, noiseModels.pose)); | 
					
						
							| 
									
										
										
										
											2012-06-14 01:42:06 +08:00
										 |  |  |         end | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  |     end | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |     initialEstimates.insert(ii,truth.cameras{i}.pose); | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | nextPoseIndex = 3; | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 10:31:32 +08:00
										 |  |  | %% Add visual measurement factors from two first poses and initialize observed landmarks | 
					
						
							| 
									
										
										
										
											2012-06-11 06:32:24 +08:00
										 |  |  | for i=1:2 | 
					
						
							|  |  |  |     ii = symbol('x',i); | 
					
						
							| 
									
										
										
										
											2012-06-13 22:58:15 +08:00
										 |  |  |     for k=1:length(data.Z{i}) | 
					
						
							|  |  |  |         j = data.J{i}{k}; | 
					
						
							|  |  |  |         jj = symbol('l',data.J{i}{k}); | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |         newFactors.add(GenericProjectionFactorCal3_S2(data.Z{i}{k}, noiseModels.measurement, ii, jj, data.K)); | 
					
						
							| 
									
										
										
										
											2012-06-13 22:58:15 +08:00
										 |  |  |         % TODO: initial estimates should not be from ground truth! | 
					
						
							|  |  |  |         if ~initialEstimates.exists(jj) | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |             initialEstimates.insert(jj, truth.points{j}); | 
					
						
							| 
									
										
										
										
											2012-06-13 22:58:15 +08:00
										 |  |  |         end | 
					
						
							|  |  |  |         if options.pointPriors % add point priors | 
					
						
							| 
									
										
										
										
											2012-09-05 03:10:03 +08:00
										 |  |  |             newFactors.add(PriorFactorPoint3(jj, truth.points{j}, noiseModels.point)); | 
					
						
							| 
									
										
										
										
											2012-06-13 10:31:32 +08:00
										 |  |  |         end | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  |     end | 
					
						
							| 
									
										
										
										
											2012-06-09 04:08:53 +08:00
										 |  |  | end | 
					
						
							| 
									
										
										
										
											2012-06-10 12:25:05 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-14 01:42:06 +08:00
										 |  |  | %% Add odometry between frames 1 and 2 | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | newFactors.add(BetweenFactorPose3(symbol('x',1), symbol('x',2), data.odometry{1}, noiseModels.odometry)); | 
					
						
							| 
									
										
										
										
											2012-06-14 01:42:06 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  | %% Update ISAM | 
					
						
							| 
									
										
										
										
											2012-06-10 23:26:59 +08:00
										 |  |  | if options.batchInitialization % Do a full optimize for first two poses | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  |     batchOptimizer = LevenbergMarquardtOptimizer(newFactors, initialEstimates); | 
					
						
							|  |  |  |     fullyOptimized = batchOptimizer.optimize(); | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  |     isam.update(newFactors, fullyOptimized); | 
					
						
							|  |  |  | else | 
					
						
							|  |  |  |     isam.update(newFactors, initialEstimates); | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | % figure(1);tic; | 
					
						
							|  |  |  | % t=toc; plot(frame_i,t,'r.'); tic | 
					
						
							| 
									
										
										
										
											2012-07-28 03:02:11 +08:00
										 |  |  | result = isam.calculateEstimate(); | 
					
						
							| 
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 |  |  | % t=toc; plot(frame_i,t,'g.'); | 
					
						
							|  |  |  | 
 |