2012-06-13 22:58:15 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								function [noiseModels,isam,result] = VisualISAMInitialize(data,truth,options)
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% VisualInitialize: initialize 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-06-09 04:08:53 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Initialize iSAM
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								isam = visualSLAM.ISAM(options.reorderInterval);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 12:25:05 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Set Noise parameters
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								noiseModels.pose = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								noiseModels.odometry = noiseModel.Diagonal.Sigmas([0.001 0.001 0.001 0.1 0.1 0.1]');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								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-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								newFactors = visualSLAM.Graph;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initialEstimates = visualSLAM.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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            newFactors.addPoseConstraint(ii,truth.cameras{1}.pose);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        else
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            newFactors.addPosePrior(ii,truth.cameras{i}.pose, noiseModels.pose);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        end
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    end
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-11 06:32:24 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initialEstimates.insertPose(ii,truth.cameras{i}.pose);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											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});
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        newFactors.addMeasurement(data.Z{i}{k}, noiseModels.measurement, ii, jj, data.K);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        % TODO: initial estimates should not be from ground truth!
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if ~initialEstimates.exists(jj)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            initialEstimates.insertPoint(jj, truth.points{j});
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        if options.pointPriors % add point priors
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								            newFactors.addPointPrior(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-06-24 10:48:12 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								newFactors.addRelativePose(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-06-19 23:00:41 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								    fullyOptimized = newFactors.optimize(initialEstimates,0);
							 | 
						
					
						
							
								
									
										
										
										
											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
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = isam.estimate();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% t=toc; plot(frame_i,t,'g.');
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 23:26:59 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								if options.alwaysRelinearize % re-linearize
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-10 13:00:42 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    isam.reorder_relinearize();
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 |