| 
									
										
										
										
											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 | 
					
						
							|  |  |  | % | 
					
						
							|  |  |  | % @brief A simple visual SLAM example for structure from motion | 
					
						
							|  |  |  | % @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. | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Generate simulated data | 
					
						
							|  |  |  | % 3D landmarks as vertices of a cube | 
					
						
							|  |  |  | points = {gtsamPoint3([10 10 10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([-10 10 10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([-10 -10 10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([10 -10 10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([10 10 -10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([-10 10 -10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([-10 -10 -10]'),... | 
					
						
							|  |  |  |     gtsamPoint3([10 -10 -10]')}; | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | % Camera poses on a circle around the cube, pointing at the world origin | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  | nCameras = 6; | 
					
						
							|  |  |  | height = 0; | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | r = 30; | 
					
						
							|  |  |  | poses = {}; | 
					
						
							|  |  |  | for i=1:nCameras | 
					
						
							| 
									
										
										
										
											2012-06-06 07:51:12 +08:00
										 |  |  |     theta = (i-1)*2*pi/nCameras; | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  |     t = gtsamPoint3([r*cos(theta), r*sin(theta), height]'); | 
					
						
							|  |  |  |     camera = gtsamSimpleCamera_lookat(t, gtsamPoint3(), gtsamPoint3([0,0,1]'), gtsamCal3_S2()) | 
					
						
							|  |  |  |     poses{i} = camera.pose(); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							| 
									
										
										
										
											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-06 17:39:55 +08:00
										 |  |  | measurementNoise = gtsamSharedNoiseModel_Sigma(2,measurementNoiseSigma); | 
					
						
							|  |  |  | K = gtsamCal3_S2(500,500,0,640/2,480/2); | 
					
						
							|  |  |  | for i=1:nCameras | 
					
						
							|  |  |  |     camera = gtsamSimpleCamera(K,poses{i}); | 
					
						
							|  |  |  |     for j=1:size(points,2) | 
					
						
							|  |  |  |         zij = camera.project(points{j}); % you can add noise here if desired | 
					
						
							|  |  |  |         graph.addMeasurement(zij, measurementNoise, symbol('x',i), symbol('l',j), 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-06 17:39:55 +08:00
										 |  |  | posePriorNoise  = gtsamSharedNoiseModel_Sigmas(poseNoiseSigmas); | 
					
						
							|  |  |  | graph.addPosePrior(symbol('x',1), poses{1}, posePriorNoise); | 
					
						
							|  |  |  | pointPriorNoise  = gtsamSharedNoiseModel_Sigma(3,pointNoiseSigma); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | graph.addPointPrior(symbol('l',1), points{1}, pointPriorNoise); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Print the graph | 
					
						
							|  |  |  | graph.print(sprintf('\nFactor graph:\n')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Initialize to noisy poses and points | 
					
						
							|  |  |  | initialEstimate = visualSLAMValues; | 
					
						
							|  |  |  | for i=1:size(poses,2) | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  |     initialEstimate.insertPose(symbol('x',i), poses{i}); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							|  |  |  | for j=1:size(points,2) | 
					
						
							| 
									
										
										
										
											2012-06-06 17:39:55 +08:00
										 |  |  |     initialEstimate.insertPoint(symbol('l',j), points{j}); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							|  |  |  | initialEstimate.print(sprintf('\nInitial estimate:\n  ')); | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | %% Optimize using Levenberg-Marquardt optimization with an ordering from colamd | 
					
						
							|  |  |  | result = graph.optimize(initialEstimate); | 
					
						
							|  |  |  | 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-06 07:51:12 +08:00
										 |  |  | figure(1);clf | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | hold on; | 
					
						
							|  |  |  | for j=1:size(points,2) | 
					
						
							|  |  |  |     P = marginals.marginalCovariance(symbol('l',j)); | 
					
						
							|  |  |  |     point_j = result.point(symbol('l',j)); | 
					
						
							|  |  |  | 	plot3(point_j.x, point_j.y, point_j.z,'marker','o'); | 
					
						
							|  |  |  |     covarianceEllipse3D([point_j.x;point_j.y;point_j.z],P); | 
					
						
							|  |  |  | end | 
					
						
							|  |  |  | 
 | 
					
						
							|  |  |  | for i=1:size(poses,2) | 
					
						
							| 
									
										
										
										
											2012-06-06 07:51:12 +08:00
										 |  |  |     P = marginals.marginalCovariance(symbol('x',i)) | 
					
						
							|  |  |  |     pose_i = result.pose(symbol('x',i)) | 
					
						
							|  |  |  |     plotPose3(pose_i,P,10); | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | end | 
					
						
							| 
									
										
										
										
											2012-06-06 07:51:12 +08:00
										 |  |  | axis equal | 
					
						
							| 
									
										
										
										
											2012-06-05 13:15:26 +08:00
										 |  |  | 
 |