-
Notifications
You must be signed in to change notification settings - Fork 4
/
runVIOV2_SIM.m~
192 lines (143 loc) · 5.52 KB
/
runVIOV2_SIM.m~
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
%% Clean up
clc;
clear rosbag_wrapper;
clear ros.Bag;
clear all;
close all;
addpath('helpers');
addpath('keyframe_imu');
addpath('../MATLAB/utils');
addpath('simulation');
addpath('depth_filter/');
addpath('triangulation/');
if ismac
addpath('/Users/valentinp/Research/opengv/matlab');
else
addpath('~/Dropbox/Research/Ubuntu/opengv/matlab');
end
if ismac
addpath('/Users/valentinp/Research/gtsam_toolbox');
else
addpath('~/Dropbox/Research/Ubuntu/gtsam_toolbox/');
end
import gtsam.*;
%% Random number seed
rng('shuffle');
%% Specify transformation
T_camimu = eye(4);
%% Generate the measurments
%Generate the trajectory motion
close all;
disp('Generating trajectory...');
%Simulation parameters
simSetup.imuRate = 500; % Hz
simSetup.cameraRate = 15; % Hz
simSetup.cameraResolution = [1280, 960]; %pixels
simSetup.simTime = 15; % seconds
simSetup.gyroNoiseStd = 1e-2;
simSetup.accelNoiseStd = 1e-1;
simSetup.gyroBiasStd = 1e-5;
simSetup.accelBiasStd = 1e-5;
simSetup.pixelNoiseStd = 0.5; %pixels
[T_wImu_GT, imuData] = genTrajectoryCircle(simSetup);
T_wCam_GT = T_wImu_GT;
for i = 1:size(T_wImu_GT, 3)
T_wCam_GT(:,:,i) = T_wImu_GT(:,:,i)*inv(T_camimu);
end
%Generate the true landmarks
landmarks_w = genLandmarks([-20,20], [-20,20],[0,10], 2000);
%Set the camera intrinsics
focalLength = 4*1e-3; %10 mm
pixelWidth = 4.8*1e-6;
%
K = [focalLength/pixelWidth 0 640;
0 focalLength/pixelWidth 480;
0 0 1];
%Generate image data
disp('Generating image measurements...');
imageMeasurements = genImageMeasurements(T_wCam_GT, landmarks_w, K, simSetup);
%
%visualizeVO([], T_wCam_GT(:,:,1:10:size(T_wCam_GT,3)), zeros(3,1), 'Simulation')
disp('Done generating measurements.');
%% VIO pipeline
%Set parameters
close all;
pipelineOptions.initDisparityThreshold = 15;
pipelineOptions.kfDisparityThreshold = 15;
pipelineOptions.inlierThreshold = 10000;
pipelineOptions.verbose = false;
%GTSAM
pipelineOptions.minViewingsForLandmark = 3;
pipelineOptions.obsNoiseSigma = 0.5;
pipelineOptions.useRobustMEst = false;
pipelineOptions.mEstWeight = 1;
pipelineOptions.maxBatchOptimizerError = 5;
noiseParams.sigma_g = 1e-2*ones(3,1);
noiseParams.sigma_a = 1e-1*ones(3,1);
noiseParams.sigma_bg = 1e-5*ones(3,1);
noiseParams.sigma_ba = 1e-5*ones(3,1);
noiseParams.init_ba = zeros(3,1);
noiseParams.init_bg = zeros(3,1);
xInit.p = imuData.initialPosition;
xInit.v = imuData.initialVelocity;
xInit.b_g = zeros(3,1);
xInit.b_a = zeros(3,1);
xInit.q = imuData.measOrient(:,1);
g_w = [0 0 -9.81]';
%The pipeline
[T_wc_estimated,T_wimu_estimated, T_wimu_gtsam, keyFrames] = VIOPipelineV2_SIM(K, T_camimu, imageMeasurements, imuData, pipelineOptions, noiseParams, xInit, g_w, T_wImu_GT, landmarks_w);
% Plot the estimated values
figure;
set (gcf(), 'outerposition', [25 800, 560, 470])
p_IMUw_w_GT = zeros(3, length(keyFrames));
p_IMUw_w_int = zeros(3, length(keyFrames));
p_IMUw_w_gtsam = zeros(3, length(keyFrames));
% Get the keyframe IMU ids
keyFrameIdsIMU = zeros(1, length(keyFrames));
for kf_i = 1:length(keyFrames)
keyFrameIdsIMU(kf_i) = keyFrames(kf_i).imuMeasId;
p_IMUw_w_GT(:,kf_i) = homo2cart(T_wImu_GT(:,:,keyFrames(kf_i).imuMeasId)*[0;0;0;1]);
p_IMUw_w_int(:,kf_i) = homo2cart(T_wimu_estimated(:,:,keyFrames(kf_i).imuMeasId)*[0;0;0;1]);
p_IMUw_w_gtsam(:,kf_i) = homo2cart(T_wimu_gtsam(:,:,kf_i)*[0;0;0;1]);
end
plot3(p_IMUw_w_GT(1,:),p_IMUw_w_GT(2,:),p_IMUw_w_GT(3,:), '.-k');
hold on; grid on;
plot3(p_IMUw_w_int(1,:), p_IMUw_w_int(2,:), p_IMUw_w_int(3,:),'.-r');
plot3(p_IMUw_w_gtsam(1,:),p_IMUw_w_gtsam(2,:),p_IMUw_w_gtsam(3,:), '.-g');
view([0 90]);
legend('Ground Truth', 'Integrated','GTSAM', 4)
% Calculate Relative Pose Error
% Take only the poses at the keyframes
T_wIMU_GT_sync = T_wImu_GT(:,:,keyFrameIdsIMU);
T_wimu_est_sync = T_wimu_estimated(:,:, keyFrameIdsIMU);
RMSE_RPE_imuonly_list = zeros(1, size(T_wIMU_GT_sync,3)-1);
RMSE_RPE_gtsam_list =zeros(1, size(T_wIMU_GT_sync,3)-1);
%Iterative through different step sizes
for dstep = 1:size(T_wIMU_GT_sync,3)-1
RPE_opt = zeros(4,4, size(T_wIMU_GT_sync,3) - dstep);
RPE_imuonly = RPE_opt;
for i = 1:(size(T_wIMU_GT_sync,3)-dstep)
RPE_opt(:,:,i) = inv(inv(T_wIMU_GT_sync(:,:,i))*T_wIMU_GT_sync(:,:,i+dstep))*inv(T_wimu_gtsam(:,:,i))*T_wimu_gtsam(:,:,i+dstep);
RPE_imuonly(:,:,i) = inv(inv(T_wIMU_GT_sync(:,:,i))*T_wIMU_GT_sync(:,:,i+dstep))*inv(T_wimu_est_sync(:,:,i))*T_wimu_est_sync(:,:,i+dstep);
end
%Calculate the root mean squared error of all the relative pose errors
RMSE_RPE_opt = 0;
RMSE_RPE_imuonly = 0;
for i = 1:size(RPE_opt,3)
RMSE_RPE_opt = RMSE_RPE_opt + norm(RPE_opt(1:3,4,i))^2;
RMSE_RPE_imuonly = RMSE_RPE_imuonly + norm(RPE_imuonly(1:3,4,i))^2;
end
RMSE_RPE_imuonly_list(dstep) = sqrt(RMSE_RPE_imuonly/size(RPE_opt,3));
RMSE_RPE_gtsam_list(dstep) = sqrt(RMSE_RPE_opt/size(RPE_opt,3));
end
RMSE_RPE_opt = mean(RMSE_RPE_gtsam_list);
RMSE_RPE_imuonly = mean(RMSE_RPE_imuonly_list);
%Add to the title
title(sprintf('Mean RMSE RPE (Optimized/IMU Only): %.5f / %.5f ', RMSE_RPE_opt, RMSE_RPE_imuonly));
printf('--------- \n End Euclidian Error (Opt/IMU): %.5f / %.5f', norm(p_IMUw_w_GT(:,end) - p_IMUw_w_gtsam(:, end)) ,norm(p_IMUw_w_GT(:,end) - p_IMUw_w_int(:, end)));
% Display mean errors
opt_errors = p_IMUw_w_GT - p_IMUw_w_gtsam;
imu_errors = p_IMUw_w_GT - p_IMUw_w_int;
mean_opt_euc = mean(sqrt(sum(opt_errors.^2, 1)));
mean_imu_euc = mean(sqrt(sum(imu_errors.^2, 1)));
printf('--------- \n Mean Euclidian Error (Opt/IMU): %.5f / %.5f',mean_opt_euc , mean_imu_euc);