gtsam/matlab/examples/StereoVOExample_large.m

86 lines
2.7 KiB
Matlab
Raw Normal View History

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
%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%%
%% Load calibration
import gtsam.*
2012-06-06 01:54:29 +08:00
% format: fx fy skew cx cy baseline
2012-06-08 05:52:15 +08:00
calib = dlmread('../../examples/Data/VO_calibration.txt');
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
graph = visualSLAM.Graph;
initial = visualSLAM.Values;
2012-06-06 01:54:29 +08:00
%% load the initial poses from VO
% row format: camera_id 4x4 pose (row, major)
import gtsam.*
fprintf(1,'Reading data\n');
2012-06-14 12:51:42 +08:00
cameras = dlmread('../../examples/Data/VO_camera_poses_large.txt');
for i=1:size(cameras,1)
pose = Pose3(reshape(cameras(i,2:17),4,4)');
initial.insertPose(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
import gtsam.*
2012-06-14 12:51:42 +08:00
measurements = dlmread('../../examples/Data/VO_stereo_factors_large.txt');
2012-06-06 01:54:29 +08:00
fprintf(1,'Creating Graph\n'); tic
for i=1:size(measurements,1)
sf = measurements(i,:);
graph.addStereoMeasurement(StereoPoint2(sf(3),sf(4),sf(5)), stereo_model, ...
symbol('x', sf(1)), symbol('l', sf(2)), K);
2012-06-06 01:54:29 +08:00
if ~initial.exists(symbol('l',sf(2)))
% 3D landmarks are stored in camera coordinates: transform
2012-06-06 01:54:29 +08:00
% to world coordinates using the respective initial pose
pose = initial.pose(symbol('x', sf(1)));
world_point = pose.transform_from(Point3(sf(6),sf(7),sf(8)));
2012-06-06 01:54:29 +08:00
initial.insertPoint(symbol('l',sf(2)), world_point);
end
end
toc
2012-06-06 01:54:29 +08:00
%% add a constraint on the starting pose
key = symbol('x',1);
first_pose = initial.pose(key);
graph.addPoseConstraint(key, first_pose);
2012-06-06 01:54:29 +08:00
%% optimize
fprintf(1,'Optimizing\n'); tic
result = graph.optimize(initial,1);
toc
2012-06-06 01:54:29 +08:00
%% visualize initial trajectory, final trajectory, and final points
figure(1); clf; hold on;
2012-06-06 01:54:29 +08:00
% initial trajectory in red (rotated so Z is up)
plot3(initial.zs(),-initial.xs(),-initial.ys(), '-*r','LineWidth',2);
2012-06-06 01:54:29 +08:00
% final trajectory in green (rotated so Z is up)
plot3(result.zs(),-result.xs(),-result.ys(), '-*g','LineWidth',2);
2012-06-06 01:54:29 +08:00
xlabel('X (m)'); ylabel('Y (m)'); zlabel('Z (m)');
% switch to XZ view
view([0 0]);
% optimized 3D points (rotated so Z is up)
2012-06-06 01:54:29 +08:00
points = result.points();
plot3(points(:,3),-points(:,1),-points(:,2),'.');
2012-06-06 01:54:29 +08:00
axis([0 100 -20 20 -5 20]);
axis equal
view(3)