-
Notifications
You must be signed in to change notification settings - Fork 35
/
Copy pathevaluate_pose.py
260 lines (198 loc) · 9.75 KB
/
evaluate_pose.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
# Copyright Niantic 2019. Patent Pending. All rights reserved.
#
# This software is licensed under the terms of the Monodepth2 licence
# which allows for non-commercial use only, the full terms of which are made
# available in the LICENSE file.
from __future__ import absolute_import, division, print_function
import os
import numpy as np
import torch
from torch.utils.data import DataLoader
from layers import transformation_from_parameters
from utils import readlines
from options import MonodepthOptions
from datasets import KITTIOdomDataset
import networks
from maskrcnn_benchmark.config import cfg
# from https://github.com/tinghuiz/SfMLearner
def dump_xyz(source_to_target_transformations):
xyzs = []
cam_to_world = np.eye(4)
xyzs.append(cam_to_world[:3, 3])
for source_to_target_transformation in source_to_target_transformations:
cam_to_world = np.dot(cam_to_world, source_to_target_transformation)
xyzs.append(cam_to_world[:3, 3])
return xyzs
# from https://github.com/tinghuiz/SfMLearner
def compute_ate(gtruth_xyz, pred_xyz_o):
# Make sure that the first matched frames align (no need for rotational alignment as
# all the predicted/ground-truth snippets have been converted to use the same coordinate
# system with the first frame of the snippet being the origin).
offset = gtruth_xyz[0] - pred_xyz_o[0]
pred_xyz = pred_xyz_o + offset[None, :]
# Optimize the scaling factor
scale = np.sum(gtruth_xyz * pred_xyz) / np.sum(pred_xyz ** 2)
alignment_error = pred_xyz * scale - gtruth_xyz
rmse = np.sqrt(np.sum(alignment_error ** 2)) / gtruth_xyz.shape[0]
return rmse
def evaluate(opt):
"""Evaluate odometry on the KITTI dataset
"""
assert os.path.isdir(opt.load_weights_folder), \
"Cannot find a folder at {}".format(opt.load_weights_folder)
assert opt.eval_split == "odom_9" or opt.eval_split == "odom_10", \
"eval_split should be either odom_9 or odom_10"
sequence_id = int(opt.eval_split.split("_")[1])
opt.batch_size = 1
filenames = readlines(
os.path.join(os.path.dirname(__file__), "splits", "odom",
"test_files_{:02d}.txt".format(sequence_id)))
dataset = KITTIOdomDataset(opt.data_path, filenames, opt.height, opt.width,
[0, -1, 1], 4, is_train=False, img_ext='.png')
dataloader = DataLoader(dataset, opt.batch_size, shuffle=False,
num_workers=opt.num_workers, pin_memory=True, drop_last=False)
# pose_encoder_path = os.path.join(opt.load_weights_folder, "pose_encoder.pth")
pose_decoder_path = os.path.join(opt.load_weights_folder, "pose.pth")
config_file = "./configs/e2e_mask_rcnn_R_50_FPN_1x.yaml"
cfg.merge_from_file(config_file)
cfg.freeze()
maskrcnn_path = "./e2e_mask_rcnn_R_50_FPN_1x.pth"
pose_encoder = networks.ResnetEncoder(cfg, maskrcnn_path)
# pose_encoder = networks.ResnetEncoder(opt.num_layers, False, 2)
# pose_encoder.load_state_dict(torch.load(pose_encoder_path))
pose_decoder = networks.PoseDecoder(len(opt.frame_ids))
pose_decoder.load_state_dict(torch.load(pose_decoder_path))
pose_encoder.cuda()
pose_encoder.eval()
pose_decoder.cuda()
pose_decoder.eval()
pred_poses = []
print("-> Computing pose predictions")
# opt.frame_ids = [0, 1] # pose network only takes two frames as input
ii = 0
with torch.no_grad():
for inputs in dataloader:
for key, ipt in inputs.items():
inputs[key] = ipt.cuda()
all_color_aug = torch.cat([inputs[("color_aug", i, 0)] for i in opt.frame_ids])
all_features = pose_encoder(all_color_aug)
all_features = [torch.split(f, opt.batch_size) for f in all_features]
features = {}
for i, k in enumerate(opt.frame_ids):
features[k] = [f[i] for f in all_features]
pose_inputs = [features[i] for i in opt.frame_ids if i != "s"]
axisangle, translation = pose_decoder(pose_inputs)
if ii == 0:
pred_poses.append(
transformation_from_parameters(axisangle[:, 0], translation[:, 0], True).cpu().numpy())
pred_poses.append(
transformation_from_parameters(axisangle[:, 1], translation[:, 1]).cpu().numpy())
if ii % opt.log_frequency == 0:
print("{:04d}-th image processing".format(ii))
ii += 1
# pred_poses.append(
# transformation_from_parameters(axisangle[:, 1], translation[:, 1]).cpu().numpy())
pred_poses = np.concatenate(pred_poses)
gt_poses_path = os.path.join(opt.data_path, "poses", "{:02d}.txt".format(sequence_id))
gt_global_poses = np.loadtxt(gt_poses_path).reshape(-1, 3, 4)
gt_global_poses = np.concatenate(
(gt_global_poses, np.zeros((gt_global_poses.shape[0], 1, 4))), 1)
gt_global_poses[:, 3, 3] = 1
gt_xyzs = gt_global_poses[:, :3, 3]
gt_local_poses = []
for i in range(1, len(gt_global_poses)):
gt_local_poses.append(
np.linalg.inv(np.dot(np.linalg.inv(gt_global_poses[i - 1]), gt_global_poses[i])))
ates = []
num_frames = gt_xyzs.shape[0]
track_length = 3
for i in range(0, num_frames - 1):
local_xyzs = np.array(dump_xyz(pred_poses[i:i + track_length - 1]))
gt_local_xyzs = np.array(dump_xyz(gt_local_poses[i:i + track_length - 1]))
ates.append(compute_ate(gt_local_xyzs, local_xyzs))
'''
for i in range(0, num_frames - 2):
local_xyzs = np.array(dump_xyz(pred_poses[i:i + track_length - 1]))
gt_local_xyzs = np.array(dump_xyz(gt_local_poses[i + 1:i + track_length]))
ates.append(compute_ate(gt_local_xyzs, local_xyzs))
'''
print("\n Trajectory error: {:0.3f}, std: {:0.3f}\n".format(np.mean(ates), np.std(ates)))
save_path = os.path.join(opt.load_weights_folder, "poses.npy")
np.save(save_path, pred_poses)
print("-> Predictions saved to", save_path)
if __name__ == "__main__":
options = MonodepthOptions()
evaluate(options.parse())
'''
opt = options.parse()
sequence_id = int(opt.eval_split.split("_")[1])
filenames = readlines(
os.path.join(os.path.dirname(__file__), "splits", "odom",
"test_files_{:02d}.txt".format(sequence_id)))
dataset = KITTIOdomDataset(opt.data_path, filenames, opt.height, opt.width,
[0, -1, 1], 4, is_train=False, img_ext='.png')
dataloader = DataLoader(dataset, opt.batch_size, shuffle=False,
num_workers=opt.num_workers, pin_memory=True, drop_last=False)
# pose_encoder_path = os.path.join(opt.load_weights_folder, "pose_encoder.pth")
pose_decoder_path = os.path.join(opt.load_weights_folder, "pose.pth")
config_file = "./configs/e2e_mask_rcnn_R_50_FPN_1x.yaml"
cfg.merge_from_file(config_file)
cfg.freeze()
maskrcnn_path = "./e2e_mask_rcnn_R_50_FPN_1x.pth"
pose_encoder = networks.ResnetEncoder(cfg, maskrcnn_path)
# pose_encoder = networks.ResnetEncoder(opt.num_layers, False, 2)
# pose_encoder.load_state_dict(torch.load(pose_encoder_path))
pose_decoder = networks.PoseDecoder(len(opt.frame_ids))
pose_decoder.load_state_dict(torch.load(pose_decoder_path))
pose_encoder.cuda()
pose_encoder.eval()
pose_decoder.cuda()
pose_decoder.eval()
pred_poses = []
print("-> Computing pose predictions")
# opt.frame_ids = [0, 1] # pose network only takes two frames as input
with torch.no_grad():
for inputs in dataloader:
for key, ipt in inputs.items():
inputs[key] = ipt.cuda()
all_color_aug = torch.cat([inputs[("color_aug", i, 0)] for i in opt.frame_ids])
all_features = pose_encoder(all_color_aug)
all_features = [torch.split(f, opt.batch_size) for f in all_features]
features = {}
for i, k in enumerate(opt.frame_ids):
features[k] = [f[i] for f in all_features]
pose_inputs = [features[i] for i in opt.frame_ids if i != "s"]
axisangle, translation = pose_decoder(pose_inputs)
pred_poses.append(
# transformation_from_parameters(axisangle[:, 0], translation[:, 0]).cpu().numpy())
transformation_from_parameters(axisangle[:, 1], translation[:, 1]).cpu().numpy())
# break
pred_poses = np.concatenate(pred_poses)
gt_poses_path = os.path.join(opt.data_path, "poses", "{:02d}.txt".format(sequence_id))
gt_global_poses = np.loadtxt(gt_poses_path).reshape(-1, 3, 4)
gt_global_poses = np.concatenate(
(gt_global_poses, np.zeros((gt_global_poses.shape[0], 1, 4))), 1)
gt_global_poses[:, 3, 3] = 1
gt_xyzs = gt_global_poses[:, :3, 3]
gt_local_poses = []
for i in range(1, len(gt_global_poses)):
gt_local_poses.append(
np.linalg.inv(np.dot(np.linalg.inv(gt_global_poses[i - 1]), gt_global_poses[i])))
ates = []
num_frames = gt_xyzs.shape[0]
track_length = 5
'''
# for i in range(0, num_frames - 1):
# local_xyzs = np.array(dump_xyz(pred_poses[i:i + track_length - 1]))
# gt_local_xyzs = np.array(dump_xyz(gt_local_poses[i:i + track_length - 1]))
# ates.append(compute_ate(gt_local_xyzs, local_xyzs))
'''
for i in range(0, num_frames - 2):
local_xyzs = np.array(dump_xyz(pred_poses[i:i + track_length - 1]))
gt_local_xyzs = np.array(dump_xyz(gt_local_poses[i + 1:i + track_length]))
ates.append(compute_ate(gt_local_xyzs, local_xyzs))
print("\n Trajectory error: {:0.3f}, std: {:0.3f}\n".format(np.mean(ates), np.std(ates)))
save_path = os.path.join(opt.load_weights_folder, "poses.npy")
np.save(save_path, pred_poses)
print("-> Predictions saved to", save_path)
'''