| 
									
										
										
										
											2012-06-05 13:15:26 +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 | 
					
						
							|  |  |  | % | 
					
						
							| 
									
										
										
										
											2012-06-13 20:14:50 +08:00
										 |  |  | % @brief A structure from motion example | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | % @author Duy-Nguyen Ta | 
					
						
							|  |  |  | %%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%% | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% 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. | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | % Data Options | 
					
						
							|  |  |  | options.triangle = false; | 
					
						
							|  |  |  | options.nrCameras = 10; | 
					
						
							|  |  |  | options.showImages = false; | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | %% Generate data | 
					
						
							|  |  |  | [data,truth] = VisualISAMGenerateData(options); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  | measurementNoiseSigma = 1.0; | 
					
						
							|  |  |  | pointNoiseSigma = 0.1; | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | poseNoiseSigmas = [0.001 0.001 0.001 0.1 0.1 0.1]'; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Create the graph (defined in visualSLAM.h, derived from NonlinearFactorGraph) | 
					
						
							|  |  |  | graph = visualSLAMGraph; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Add factors for all measurements | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | measurementNoise = gtsamnoiseModelIsotropic_Sigma(2,measurementNoiseSigma); | 
					
						
							| 
									
										
										
										
											2012-06-13 22:58:15 +08:00
										 |  |  | for i=1:length(data.Z) | 
					
						
							|  |  |  |     for k=1:length(data.Z{i}) | 
					
						
							|  |  |  |         j = data.J{i}{k}; | 
					
						
							| 
									
										
										
										
											2012-06-14 13:05:41 +08:00
										 |  |  |         graph.addMeasurement(data.Z{i}{k}, measurementNoise, symbol('x',i), symbol('p',j), data.K); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  |     end | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-06 07:51:12 +08:00
										 |  |  | %% Add Gaussian priors for a pose and a landmark to constrain the system | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | posePriorNoise  = gtsamnoiseModelDiagonal_Sigmas(poseNoiseSigmas); | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | graph.addPosePrior(symbol('x',1), truth.cameras{1}.pose, posePriorNoise); | 
					
						
							| 
									
										
										
										
											2012-06-23 03:36:49 +08:00
										 |  |  | pointPriorNoise  = gtsamnoiseModelIsotropic_Sigma(3,pointNoiseSigma); | 
					
						
							| 
									
										
										
										
											2012-06-14 13:05:41 +08:00
										 |  |  | graph.addPointPrior(symbol('p',1), truth.points{1}, pointPriorNoise); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | 
 | 
					
						
							|  |  |  | %% Print the graph | 
					
						
							|  |  |  | graph.print(sprintf('\nFactor graph:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-19 23:00:41 +08:00
										 |  |  | %% Initialize cameras and points close to ground truth in this example | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | initialEstimate = visualSLAMValues; | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | for i=1:size(truth.cameras,2) | 
					
						
							| 
									
										
										
										
											2012-06-19 23:00:41 +08:00
										 |  |  |     pose_i = truth.cameras{i}.pose.retract(0.1*randn(6,1)); | 
					
						
							|  |  |  |     initialEstimate.insertPose(symbol('x',i), pose_i); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | for j=1:size(truth.points,2) | 
					
						
							| 
									
										
										
										
											2012-06-19 23:00:41 +08:00
										 |  |  |     point_j = truth.points{j}.retract(0.1*randn(3,1)); | 
					
						
							|  |  |  |     initialEstimate.insertPoint(symbol('p',j), point_j); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							|  |  |  | initialEstimate.print(sprintf('\nInitial estimate:\n  ')); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-21 22:28:08 +08:00
										 |  |  | %% Fine grain optimization, allowing user to iterate step by step | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-24 04:07:03 +08:00
										 |  |  | parameters = gtsamLevenbergMarquardtParams(1e-5, 1e-5, 0, 0); | 
					
						
							|  |  |  | parameters.setlambdaInitial(1.0); | 
					
						
							|  |  |  | parameters.setVerbosityLM('trylambda'); | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-21 22:28:08 +08:00
										 |  |  | optimizer = graph.optimizer(initialEstimate, parameters); | 
					
						
							| 
									
										
										
										
											2012-06-24 04:07:03 +08:00
										 |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-21 22:28:08 +08:00
										 |  |  | for i=1:5 | 
					
						
							|  |  |  |     optimizer.iterate(); | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | result = optimizer.values(); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | result.print(sprintf('\nFinal result:\n  ')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Plot results with covariance ellipses | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  | marginals = graph.marginals(result); | 
					
						
							| 
									
										
										
										
											2012-06-12 12:46:51 +08:00
										 |  |  | cla | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | hold on; | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | for j=1:result.nrPoints | 
					
						
							| 
									
										
										
										
											2012-06-14 13:05:41 +08:00
										 |  |  |     P = marginals.marginalCovariance(symbol('p',j)); | 
					
						
							|  |  |  |     point_j = result.point(symbol('p',j)); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | 	plot3(point_j.x, point_j.y, point_j.z,'marker','o'); | 
					
						
							|  |  |  |     covarianceEllipse3D([point_j.x;point_j.y;point_j.z],P); | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											2012-06-13 20:07:02 +08:00
										 |  |  | for i=1:result.nrPoses | 
					
						
							|  |  |  |     P = marginals.marginalCovariance(symbol('x',i)); | 
					
						
							|  |  |  |     pose_i = result.pose(symbol('x',i)); | 
					
						
							| 
									
										
										
										
											2012-06-06 07:51:12 +08:00
										 |  |  |     plotPose3(pose_i,P,10); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							| 
									
										
										
										
											2012-06-13 20:22:31 +08:00
										 |  |  | axis([-40 40 -40 40 -10 20]);axis equal | 
					
						
							|  |  |  | view(3) | 
					
						
							|  |  |  | colormap('hot') |