2012-06-06 01:54:29 +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 Read Stereo Visual Odometry from file and optimize
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% @author Chris Beall
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								import gtsam.*
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% Load calibration
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% format: fx fy skew cx cy baseline
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								calib = dlmread(findExampleDataFile('VO_calibration.txt'));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								K = Cal3_S2Stereo(calib(1), calib(2), calib(3), calib(4), calib(5), calib(6));
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								stereo_model = noiseModel.Diagonal.Sigmas([1.0; 1.0; 1.0]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% create empty graph and values
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph = NonlinearFactorGraph;
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								initial = Values;
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% load the initial poses from VO
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% row format: camera_id 4x4 pose (row, major)
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								fprintf(1,'Reading data\n');
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								cameras = dlmread(findExampleDataFile('VO_camera_poses_large.txt'));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:size(cameras,1)
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-18 23:47:06 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    pose = Pose3(reshape(cameras(i,2:17),4,4)');
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    initial.insert(symbol('x',cameras(i,1)),pose);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% load stereo measurements and initialize landmarks
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								% camera_id landmark_id uL uR v X Y Z
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								measurements = dlmread(findExampleDataFile('VO_stereo_factors_large.txt'));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								fprintf(1,'Creating Graph\n'); tic
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								for i=1:size(measurements,1)
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    sf = measurements(i,:);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    graph.add(GenericStereoFactor3D(StereoPoint2(sf(3),sf(4),sf(5)), stereo_model, ...
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        symbol('x', sf(1)), symbol('l', sf(2)), K));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    if ~initial.exists(symbol('l',sf(2)))
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        % 3D landmarks are stored in camera coordinates: transform
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        % to world coordinates using the respective initial pose
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 07:51:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        pose = initial.atPose3(symbol('x', sf(1)));
							 | 
						
					
						
							
								
									
										
										
										
											2019-05-17 02:33:58 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								        world_point = pose.transformFrom(Point3(sf(6),sf(7),sf(8)));
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								        initial.insert(symbol('l',sf(2)), world_point);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								    end
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								end
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								toc
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% add a constraint on the starting pose
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								key = symbol('x',1);
							 | 
						
					
						
							
								
									
										
										
										
											2014-11-14 07:51:11 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								first_pose = initial.atPose3(key);
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								graph.add(NonlinearEqualityPose3(key, first_pose));
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% optimize
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								fprintf(1,'Optimizing\n'); tic
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								optimizer = LevenbergMarquardtOptimizer(graph, initial);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								result = optimizer.optimizeSafely();
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								toc
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								%% visualize initial trajectory, final trajectory, and final points
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								cla; hold on;
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-08-06 03:31:27 +08:00
										 
									 
								 
							 | 
							
								
									
										
									
								
							 | 
							
								
							 | 
							
							
								plot3DTrajectory(initial, 'r', 1, 0.5);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								plot3DTrajectory(result, 'g', 1, 0.5);
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								plot3DPoints(result);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-06 01:54:29 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								axis([-5 20 -20 20 0 100]);
							 | 
						
					
						
							
								
									
										
										
										
											2012-06-07 11:54:48 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								axis equal
							 | 
						
					
						
							| 
								
							 | 
							
								
							 | 
							
								
							 | 
							
							
								view(3)
							 | 
						
					
						
							
								
									
										
										
										
											2012-07-24 22:23:39 +08:00
										 
									 
								 
							 | 
							
								
							 | 
							
								
							 | 
							
							
								camup([0;1;0]);
							 |