forked from marynelv/IVCalibrationToolbox
-
Notifications
You must be signed in to change notification settings - Fork 0
/
pqvtrgbbUKF.m
392 lines (323 loc) · 13.7 KB
/
pqvtrgbbUKF.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
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
% Position, orientation, velocity, I-C translation, I-C rotation, gravity
% and biases UKF
%clc
close all
if (~exist('plotFlag')),
plotFlag = 1; % make 1 to plot
end
saveFlag = 0; % make 1 to save plot
%% UKF parameters
ukf_alpha = .01;
ukf_beta = 2;
%% x: state vector
% Composed by IMU position, rotation quaternion ([w x y z]') and velocity
% in the world frame
% [p_w_i; q_w_i; v_w_i; q_i_c; q_i_c; gravity; bias_accel; bias_gyro] = x(1:26);
%% P: state covariance matrix 24-by-26
% NOTE: P is not 26-by-26 because we consider 3 deg of freedom for the
% rotations
%% u: process inputs
% Composed by measured IMU acceleration and rotational velocity
% u = [accel_i_measured(1:3, i); gyro_i_measured(1:3, i)]
%% n: process noise
%% Q: 12x12 process noise covariance matrix
Qgw = eye(3) * 0.0196^2; % noise gyro bias (more or less as in the data sheet)
Qaw = eye(3) * 0.0001^2; % noise accel bias (more or less as synthesized)
Qacc = eye(3) * 0.1^2;
Qrot = eye(3) * 0.001 * 300 * pi/180; % rad/s
Q = blkdiag(Qacc, Qrot, Qaw, Qgw);
%% z: measurements
% See section 4.3 Measurement Model on page 11
% z is a 2n-by-1 column vector of observed pixel coordinates in the
% form [x1 y1 ... xn yn]' where n is the number of 3D feature points
%% R: measurement noise covariance matrix
% The associated block-daigonal covariance matrix of z
% R = diag(R1 ... Rn) = 0.1^2 * eye(length(z));
%% Starting index
%i = lengthLowPass+1;
%j = lengthLowPass+1;
%nowTime = imuData(i-1,3);
i = 2;
j = 2;
nowTime = imuData(i-1,3);
%% Initial estimate
clear x;
mrpStd = @(deg) tan(deg*pi/720); % mrp error = tan((deg*pi)/(4*180))
iniPos = p_w(:,i) + rand(3,1).*(0.08^2); % initial position in world frame
iniV = v_w(:,i-1) + rand(3,1).*(0.3^2); % initial velocity in world frame
iniQMRPerror = rand(3,1).*(mrpStd(8)^2); % 8 deg of error for initial orientation
norm_mrp_error = sqrt(sum(iniQMRPerror.^2, 1));
dq0 = (1 - norm_mrp_error) ./ (1 + norm_mrp_error);
iniQerror = [ dq0; bsxfun(@times,(1+dq0),iniQMRPerror)];
iniQ = quaternionproduct(iniQerror,q_w_i(:,i)); % initial orientation in world frame
iniQ = iniQ ./ norm(iniQ);
iniP_i_c = p_i_c+.1*randn(3,1);
iniQicMRPerror = rand(3,1).*(mrpStd(5)^2); % 5 deg of error for initial imu-cam orientation
norm_mrp_error = sqrt(sum(iniQicMRPerror.^2, 1));
dq0 = (1 - norm_mrp_error) ./ (1 + norm_mrp_error);
iniQicerror = [ dq0; bsxfun(@times,(1+dq0),iniQicMRPerror)];
iniQ_i_c = quaternionproduct(iniQicerror,q_i_c); % initial orientation in world frame
iniQ_i_c = iniQ_i_c ./ norm(iniQ_i_c);
iniG=-gravity+.1*randn(3,1);
iniBa = bias_accel(:,i) + + 0.1*rand(3,1);
iniBg = bias_gyro(:,i) + + 0.1*rand(3,1);
x = [iniPos; iniQ; iniV; iniP_i_c; iniQ_i_c; iniG; iniBa; iniBg];
Ppos = eye(3).*(.1^2);
Pori = eye(3).*(mrpStd(10)^2);
Pvel = eye(3).*(.5^2);
Ppic=eye(3).*1e-4;
Pqic=eye(3).*(mrpStd(7)^2);
Pgra = diag([1.7 1.7 0.15].^2); % just very small, though ideally it would be zero
Pba = eye(3)*0.001^2;
Pbg = eye(3)*0.02^2;
P=blkdiag(Ppos,Pori,Pvel,Ppic,Pqic,Pgra,Pba,Pbg);
%% Initialize storage matrices and figure
numCamMeasurements = size(observed_pts_c, 2) - j - 1;
numImuMeasurements = length(imuData) - i - 1;
numPoses = numImuMeasurements + numCamMeasurements;
accumPoses = zeros(3,numPoses);
accumQuat = NaN * ones(4,numPoses);
distanceError = zeros(1, numPoses);
orientationError = zeros(1, numPoses);
velocityError = zeros(1, numPoses);
picError=zeros(1,numPoses);
qicError=zeros(1,numPoses);
gravityError = zeros(1, numPoses);
biasAccelError = zeros(1,numPoses);
biasGyroError = zeros(1,numPoses);
process_params = cell(3,1);
obs_params = cell(5,1);
accum_pwc = zeros(3,numPoses);
accum_pwi = zeros(3,numPoses);
accum_pwi_estim = zeros(3,numPoses);
accum_qwc = zeros(4,numPoses);
accum_qwi = zeros(4,numPoses);
accum_qwi_estim = zeros(4,numPoses);
accum_pic_estim = zeros(3,numPoses);
accum_qic_estim = zeros(4,numPoses);
accum_pwc_estim = zeros(3,numPoses);
accum_qwc_estim = zeros(4,numPoses);
accum_biasaccel_estim = zeros(3,numPoses);
accum_biasgyro_estim = zeros(3,numPoses);
if plotFlag == 1,
h = figure('Name','Position, Orientation and Velocity Estimation', ...
'NumberTitle','off','Position',[10 10 1000 600]);
h1 = figure('Name', 'Gyro Bias', ...
'NumberTitle', 'off', 'Position',[50 50 500 300]);
h2 = figure('Name', 'Accel Bias', ...
'NumberTitle', 'off', 'Position',[50 50 500 300]);
end
%% Begin Kalman filter
count = 1;
while (i <= numImuMeasurements && j <= numCamMeasurements )
% Read the timestamp for the next data input
imuTime = imuData(i,3);
camTime = camData(j,3);
% Get previous orientation belief
prev_q = x(4:7);
prev_qic_q=x(14:17);
if (imuTime <= camTime)
%% Prediction step
pastTime = nowTime;
nowTime = imuTime;
dt = nowTime - pastTime;
u = [accel_i_measured(:,i); gyro_i_measured(:,i)];
process_params{1} = u;
process_params{2} = dt;
process_params{3} = prev_q;
process_handle = @processModelPQVTRGBB;
% State error vector with q and q_i_c as MRP
x_se = [x(1:3); 0; 0; 0; x(8:13); 0; 0; 0; x(18:26)];
[x_se, Ppred] = predictUKF(x_se, process_handle, process_params, ...
P, Q, ukf_alpha, ukf_beta);
% Convert MRP update vectors to quaternion update
mrp_error = x_se(4:6);
norm_mrp_error = sqrt(sum(mrp_error.^2, 1));
dq0 = (1 - norm_mrp_error) ./ (1 + norm_mrp_error);
q_error = [ dq0;
bsxfun(@times,(1+dq0),mrp_error)];
quat_new = quaternionproduct(q_error, prev_q);
quat_new = quat_new./norm(quat_new);
mrp_qic_error=x_se(13:15);
norm_mrp_qic_error=sqrt(sum(mrp_qic_error.^2,1));
dq_qic0=(1-norm_mrp_qic_error)./(1+norm_mrp_qic_error);
q_qic_error=[dq_qic0; bsxfun(@times,1+dq_qic0,mrp_qic_error)];
quat_qic_new=quaternionproduct(q_qic_error, prev_qic_q);
quat_qic_new=quat_qic_new/norm(quat_qic_new);
x = [x_se(1:3); quat_new; x_se(7:12); quat_qic_new; x_se(16:24)];
P=Ppred;
i = i + 1;
else
%% Correction Step
% Perform correction step
z = noisy_observed_pts_c(:,j);
R = 0.1^2 * eye(length(z));
% State error vector with q and q_i_c as MRP
x_se = [x(1:3); 0; 0; 0; x(8:13); 0; 0; 0; x(18:26)]; % State error vector with q in MRP
obs_params{1} = prev_q;
obs_params{2} = prev_qic_q;
obs_params{3} = pts_w(1:3, :); %landmarks in the world;
obs_params{4} = K;
obs_handle = @measurementModelPQVTRGBB;
[ x_se, P ] = correctUKF( x_se, P, R, z, obs_handle, obs_params, ukf_alpha, ukf_beta );
% Convert MRP update vectors to quaternion update
mrp_error = x_se(4:6);
norm_mrp_error = sqrt(sum(mrp_error.^2, 1));
dq0 = (1 - norm_mrp_error) ./ (1 + norm_mrp_error);
q_error = [ dq0;
bsxfun(@times,(1+dq0),mrp_error)];
quat_new = quaternionproduct(q_error, prev_q);
quat_new = quat_new./norm(quat_new);
mrp_qic_error=x_se(13:15);
norm_mrp_qic_error=sqrt(sum(mrp_qic_error.^2,1));
dq_qic0=(1-norm_mrp_qic_error)./(1+norm_mrp_qic_error);
q_qic_error=[dq_qic0; bsxfun(@times,1+dq_qic0,mrp_qic_error)];
quat_qic_new=quaternionproduct(q_qic_error, prev_qic_q);
quat_qic_new=quat_qic_new/norm(quat_qic_new);
x = [x_se(1:3); quat_new; x_se(7:12); quat_qic_new; x_se(16:24)];
j = j + 1;
end
if (i < numImuMeasurements)
%% Distance error
distanceError(1,count) = norm(x(1:3) - p_w(:,i-1));
velocityError(1,count) = norm(x(8:10) - v_w(:,i-1));
orientationError(1,count) = findQuaternionError(x(4:7), q_w_i(:,i-1));
picError(1,count)=norm(x(11:13)-p_i_c);
qicError(1,count)=findQuaternionError(x(14:17),q_i_c);
gravityError(1,count) = norm(x(18:20) - (-gravity));
biasAccelError(1,count) = norm(x(21:23) - bias_accel(:,i-1));
biasGyroError(1,count) = norm(x(24:26) - bias_gyro(:,i-1));
%% Plot
accumPoses(:,count) = x(1:3);
accum_pwi(:,count)=p_w(:,i-1);
accum_pwi_estim(:,count)=x(1:3);
accum_pwc(:,count)=p_w_c(:,i-1);
accum_qwi(:,count)=q_w_i(:,i-1);
accum_qwc(:,count)=q_w_c(:,i-1);
accum_qwi_estim(:,count)=x(4:7);
accum_pic_estim(:,count)=x(11:13);
accum_qic_estim(:,count)=x(14:17);
accum_qwc_estim(:,count)=rotation2quaternion(quaternion2rotation(accum_qwi_estim(:,count))*quaternion2rotation(accum_qic_estim(:,count)));
accum_pwc_estim(:,count)=accum_pwi_estim(:,count)+quaternion2rotation(accum_qwi_estim(:,count))*accum_pic_estim(:,count);
accum_biasaccel_estim(:,count) = x(21:23);
accum_biasgyro_estim(:,count) = x(24:26);
count = count + 1;
if mod(count, 10) == 1 && plotFlag == 1
figure(h);
clf
subplot(4,3,[1, 4, 7, 10]);
%plot3(accumPoses(1,1:count-1), accumPoses(2,1:count-1), accumPoses(3,1:count-1),'-');
%hold on;
%plot3(p_w(1,1:i), p_w(2,1:i), p_w(3,1:i), 'g');
% hold on;
% plot3(pts_w(1, :), pts_w(2, :), pts_w(3, :), 'r.');
%axis equal
%axis vis3d
%xlabel('x'); ylabel('y'); zlabel('z');
%grid on;
[accum_pwc_estim,accum_qwc_estim]=prettyPlotSingle(...
accum_pwc,accum_qwc,accum_pwi,...
accum_pwc_estim,accum_qwc_estim,accum_pwi_estim,...
pts_w,pts_center,count-1);
title(sprintf('Motion Estimation (Frame %d)', count));
subplot(4,3,2);
plot(1:count,distanceError(1:count));
maxErr = max(distanceError);
axis([0 numPoses 0 maxErr]);
% xlabel('Time');
%ylabel('Squared Error');
title('Distance Error');
subplot(4,3,3);
plot(1:count,velocityError(1:count));
maxErr = max(velocityError);
axis([0 numPoses 0 maxErr]);
% xlabel('Time');
%ylabel('Squared Error');
title('Velocity Error');
subplot(4,3,5);
plot(1:count,orientationError(1:count));
maxErr = max(orientationError);
axis([0 numPoses 0 maxErr]);
xlabel('Time');
% ylabel('Squared Error');
title('Orientation Error');
subplot(4,3,6);
plot(1:count,gravityError(1:count));
maxErr = max(gravityError);
axis([0 numPoses 0 maxErr]);
xlabel('Time');
%ylabel('Squared Error');
title('Gravity Error');
subplot(4,3,8);
plot(1:count,picError(1:count));
maxErr = max(picError)+.1;
axis([0 numPoses 0 maxErr]);
xlabel('Time');
%ylabel('Squared Error');
title('IMU-Camera Translation Error');
subplot(4,3,9);
plot(1:count,qicError(1:count));
maxErr = max(qicError)+.1;
axis([0 numPoses 0 maxErr]);
xlabel('Time');
% ylabel('Squared Error');
title('IMU-Camera Rotation Error');
subplot(4,3,11);
plot(1:count,biasAccelError(1:count));
maxErr = max(biasAccelError)+.1;
axis([0 numPoses 0 maxErr]);
xlabel('Time');
% ylabel('Squared Error');
title('Accel Bias Error');
subplot(4,3,12);
plot(1:count,biasGyroError(1:count));
maxErr = max(biasGyroError)+.1;
axis([0 numPoses 0 maxErr]);
xlabel('Time');
%ylabel('Squared Error');
title('Gyro Bias Error');
if (saveFlag),
F=getframe(gcf);
imwrite(F.cdata,sprintf('plot/%03d.png',i));
end
%subplot(4,3,[1, 4, 7, 10]);
%F=getframe(gca);
%imwrite(F.cdata,sprintf('motion/%03d.png',i));
%pause
%saveas(gcf,sprintf('plot/%03d.png',i));
subplot(4,3,[1, 4, 7, 10]);
if (saveFlag),
saveas(gca,sprintf('motion/%03d.png',i));
end
%print('-dpng','-r300','-opengl',sprintf('plot/%03d.png',i));
figure(h1);
clf
subplot(1,2,1);
hold on;
plot(1:i-1,bias_gyro(1,1:i-1),'r-');
plot(1:i-1,bias_gyro(2,1:i-1),'g-');
plot(1:i-1,bias_gyro(3,1:i-1),'b-');
title('Real Gyro Bias');
subplot(1,2,2);
hold on;
plot(1:count,accum_biasgyro_estim(1,1:count),'r-');
plot(1:count,accum_biasgyro_estim(2,1:count),'g-');
plot(1:count,accum_biasgyro_estim(3,1:count),'b-');
title('Estimated Gyro Bias');
figure(h2);
clf
subplot(1,2,1);
hold on;
plot(1:i-1,bias_accel(1,1:i-1),'r-');
plot(1:i-1,bias_accel(2,1:i-1),'g-');
plot(1:i-1,bias_accel(3,1:i-1),'b-');
title('Real Accel Bias');
subplot(1,2,2);
hold on;
plot(1:count,accum_biasaccel_estim(1,1:count),'r-');
plot(1:count,accum_biasaccel_estim(2,1:count),'g-');
plot(1:count,accum_biasaccel_estim(3,1:count),'b-');
title('Estimated Accel Bias');
end
end
end