forked from Rhett98/dynamic_slam
-
Notifications
You must be signed in to change notification settings - Fork 0
/
dynamic_backend_optmization.py
344 lines (305 loc) · 13.7 KB
/
dynamic_backend_optmization.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
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
from functools import partial
from typing import List, Optional
import numpy as np
import gtsam
import gtsam.utils.plot as gtsam_plot
import matplotlib.pyplot as plt
from kitti_tracking_reader import tData, tracking_dataset, seq_length
def skew_symmetric(w):
return np.array([
[0, -w[2], w[1]],
[w[2], 0, -w[0]],
[-w[1], w[0], 0]])
def Btw3Factor(poseKey1, poseKey2, poseKey3, noise_model):
def error_func(this: gtsam.CustomFactor, v: gtsam.Values, H: Optional[List[np.ndarray]]) -> float:
"""
Error function that mimics a Between3Factor
:param this: reference to the current CustomFactor being evaluated
:param v: Values object
:param H: list of references to the Jacobian arrays
:return: the non-linear error
"""
key0 = this.keys()[0]
key1 = this.keys()[1]
key2 = this.keys()[2]
p1, p2, p3 = v.atPose3(key0), v.atPose3(key1), v.atPose3(key2)
error = gtsam.Pose3.Logmap(p1.inverse() * p2 * p3.inverse())
J = np.zeros((6, 6))
J[:3, :3] = skew_symmetric(error[:3])
J[:3, 3:] = skew_symmetric(error[3:])
J[3:, 3:] = skew_symmetric(error[:3])
J = J * 0.5 + np.eye(6)
if H is not None:
H[0] = (-1) * J * ((p2 * p3.inverse()).inverse()).AdjointMap()
H[1] = J * ((p2 * p3.inverse()).inverse()).AdjointMap()
H[2] = (-1) * J
return error
return gtsam.CustomFactor(noise_model, gtsam.KeyVector([poseKey1, poseKey2, poseKey3]), error_func)
class backend_optimization():
def __init__(self):
self.graph_init()
self.noise_init()
self.odom_prior_init()
def noise_init(self):
# 设置噪声
egoP_egoP = 1e-4
egoP_objP = 1e-2
objP_objP_chgP = 1e-2
chgP_chgP = 0.1
self.prior_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([1e-6,1e-6,
1e-6,1e-6,
1e-6,1e-6]))
self.odom_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([egoP_egoP,egoP_egoP,
egoP_egoP,egoP_egoP,
egoP_egoP,egoP_egoP]))
self.obj_ego_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([egoP_objP,egoP_objP,
egoP_objP,egoP_objP,
egoP_objP,egoP_objP]))
self.frame_motion_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([objP_objP_chgP,objP_objP_chgP,
objP_objP_chgP,objP_objP_chgP,
objP_objP_chgP,objP_objP_chgP]))
self.smoothing_noise = gtsam.noiseModel.Diagonal.Sigmas(np.array([chgP_chgP,chgP_chgP,
chgP_chgP,chgP_chgP,
chgP_chgP,chgP_chgP]))
def graph_init(self):
self.graph = gtsam.NonlinearFactorGraph()
self.initial_estimate = gtsam.Values()
self.result = gtsam.Values()
self.parameters = gtsam.ISAM2Params()
self.parameters.setRelinearizeThreshold(0.1)
self.parameters.relinearizeSkip = 1
self.isam2 = gtsam.ISAM2(self.parameters)
# 因子序号
self.f_id = 0
# 帧序号
self.frame_index = 0
# 里程计因子序号
self.odom_id = [0]
self.obj_ids = {}
self.pose_change_ids = {}
self.ego_pose = []
self.obj_traj = {}
def add_keyframe(self):
a=0
def odom_prior_init(self):
self.ego_pose.append(gtsam.Pose3(np.eye(4)))
self.graph.add(gtsam.PriorFactorPose3(self.f_id, self.ego_pose[-1], self.prior_noise))
self.initial_estimate.insert(self.f_id, self.ego_pose[-1])
self.f_id+=1
def add_odom_factor(self):
# 里程计运动因子
self.graph.add(gtsam.BetweenFactorPose3(self.odom_id[-1], self.f_id, self.ego_pose[-2].inverse()*self.ego_pose[-1], self.odom_noise))
# 里程计位姿
self.initial_estimate.insert(self.f_id, self.ego_pose[-1])
self.odom_id.append(self.f_id)
self.f_id+=1
def add_dyobj_factor(self, new_obj, history_obj):
# 新加入obj
for k, v in new_obj.items():
# 动态目标与里程计相对运动因子
self.graph.add(gtsam.BetweenFactorPose3(self.odom_id[-1], self.f_id, self.ego_pose[-1].inverse()*v, self.obj_ego_noise))
self.initial_estimate.insert(self.f_id, v)
self.obj_ids[k]=[self.f_id]
self.f_id+=1
# 已存在历史obj
for k, v in history_obj.items():
self.graph.add(gtsam.BetweenFactorPose3(self.odom_id[-1], self.f_id, self.ego_pose[-1].inverse()*v, self.obj_ego_noise))
self.initial_estimate.insert(self.f_id, v)
# 记录obj节点id
self.obj_ids[k].append(self.f_id)
self.f_id+=1
# pose_chage_node
self.initial_estimate.insert(self.f_id, self.obj_traj[k][-2].inverse()*v)
# 记录pose_change节点id
if k in self.pose_change_ids.keys():
self.pose_change_ids[k].append(self.f_id)
else:
self.pose_change_ids[k]=[self.f_id]
self.f_id+=1
# 帧间动态目标相对运动因子
self.graph.add(Btw3Factor(self.obj_ids[k][-2], self.obj_ids[k][-1], self.pose_change_ids[k][-1], self.frame_motion_noise))
# 平滑运动因子
if len(self.pose_change_ids[k])>1:
self.graph.add(gtsam.BetweenFactorPose3(self.pose_change_ids[k][-2], self.pose_change_ids[k][-1], gtsam.Pose3(np.eye(4)), self.smoothing_noise))
def load_frame_tracking_data(self, ego_pose:gtsam.Pose3, data_list:List[tData]):
new_obj=dict()
history_obj = dict()
for obj_data in data_list:
obj_pose = gtsam.Pose3(obj_data.T)
global_obj_pose = ego_pose * obj_pose
if obj_data.track_id in self.obj_traj.keys():
self.obj_traj[obj_data.track_id].append(global_obj_pose)
history_obj[obj_data.track_id] = global_obj_pose
else:
self.obj_traj[obj_data.track_id] = [global_obj_pose]
new_obj[obj_data.track_id] = global_obj_pose
return new_obj, history_obj
def update_frame_message(self, ego_pose, dyobj_data):
# print(self.frame_index)
# 更新当前帧里程计位姿
self.ego_pose.append(ego_pose)
# 加载当前帧数据
new_obj, history_obj = self.load_frame_tracking_data(ego_pose, dyobj_data)
# 添加新因子
self.add_odom_factor()
self.add_dyobj_factor(new_obj, history_obj)
# 因子图优化
self.isam2.update(self.graph, self.initial_estimate)
self.graph.resize(0)
self.initial_estimate.clear()
current_estimate = self.isam2.calculateEstimate()
# 优化后数据更新到self.ego_pose与self.obj_traj
# 更新当前帧序号
self.frame_index+=1
return current_estimate
def aug_matrix():
anglex = 0#np.clip(0.01 * np.random.randn(), -0.02, 0.02).astype(float) * np.pi / 4.0
angley = 0#np.clip(0.01 * np.random.randn(), -0.02, 0.02).astype(float) * np.pi / 4.0
anglez = np.clip(0.05 * np.random.randn(), -0.1, 0.1).astype(float) * np.pi / 4.0
cosx = np.cos(anglex)
cosy = np.cos(angley)
cosz = np.cos(anglez)
sinx = np.sin(anglex)
siny = np.sin(angley)
sinz = np.sin(anglez)
Rx = np.array([[1, 0, 0],
[0, cosx, -sinx],
[0, sinx, cosx]])
Ry = np.array([[cosy, 0, siny],
[0, 1, 0],
[-siny, 0, cosy]])
Rz = np.array([[cosz, -sinz, 0],
[sinz, cosz, 0],
[0, 0, 1]])
scale = np.diag(np.random.uniform(1.00, 1.00, 3).astype(float))
R_trans = Rx.dot(Ry).dot(Rz).dot(scale.T)
xx = np.clip(0.5*np.random.rand()-0.25, -0.5, 0.5).astype(float)
yy = np.clip(0.2*np.random.rand()-0.1, -0.2, 0.2).astype(float)
zz = 0#np.clip(0.05 * np.random.randn(), -0.15, 0.15).astype(float)
add_xyz = np.array([[xx], [yy], [zz]])
T_trans = np.concatenate([R_trans, add_xyz], axis=-1)
filler = np.array([0.0, 0.0, 0.0, 1.0])
filler = np.expand_dims(filler, axis=0) ##1*4
T_trans = np.concatenate([T_trans, filler], axis=0) # 4*4
return T_trans
if __name__ == '__main__':
import os
eval_list = [4,7,8,9,15,18,19]
local_graph = backend_optimization()
seq_index = 18
dataset = tracking_dataset("/home/yu/Resp/dataset/data_tracking_velodyne/training",seq_index,"experiment/odometry_EVAL_KITTI_2024-01-11_17-21")
fig = plt.figure(0)
if not fig.axes:
axes = fig.add_subplot(projection='3d')
else:
axes = fig.axes[0]
plt.cla()
# print(gtsam.Pose3(aug_matrix()))
######### 原始obj轨迹 ########
origin_obj_traj = dict()
first = True
frame_ego_pose = gtsam.Pose3(gtsam.Rot3.RzRyRx(0, 0, 0), gtsam.Point3(0, 0, 0))
for frame in range(seq_length[seq_index]):
if first:
frame_ego_pose = gtsam.Pose3(dataset.get_pose(frame))
frame_obj_data = dataset.get_label(frame)
current_estimate = local_graph.update_frame_message(frame_ego_pose, frame_obj_data)
# 保存原始obj轨迹
for obj_data in frame_obj_data:
obj_pose = gtsam.Pose3(obj_data.T)
global_obj_pose = frame_ego_pose * obj_pose
if obj_data.track_id in origin_obj_traj.keys():
origin_obj_traj[obj_data.track_id].append(global_obj_pose)
else:
origin_obj_traj[obj_data.track_id] = [global_obj_pose]
first = False
else:
if frame_ego_pose.range(gtsam.Pose3(dataset.get_pose(frame)))>0:
# print(frame_ego_pose.range(gtsam.Pose3(dataset.get_pose(frame))))
frame_ego_pose = gtsam.Pose3(dataset.get_pose(frame))#*gtsam.Pose3(aug_matrix())
frame_obj_data = dataset.get_label(frame)
current_estimate = local_graph.update_frame_message(frame_ego_pose, frame_obj_data)
# 保存原始obj轨迹
for obj_data in frame_obj_data:
obj_pose = gtsam.Pose3(obj_data.T)
global_obj_pose = frame_ego_pose * obj_pose
if obj_data.track_id in origin_obj_traj.keys():
origin_obj_traj[obj_data.track_id].append(global_obj_pose)
else:
origin_obj_traj[obj_data.track_id] = [global_obj_pose]
# if frame==150:
# break
# ######## 绘制原始动态目标轨迹 ########
# obj_value = gtsam.Values()
# for id, traj in origin_obj_traj.items():
# obj_value.clear()
# flag = 0
# for t in traj:
# obj_value.insert(flag, t.translation())
# flag+=1
# gtsam_plot.plot_3d_points(0, obj_value, 'g*')
# ######### 优化后动态目标轨迹 ########
# obj_traj_value = gtsam.Values()
# for i in local_graph.obj_ids.keys():
# obj_traj_value.clear()
# f = 0
# for vv in local_graph.obj_ids[i]:
# obj_traj_value.insert(f, current_estimate.atPose3(vv).translation())
# f+=1
# gtsam_plot.plot_3d_points(0, obj_traj_value,'r+')
######## 得到优化后的里程计轨迹 ########
plot_value = gtsam.Values()
i=0
for v in local_graph.odom_id:
plot_value.insert(i, current_estimate.atPose3(v))
T_final = current_estimate.atPose3(v).matrix()
if i==0:
T = T_final[:3, :]
T = T.reshape(1, 1, 12)
else:
T_current = T_final[:3, :]
T_current = T_current.reshape(1, 1, 12)
T = np.append(T, T_current, axis=0)
i+=1
# gtsam_plot.plot_trajectory(0,plot_value)
####### 保存优化后的里程计轨迹到txt #########
T_list = T.reshape(-1, 12)
fname_txt = os.path.join('test_data/'+str(seq_index)+'_optimazation_noise.txt')
np.savetxt(fname_txt, T_list)
####### 绘制原始里程计轨迹 ########
origin_odom_value = gtsam.Values()
f = 0
for vv in local_graph.ego_pose:
origin_odom_value.insert(f, vv)
f+=1
# gtsam_plot.plot_trajectory(0, origin_odom_value,5)
####### 保存优化后的里程计轨迹到txt #########
print(len(local_graph.ego_pose))
i=0
for tj in local_graph.ego_pose:
T_final = tj.matrix()
if i==0:
Tt = T_final[:3, :]
Tt = Tt.reshape(1, 1, 12)
else:
T_current = T_final[:3, :]
T_current = T_current.reshape(1, 1, 12)
Tt = np.append(Tt, T_current, axis=0)
i+=1
Tt_list = Tt.reshape(-1, 12)
fname_txt = os.path.join('test_data/'+str(seq_index)+'_optimazation_noise_origin.txt')
np.savetxt(fname_txt, Tt_list)
### 绘制动态目标的速度(帧间运动距离) ###
obj_speed_value = {}
f = 0
for i in local_graph.pose_change_ids.keys():
for vv in local_graph.pose_change_ids[i]:
if f in obj_speed_value.keys():
obj_speed_value[f].append(current_estimate.atPose3(vv).range(gtsam.Pose3(np.eye(4))))
else:
obj_speed_value[f] = [current_estimate.atPose3(vv).range(gtsam.Pose3(np.eye(4)))]
f+=1
# print(obj_speed_value)
# plt.axis('equal')
# plt.ioff()
# plt.show()