forked from Ghost1995/Estimation-of-Quadrotor-State
-
Notifications
You must be signed in to change notification settings - Fork 0
/
Wrapper.m
206 lines (179 loc) · 6.13 KB
/
Wrapper.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
%% Wrapper for P2Ph1 for CMSC828T Course at University of Maryland, College Park
% Code by: Nitin J. Sanket ([email protected])
clc
clear all
close all
%% Add ToolBox to Path eg. ToolboxPath = 'gtsam_toolbox';
addpath('gtsam_toolbox');
addpath('QuaternionToolbox');
%% Load Data
% Download data from the following link:
% https://drive.google.com/drive/folders/0B-6qEdcGmuD8djIxVVJtYmhBd0E
% filename = 'DataFastCircle.mat';
% load('./Data/Fast Circle/DataFastCircle.mat');
% for i=1:length(DetAll)
% LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Fast Circle/FastCircleFrames/' num2str(i) '.jpg']));
% end
filename = 'DataMapping.mat';
load('./Data/Mapping/DataMapping.mat');
for i=1:length(DetAll)
LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Mapping/MappingFrames/' num2str(i) '.jpg']));
end
% filename = 'DataMountain.mat';
% load('./Data/Mountain/DataMountain.mat');
% for i=1:length(DetAll)
% LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Mountain/MountainFrames/' num2str(i) '.jpg']));
% end
% filename = 'DataSlowCircle.mat';
% load('./Data/Slow Circle/DataSlowCircle.mat');
% for i=1:length(DetAll)
% LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Slow Circle/SlowCircleFrames/' num2str(i) '.jpg']));
% end
% filename = 'DataSquare.mat';
% load('./Data/Square/DataSquare.mat');
% for i=1:length(DetAll)
% LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Square/SquareFrames/' num2str(i) '.jpg']));
% end
% filename = 'DataStraightLine.mat';
% load('./Data/Straight Line/DataStraightLine.mat');
% for i=1:length(DetAll)
% LeftImgs(:,:,i) = rgb2gray(imread(['./Data/Straight Line/StraightLineFrames/' num2str(i) '.jpg']));
% end
load('./Data/CalibParams.mat');
%% SLAM Using GTSAM
[LandMarksComputed, AllPosesComputedGTSAM, covariance] = SLAMusingGTSAM(DetAll, K, TagSize, filename);
%% Estimate Velocity
dT = [0;abs(TLeftImgs(2:end) - TLeftImgs(1:end-1))];
Z = correctAltitude(AllPosesComputedGTSAM, LandMarksComputed, TagSize, K);
V = velocityEstimator(LeftImgs, dT, K, Z);
% convert velocity to world frame
VelComputedGTSAM = zeros(length(DetAll),3);
for i=1:length(DetAll)
VelComputedGTSAM(i,:) = QuatToRot(AllPosesComputedGTSAM(i,4:7))*V(i,1:3)' + AllPosesComputedGTSAM(i,1:3)';
end
%% Localization using iSAM2
AllPosesComputediSAM = LocalizationUsingiSAM2(DetAll, K, TagSize, LandMarksComputed, filename);
%% Estimate Velocity
dT = [0;abs(TLeftImgs(2:end) - TLeftImgs(1:end-1))];
Z = correctAltitude(AllPosesComputediSAM, LandMarksComputed, TagSize, K);
V = velocityEstimator(LeftImgs, dT, K, Z);
% convert velocity to world frame
VelComputediSAM = zeros(length(DetAll),3);
for i=1:length(DetAll)
VelComputediSAM(i,:) = QuatToRot(AllPosesComputediSAM(i,4:7))*V(i,1:3)' + AllPosesComputediSAM(i,1:3)';
end
VelError = ComputeVelError(VelComputediSAM,VeliSAM2);
covariance = [covariance, zeros(6,3); zeros(3,6), cov(VelError)];
%% Extended Kalman Filter
PoseEKF = extendedKalmanFilter(AllPosesComputediSAM, VelComputediSAM, IMU, TLeftImgs, covariance);
% Plot the result (Position)
figure
subplot(1,3,1);
hold on
plot(AllPosesComputediSAM(:,1));
plot(PoseEKF(:,1));
plot(PoseGTSAM(:,1));
plot(AllPosesComputedGTSAM(:,1));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Position in x-direction (m)')
subplot(1,3,2);
hold on
plot(AllPosesComputediSAM(:,2));
plot(PoseEKF(:,2));
plot(PoseGTSAM(:,2));
plot(AllPosesComputedGTSAM(:,2));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Position in y-direction (m)')
subplot(1,3,3);
hold on
plot(AllPosesComputediSAM(:,3));
plot(PoseEKF(:,3));
plot(PoseGTSAM(:,3));
plot(AllPosesComputedGTSAM(:,3));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Position in z-direction (m)')
supertitle('Position of the Quadrotor')
OrientationComputediSAM = zeros(length(DetAll),3);
for i=1:length(DetAll)
OrientationComputediSAM(i,:) = RotToRPY_ZXY(QuatToRot(AllPosesComputediSAM(i,4:7)));
end
OrientationGTSAM = zeros(length(DetAll),3);
for i=1:length(DetAll)
OrientationGTSAM(i,:) = RotToRPY_ZXY(QuatToRot(PoseGTSAM(i,4:7)));
end
OrientationComputedGTSAM = zeros(length(DetAll),3);
for i=1:length(DetAll)
OrientationComputedGTSAM(i,:) = RotToRPY_ZXY(QuatToRot(AllPosesComputedGTSAM(i,4:7)));
end
% Plot the result (Orientation)
figure
subplot(1,3,1);
hold on
plot(OrientationComputediSAM(:,1));
plot(PoseEKF(:,4));
plot(OrientationGTSAM(:,1));
plot(OrientationComputedGTSAM(:,1));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Orientation about x-direction (rad)')
subplot(1,3,2);
hold on
plot(OrientationComputediSAM(:,2));
plot(PoseEKF(:,5));
plot(OrientationGTSAM(:,2));
plot(OrientationComputedGTSAM(:,2));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Orientation about y-direction (rad)')
subplot(1,3,3);
hold on
plot(OrientationComputediSAM(:,3));
plot(PoseEKF(:,6));
plot(OrientationGTSAM(:,3));
plot(OrientationComputedGTSAM(:,3));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Orientation about z-direction (rad)')
supertitle('Orientation of the Quadrotor')
% Plot the result (Velocity)
figure
subplot(1,3,1);
hold on
plot(VelComputediSAM(:,1));
plot(PoseEKF(:,7));
plot(VelGTSAM(:,1));
plot(VelComputedGTSAM(:,1));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Velocity in x-direction (m/s)')
subplot(1,3,2);
hold on
plot(VelComputediSAM(:,2));
plot(PoseEKF(:,8));
plot(VelGTSAM(:,2));
plot(VelComputedGTSAM(:,2));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Velocity in y-direction (m/s)')
subplot(1,3,3);
hold on
plot(VelComputediSAM(:,3));
plot(PoseEKF(:,9));
plot(VelGTSAM(:,3));
plot(VelComputedGTSAM(:,3));
hold off
legend({'iSAM2 Output','EKF Output','GTSAM Ground Truth','GTSAM Output'})
xlabel('Frame Number')
ylabel('Velocity in z-direction (m/s)')
supertitle('Velocity of the Quadrotor')