Fixed examples

release/4.3a0
Frank Dellaert 2012-07-25 22:15:20 +00:00
parent dff2fc6de2
commit 29f48e1127
3 changed files with 18 additions and 12 deletions

View File

@ -38,11 +38,13 @@ initial.insertPose(5, hexagon.pose(5).retract([-0.1, 0.1,-0.1]'));
%% Plot Initial Estimate
figure(1);clf
plot(initial.xs(),initial.ys(),'g-*'); axis equal
P=initial.poses;
plot(P(:,1),P(:,2),'g-*'); axis equal
%% optimize
result = fg.optimize(initial);
result = fg.optimize(initial,1);
%% Show Result
hold on; plot(result.xs(),result.ys(),'b-*')
P=result.poses;
hold on; plot(P(:,1),P(:,2),'b-*')
result.print(sprintf('\nFinal result:\n'));

View File

@ -13,7 +13,7 @@
%% Initialize graph, initial estimate, and odometry noise
import gtsam.*
model = noiseModel.Diagonal.Sigmas([0.05; 0.05; 5*pi/180]);
[graph,initial]=load2D('../../examples/Data/w100-odom.graph',model);
[graph,initial]=load2D('Data/w100-odom.graph',model);
initial.print(sprintf('Initial estimate:\n'));
%% Add a Gaussian prior on pose x_1
@ -24,11 +24,13 @@ graph.addPosePrior(0, priorMean, priorNoise); % add directly to graph
%% Plot Initial Estimate
figure(1);clf
plot(initial.xs(),initial.ys(),'g-*'); axis equal
P=initial.poses;
plot(P(:,1),P(:,2),'g-*'); axis equal
%% Optimize using Levenberg-Marquardt optimization with an ordering from colamd
result = graph.optimize(initial);
hold on; plot(result.xs(),result.ys(),'b-*')
result = graph.optimize(initial,1);
P=result.poses;
hold on; plot(P(:,1),P(:,2),'b-*')
result.print(sprintf('\nFinal result:\n'));
%% Plot Covariance Ellipses

View File

@ -13,7 +13,7 @@
%% Load calibration
import gtsam.*
% format: fx fy skew cx cy baseline
calib = dlmread('../../examples/Data/VO_calibration.txt');
calib = dlmread('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]);
@ -26,7 +26,7 @@ initial = visualSLAM.Values;
% row format: camera_id 4x4 pose (row, major)
import gtsam.*
fprintf(1,'Reading data\n');
cameras = dlmread('../../examples/Data/VO_camera_poses_large.txt');
cameras = dlmread('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);
@ -35,7 +35,7 @@ end
%% load stereo measurements and initialize landmarks
% camera_id landmark_id uL uR v X Y Z
import gtsam.*
measurements = dlmread('../../examples/Data/VO_stereo_factors_large.txt');
measurements = dlmread('Data/VO_stereo_factors_large.txt');
fprintf(1,'Creating Graph\n'); tic
for i=1:size(measurements,1)
@ -67,10 +67,12 @@ toc
figure(1); clf; hold on;
% initial trajectory in red (rotated so Z is up)
plot3(initial.zs(),-initial.xs(),-initial.ys(), '-*r','LineWidth',2);
P = initial.translations;
plot3(P(:,3),-P(:,1),-P(:,2), '-*r','LineWidth',2);
% final trajectory in green (rotated so Z is up)
plot3(result.zs(),-result.xs(),-result.ys(), '-*g','LineWidth',2);
P = result.translations;
plot3(P(:,3),-P(:,1),-P(:,2), '-*g','LineWidth',2);
xlabel('X (m)'); ylabel('Y (m)'); zlabel('Z (m)');
% switch to XZ view