-
Notifications
You must be signed in to change notification settings - Fork 2
/
ekf.py
300 lines (252 loc) · 13.1 KB
/
ekf.py
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
# Starter code for the State Estimation Pipeline.
import pickle
import numpy as np
import matplotlib.pyplot as plt
from mpl_toolkits.mplot3d import Axes3D
from rotations import angle_normalize, rpy_jacobian_axis_angle, skew_symmetric_1,skew_symmetric_2, Quaternion
#### 1. Data ##############################################################################################################
###########################################################################################################################
# This is where you will load the data from the pickle files. You will use data.pkl. For Part 3, you will use pt3_data.pkl.
##########################################################################################################################
file_path="c:/Users/Reethika Prasanna/Downloads/EKF_State_Estimator (2)/EKF_State_Estimator/data/pt1_data.pkl"
with open(file_path, 'rb') as file:
data = pickle.load(file)
################################################################################################
# Each element of the data dictionary is stored as an item from the data dictionary, which we
# will store in local variables, described by the following:
# gt: Data object containing ground truth. with the following fields:
# a: Acceleration of the vehicle, in the inertial frame
# v: Velocity of the vehicle, in the inertial frame
# p: Position of the vehicle, in the inertial frame
# alpha: Rotational acceleration of the vehicle, in the inertial frame
# w: Rotational velocity of the vehicle, in the inertial frame
# r: Rotational position of the vehicle, in Euler (XYZ) angles in the inertial frame
# _t: Timestamp in ms.
# imu_f: StampedData object with the imu specific force data (given in vehicle frame).
# data: The actual data
# t: Timestamps in ms.
# imu_w: StampedData object with the imu rotational velocity (given in the vehicle frame).
# data: The actual data
# t: Timestamps in ms.
# gnss: StampedData object with the GNSS data.
# data: The actual data
# t: Timestamps in ms.
# lidar: StampedData object with the LIDAR data (positions only).
# data: The actual data
# t: Timestamps in ms.
################################################################################################
gt = data['gt']
imu_f = data['imu_f']
imu_w = data['imu_w']
gnss = data['gnss']
lidar = data['lidar']
################################################################################################
# Let's plot the ground truth trajectory to see what it looks like. When you're testing your
# code later, feel free to comment this out.
################################################################################################
gt_fig = plt.figure()
ax = gt_fig.add_subplot(111, projection='3d')
ax.plot(gt.p[:,0], gt.p[:,1], gt.p[:,2])
ax.set_xlabel('x [m]')
ax.set_ylabel('y [m]')
ax.set_zlabel('z [m]')
ax.set_title('Ground Truth trajectory')
ax.set_zlim(-1, 5)
#plt.show()
################################################################################################
# Remember that our LIDAR data is actually just a set of positions estimated from a separate
# scan-matching system, so we can insert it into our solver as another position measurement,
# just as we do for GNSS. However, the LIDAR frame is not the same as the frame shared by the
# IMU and the GNSS. To remedy this, we transform the LIDAR data to the IMU frame using our
# known extrinsic calibration rotation matrix C_li and translation vector t_i_li.
#
# THIS IS THE CODE YOU WILL MODIFY FOR PART 2 OF THE ASSIGNMENT.
################################################################################################
# Correct calibration rotation matrix, corresponding to Euler RPY angles (0.05, 0.05, 0.1).
#C_li = np.array([
# [ 0.99376, -0.09722, 0.05466],
# [ 0.09971, 0.99401, -0.04475],
#[-0.04998, 0.04992, 0.9975 ]
#])
# Incorrect calibration rotation matrix, corresponding to Euler RPY angles (0.05, 0.05, 0.05).
C_li = np.array([
[ 0.9975 , -0.04742, 0.05235],
[ 0.04992, 0.99763, -0.04742],
[-0.04998, 0.04992, 0.9975 ]
])
t_i_li = np.array([0.5, 0.1, 0.5])
# Transform from the LIDAR frame to the vehicle (IMU) frame.
lidar.data = (C_li @ lidar.data.T).T + t_i_li
#### 2. Constants ##############################################################################
################################################################################################
# Now that our data is set up, we can start getting things ready for our solver. One of the
# most important aspects of a filter is setting the estimated sensor variances correctly.
# We set the values here.
################################################################################################
var_imu_f = 0.10
var_imu_w = 0.25
var_gnss = 0.01
var_lidar = 1.00
################################################################################################
# We can also set up some constants that won't change for any iteration of our solver.
################################################################################################
g = np.array([0, 0, -9.81]) # gravity
l_jac = np.zeros([9, 6])
l_jac[3:, :] = np.eye(6) # motion model noise jacobian
h_jac = np.zeros([3, 9])
h_jac[:, :3] = np.eye(3) # measurement model jacobian
#### 3. Initial Values #########################################################################
################################################################################################
# Let's set up some initial values for our EKF solver.
################################################################################################
p_est = np.zeros([imu_f.data.shape[0], 3]) # position estimates
v_est = np.zeros([imu_f.data.shape[0], 3]) # velocity estimates
q_est = np.zeros([imu_f.data.shape[0], 4]) # orientation estimates as quaternions
p_cov = np.zeros([imu_f.data.shape[0], 9, 9]) # covariance matrices at each timestep
# Set initial values.
p_est[0] = gt.p[0]
v_est[0] = gt.v[0]
q_est[0] = Quaternion(euler=gt.r[0]).to_numpy()
p_cov[0] = np.zeros(9) # covariance of estimate
gnss_i = 0
lidar_i = 0
#### 4. Measurement Update #####################################################################
################################################################################################
# Since we'll need a measurement update for both the GNSS and the LIDAR data, let's make
# a function for it.
################################################################################################
def measurement_update(sensor_var, p_cov_check, y_k, p_check, v_check, q_check):
# 3.1 Compute Kalman Gain
K_k = p_cov_check @ h_jac.T @ np.linalg.inv(h_jac @ p_cov_check @ h_jac.T + sensor_var)
# 3.2 Compute error state
delta_x_k = K_k @ (y_k - p_check)
# 3.3 Correct predicted state
p_hat = p_check + delta_x_k[0:3]
v_hat = v_check + delta_x_k[3:6]
q_hat = Quaternion( euler = delta_x_k[6:9] ).quat_mult_left(q_check)
# 3.4 Compute corrected covariance
p_cov_hat = ( np.identity(9) - K_k @ h_jac ) @ p_cov_check
delta_x_k = K_k @ (y_k - p_check)
return p_hat, v_hat, q_hat, p_cov_hat
#### 5. Main Filter Loop #######################################################################
################################################################################################
# Now that everything is set up, we can start taking in the sensor data and creating estimates
# for our state in a loop.
################################################################################################
for k in range(1, imu_f.data.shape[0]): # start at 1 b/c we have initial prediction from gt
delta_t = imu_f.t[k] - imu_f.t[k - 1]
# 1. Update state with IMU inputs
C_ns = Quaternion(*q_est[k-1]).to_mat()
C_ns_dot_f_km = C_ns @ imu_f.data[k-1]
p_est[k] = p_est[k-1] + delta_t*v_est[k-1] + delta_t**2*(C_ns_dot_f_km+g)/2
v_est[k] = v_est[k-1] + delta_t*(C_ns_dot_f_km+g)
q_est[k] = Quaternion(euler = delta_t * imu_w.data[k - 1]).quat_mult_right(q_est[k - 1])
# 1.1 Linearize the motion model and compute Jacobians
F_km = np.identity(9)
F_km[0:3, 3:6] = np.identity(3) * delta_t
F_km[3:6, 6:9] = -skew_symmetric_2(C_ns_dot_f_km)*delta_t
# 2. Propagate uncertainty
Q = np.eye(6)
Q[:3, :3] = var_imu_f * delta_t**2 * np.eye(3)
Q[3:, 3:] = var_imu_w * delta_t**2 * np.eye(3)
p_cov[k] = F_km @ p_cov[k-1] @ F_km.T + l_jac @ Q @ l_jac.T
# 3. Check availability of GNSS and LIDAR measurements
R_GNSS = np.identity(3) * var_gnss # covariance matrix related to GNSS
R_Lidar = np.identity(3) * var_lidar # covariance matrix related to Lidar
if lidar_i < lidar.t.shape[0] and lidar.t[lidar_i] <= imu_f.t[k-1]:
p_est[k], v_est[k], q_est[k], p_cov[k] = measurement_update(
R_Lidar , p_cov[k], lidar.data[lidar_i].T, p_est[k], v_est[k], q_est[k])
lidar_i += 1
if gnss_i < gnss.t.shape[0] and gnss.t[gnss_i] <= imu_f.t[k-1]:
p_est[k], v_est[k], q_est[k], p_cov[k] = measurement_update(
R_GNSS, p_cov[k], gnss.data[gnss_i].T, p_est[k], v_est[k], q_est[k])
gnss_i += 1
#### 6. Results and Analysis ###################################################################
################################################################################################
# Now that we have state estimates for all of our sensor data, let's plot the results. This plot
# will show the ground truth and the estimated trajectories on the same plot. Notice that the
# estimated trajectory continues past the ground truth. This is because we will be evaluating
# your estimated poses from the part of the trajectory where you don't have ground truth!
################################################################################################
est_traj_fig = plt.figure()
ax = est_traj_fig.add_subplot(111, projection='3d')
ax.plot(p_est[:,0], p_est[:,1], p_est[:,2], label='Estimated')
ax.plot(gt.p[:,0], gt.p[:,1], gt.p[:,2], label='Ground Truth')
ax.set_xlabel('Easting [m]')
ax.set_ylabel('Northing [m]')
ax.set_zlabel('Up [m]')
ax.set_title('Ground Truth and Estimated Trajectory')
ax.set_xlim(0, 200)
ax.set_ylim(0, 200)
ax.set_zlim(-2, 2)
ax.set_xticks([0, 50, 100, 150, 200])
ax.set_yticks([0, 50, 100, 150, 200])
ax.set_zticks([-2, -1, 0, 1, 2])
ax.legend(loc=(0.62,0.77))
ax.view_init(elev=45, azim=-50)
#plt.show()
################################################################################################
# We can also plot the error for each of the 6 DOF, with estimates for our uncertainty
# included. The error estimates are in blue, and the uncertainty bounds are red and dashed.
# The uncertainty bounds are +/- 3 standard deviations based on our uncertainty (covariance).
################################################################################################
error_fig, ax = plt.subplots(2, 3)
error_fig.suptitle('Error Plots')
num_gt = gt.p.shape[0]
p_est_euler = []
p_cov_euler_std = []
# Convert estimated quaternions to euler angles
for i in range(len(q_est)):
qc = Quaternion(*q_est[i, :])
p_est_euler.append(qc.to_euler())
# First-order approximation of RPY covariance
J = rpy_jacobian_axis_angle(qc.to_axis_angle())
p_cov_euler_std.append(np.sqrt(np.diagonal(J @ p_cov[i, 6:, 6:] @ J.T)))
p_est_euler = np.array(p_est_euler)
p_cov_euler_std = np.array(p_cov_euler_std)
# Get uncertainty estimates from P matrix
p_cov_std = np.sqrt(np.diagonal(p_cov[:, :6, :6], axis1=1, axis2=2))
titles = ['Easting', 'Northing', 'Up', 'Roll', 'Pitch', 'Yaw']
for i in range(3):
ax[0, i].plot(range(num_gt), gt.p[:, i] - p_est[:num_gt, i])
ax[0, i].plot(range(num_gt), 3 * p_cov_std[:num_gt, i], 'r--')
ax[0, i].plot(range(num_gt), -3 * p_cov_std[:num_gt, i], 'r--')
ax[0, i].set_title(titles[i])
ax[0,0].set_ylabel('Meters')
for i in range(3):
ax[1, i].plot(range(num_gt), \
angle_normalize(gt.r[:, i] - p_est_euler[:num_gt, i]))
ax[1, i].plot(range(num_gt), 3 * p_cov_euler_std[:num_gt, i], 'r--')
ax[1, i].plot(range(num_gt), -3 * p_cov_euler_std[:num_gt, i], 'r--')
ax[1, i].set_title(titles[i+3])
ax[1,0].set_ylabel('Radians')
#plt.show()
#### 7. Submission #############################################################################
################################################################################################
# To prepare results for submission, Uncomment the
# corresponding lines to prepare a file.
################################################################################################
#Pt.1 submission
#p1_indices = [9000, 9400, 9800, 10200, 10600]
#p1_str = ''
#for val in p1_indices:
# for i in range(3):
# p1_str += '%.3f ' % (p_est[val, i])
#with open('pt1_submission.txt', 'w') as file:
# file.write(p1_str)
# Pt. 2 submission
p2_indices = [9000, 9400, 9800, 10200, 10600]
p2_str = ''
for val in p2_indices:
for i in range(3):
p2_str += '%.3f ' % (p_est[val, i])
with open('pt2_submission.txt', 'w') as file:
file.write(p2_str)
# Pt. 3 submission
#p3_indices = [6800, 7600, 8400, 9200, 10000]
#p3_str = ''
#for val in p3_indices:
# for i in range(3):
# p3_str += '%.3f ' % (p_est[val, i])
#with open('pt3_submission.txt', 'w') as file:
# file.write(p3_str)