-
Notifications
You must be signed in to change notification settings - Fork 1
/
utils.py
416 lines (362 loc) · 13.3 KB
/
utils.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
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
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
# -------------------------------------------------------------------
# Copyright (C) 2020 Università degli studi di Milano-Bicocca, iralab
# Author: Daniele Cattaneo ([email protected])
# Released under Creative Commons
# Attribution-NonCommercial-ShareAlike 4.0 International License.
# http://creativecommons.org/licenses/by-nc-sa/4.0/
# -------------------------------------------------------------------
# Modified Author: Xudong Lv
# based on github.com/cattaneod/CMRNet/blob/master/utils.py
import math
import mathutils
import numpy as np
import torch
import torch.nn.functional as F
from matplotlib import cm
from torch.utils.data.dataloader import default_collate
def rotate_points(PC, R, T=None, inverse=True):
if T is not None:
R = R.to_matrix()
R.resize_4x4()
T = mathutils.Matrix.Translation(T)
RT = T*R
else:
RT=R.copy()
if inverse:
RT.invert_safe()
RT = torch.tensor(RT, device=PC.device, dtype=torch.float)
if PC.shape[0] == 4:
PC = torch.mm(RT, PC)
elif PC.shape[1] == 4:
PC = torch.mm(RT, PC.t())
PC = PC.t()
else:
raise TypeError("Point cloud must have shape [Nx4] or [4xN] (homogeneous coordinates)")
return PC
def rotate_points_torch(PC, R, T=None, inverse=True):
if T is not None:
R = quat2mat(R)
T = tvector2mat(T)
RT = torch.mm(T, R)
else:
RT = R.clone()
if inverse:
RT = RT.inverse()
if PC.shape[0] == 4:
PC = torch.mm(RT, PC)
elif PC.shape[1] == 4:
PC = torch.mm(RT, PC.t())
PC = PC.t()
else:
raise TypeError("Point cloud must have shape [Nx4] or [4xN] (homogeneous coordinates)")
return PC
def rotate_points_torch_batch(PC, R, T=None, inverse=True):
if T is not None:
R = quat2mat_batch(R)
T = tvector2mat_batch(T)
RT = torch.bmm(T, R)
else:
RT = R.clone()
if inverse:
RT = inverse_batch(RT)
if PC.shape[1] == 4:
PC = torch.bmm(RT, PC)
elif PC.shape[2] == 4:
PC = torch.bmm(RT, PC.permute(0,2,1))
PC = PC.t()
else:
raise TypeError("Point cloud must have shape [Nx4] or [4xN] (homogeneous coordinates)")
return PC
def rotate_forward_batch(PC, R, T=None):
"""
Transform the point cloud PC, so to have the points 'as seen from' the new
pose T*R
Args:
PC (torch.Tensor): Point Cloud to be transformed, shape [4xN] or [Nx4]
R (torch.Tensor/mathutils.Euler): can be either:
* (mathutils.Euler) euler angles of the rotation part, in this case T cannot be None
* (torch.Tensor shape [4]) quaternion representation of the rotation part, in this case T cannot be None
* (mathutils.Matrix shape [4x4]) Rotation matrix,
in this case it should contains the translation part, and T should be None
* (torch.Tensor shape [4x4]) Rotation matrix,
in this case it should contains the translation part, and T should be None
T (torch.Tensor/mathutils.Vector): Translation of the new pose, shape [3], or None (depending on R)
Returns:
torch.Tensor: Transformed Point Cloud 'as seen from' pose T*R
"""
if isinstance(R, torch.Tensor):
return rotate_points_torch_batch(PC, R, T, inverse=True)
else:
raise TypeError("Only tensor support")
def rotate_back_batch(PC_ROTATED, R, T=None):
"""
Inverse of :func:`~utils.rotate_forward`.
"""
if isinstance(R, torch.Tensor):
return rotate_points_torch_batch(PC_ROTATED, R, T, inverse=False)
else:
return rotate_points(PC_ROTATED, R, T, inverse=False)
def rotate_forward(PC, R, T=None):
"""
Transform the point cloud PC, so to have the points 'as seen from' the new
pose T*R
Args:
PC (torch.Tensor): Point Cloud to be transformed, shape [4xN] or [Nx4]
R (torch.Tensor/mathutils.Euler): can be either:
* (mathutils.Euler) euler angles of the rotation part, in this case T cannot be None
* (torch.Tensor shape [4]) quaternion representation of the rotation part, in this case T cannot be None
* (mathutils.Matrix shape [4x4]) Rotation matrix,
in this case it should contains the translation part, and T should be None
* (torch.Tensor shape [4x4]) Rotation matrix,
in this case it should contains the translation part, and T should be None
T (torch.Tensor/mathutils.Vector): Translation of the new pose, shape [3], or None (depending on R)
Returns:
torch.Tensor: Transformed Point Cloud 'as seen from' pose T*R
"""
if isinstance(R, torch.Tensor):
return rotate_points_torch(PC, R, T, inverse=True)
else:
return rotate_points(PC, R, T, inverse=True)
def rotate_back(PC_ROTATED, R, T=None):
"""
Inverse of :func:`~utils.rotate_forward`.
"""
if isinstance(R, torch.Tensor):
return rotate_points_torch(PC_ROTATED, R, T, inverse=False)
else:
return rotate_points(PC_ROTATED, R, T, inverse=False)
def invert_pose(R, T):
"""
Given the 'sampled pose' (aka H_init), we want CMRNet to predict inv(H_init).
inv(T*R) will be used as ground truth for the network.
Args:
R (mathutils.Euler): Rotation of 'sampled pose'
T (mathutils.Vector): Translation of 'sampled pose'
Returns:
(R_GT, T_GT) = (mathutils.Quaternion, mathutils.Vector)
"""
R = R.to_matrix()
R.resize_4x4()
T = mathutils.Matrix.Translation(T)
RT = T * R
RT.invert_safe()
T_GT, R_GT, _ = RT.decompose()
return R_GT.normalized(), T_GT
def merge_inputs(queries):
point_clouds = []
imgs = []
reflectances = []
pc_rotated = []
shape_pad = []
real_shape = []
depth_gt = []
ignore_keys = ['point_cloud', 'rgb', 'reflectance', 'pc_rotated', 'shape_pad', 'real_shape', 'depth_gt']
returns = {key: default_collate([d[key] for d in queries]) for key in queries[0]
if key not in ignore_keys}
for input in queries:
point_clouds.append(input['point_cloud'])
imgs.append(input['rgb'])
if 'pc_rotated' in input:
pc_rotated.append(input['pc_rotated'])
if 'shape_pad' in input:
shape_pad.append(input['shape_pad'])
if 'real_shape' in input:
real_shape.append(input['real_shape'])
if 'depth_gt' in input:
depth_gt.append(input['depth_gt'])
if 'reflectance' in input:
reflectances.append(input['reflectance'])
returns['point_cloud'] = point_clouds
returns['rgb'] = imgs
if len(pc_rotated) > 0:
returns['pc_rotated'] = pc_rotated
if len(shape_pad) > 0:
returns['shape_pad'] = shape_pad
if len(real_shape) > 0:
returns['real_shape'] = real_shape
if len(depth_gt) > 0:
returns['depth_gt'] = depth_gt
if len(reflectances) > 0:
returns['reflectance'] = reflectances
return returns
def quaternion_from_matrix(matrix):
"""
Convert a rotation matrix to quaternion.
Args:
matrix (torch.Tensor): [4x4] transformation matrix or [3,3] rotation matrix.
Returns:
torch.Tensor: shape [4], normalized quaternion
"""
if matrix.shape == (4, 4):
R = matrix[:-1, :-1]
elif matrix.shape == (3, 3):
R = matrix
else:
raise TypeError("Not a valid rotation matrix")
tr = R[0, 0] + R[1, 1] + R[2, 2]
q = torch.zeros(4, device=matrix.device)
if tr > 0.:
S = (tr+1.0).sqrt() * 2
q[0] = 0.25 * S
q[1] = (R[2, 1] - R[1, 2]) / S
q[2] = (R[0, 2] - R[2, 0]) / S
q[3] = (R[1, 0] - R[0, 1]) / S
elif R[0, 0] > R[1, 1] and R[0, 0] > R[2, 2]:
S = (1.0 + R[0, 0] - R[1, 1] - R[2, 2]).sqrt() * 2
q[0] = (R[2, 1] - R[1, 2]) / S
q[1] = 0.25 * S
q[2] = (R[0, 1] + R[1, 0]) / S
q[3] = (R[0, 2] + R[2, 0]) / S
elif R[1, 1] > R[2, 2]:
S = (1.0 + R[1, 1] - R[0, 0] - R[2, 2]).sqrt() * 2
q[0] = (R[0, 2] - R[2, 0]) / S
q[1] = (R[0, 1] + R[1, 0]) / S
q[2] = 0.25 * S
q[3] = (R[1, 2] + R[2, 1]) / S
else:
S = (1.0 + R[2, 2] - R[0, 0] - R[1, 1]).sqrt() * 2
q[0] = (R[1, 0] - R[0, 1]) / S
q[1] = (R[0, 2] + R[2, 0]) / S
q[2] = (R[1, 2] + R[2, 1]) / S
q[3] = 0.25 * S
return q / q.norm()
def quatmultiply(q, r):
"""
Multiply two quaternions
Args:
q (torch.Tensor/nd.ndarray): shape=[4], first quaternion
r (torch.Tensor/nd.ndarray): shape=[4], second quaternion
Returns:
torch.Tensor: shape=[4], normalized quaternion q*r
"""
t = torch.zeros(4, device=q.device)
t[0] = r[0] * q[0] - r[1] * q[1] - r[2] * q[2] - r[3] * q[3]
t[1] = r[0] * q[1] + r[1] * q[0] - r[2] * q[3] + r[3] * q[2]
t[2] = r[0] * q[2] + r[1] * q[3] + r[2] * q[0] - r[3] * q[1]
t[3] = r[0] * q[3] - r[1] * q[2] + r[2] * q[1] + r[3] * q[0]
return t / t.norm()
def quat2mat(q):
"""
Convert a quaternion to a rotation matrix
Args:
q (torch.Tensor): shape [4], input quaternion
Returns:
torch.Tensor: [4x4] homogeneous rotation matrix
"""
assert q.shape == torch.Size([4]), "Not a valid quaternion"
if q.norm() != 1.:
q = q / q.norm()
mat = torch.zeros((4, 4), device=q.device)
mat[0, 0] = 1 - 2*q[2]**2 - 2*q[3]**2
mat[0, 1] = 2*q[1]*q[2] - 2*q[3]*q[0]
mat[0, 2] = 2*q[1]*q[3] + 2*q[2]*q[0]
mat[1, 0] = 2*q[1]*q[2] + 2*q[3]*q[0]
mat[1, 1] = 1 - 2*q[1]**2 - 2*q[3]**2
mat[1, 2] = 2*q[2]*q[3] - 2*q[1]*q[0]
mat[2, 0] = 2*q[1]*q[3] - 2*q[2]*q[0]
mat[2, 1] = 2*q[2]*q[3] + 2*q[1]*q[0]
mat[2, 2] = 1 - 2*q[1]**2 - 2*q[2]**2
mat[3, 3] = 1.
return mat
def quat2mat_batch(q):
"""
Convert a quaternion to a rotation matrix
Args:
q (torch.Tensor): shape [N,4], input quaternion
Returns:
torch.Tensor: [4x4] homogeneous rotation matrix
"""
assert q.shape[1] == 4, "Not a valid quaternion"
q = q / q.norm(dim=[1]).reshape(q.shape[0],1)
mat = torch.zeros((q.shape[0], 4, 4), device=q.device)
mat[:,0, 0] = 1 - 2*q[:,2]**2 - 2*q[:,3]**2
mat[:, 0, 1] = 2*q[:, 1]*q[:, 2] - 2*q[:, 3]*q[:, 0]
mat[:, 0, 2] = 2*q[:, 1]*q[:, 3] + 2*q[:, 2]*q[:, 0]
mat[:, 1, 0] = 2*q[:, 1]*q[:, 2] + 2*q[:, 3]*q[:, 0]
mat[:, 1, 1] = 1 - 2*q[:, 1]**2 - 2*q[:, 3]**2
mat[:, 1, 2] = 2*q[:, 2]*q[:, 3] - 2*q[:, 1]*q[:, 0]
mat[:, 2, 0] = 2*q[:, 1]*q[:, 3] - 2*q[:, 2]*q[:, 0]
mat[:, 2, 1] = 2*q[:, 2]*q[:, 3] + 2*q[:, 1]*q[:, 0]
mat[:, 2, 2] = 1 - 2*q[:, 1]**2 - 2*q[:, 2]**2
mat[:, 3, 3] = 1.
return mat
def inverse_batch(b_mat):
eye = b_mat.new_ones(b_mat.size(-1)).diag().expand_as(b_mat)
b_inv, _ = torch.solve(eye, b_mat)
return b_inv
def tvector2mat(t):
"""
Translation vector to homogeneous transformation matrix with identity rotation
Args:
t (torch.Tensor): shape=[3], translation vector
Returns:
torch.Tensor: [4x4] homogeneous transformation matrix
"""
assert t.shape == torch.Size([3]), "Not a valid translation"
mat = torch.eye(4, device=t.device)
mat[0, 3] = t[0]
mat[1, 3] = t[1]
mat[2, 3] = t[2]
return mat
def tvector2mat_batch(t):
"""
Translation vector to homogeneous transformation matrix with identity rotation
Args:
t (torch.Tensor): shape=[N,3], translation vector
Returns:
torch.Tensor: [4x4] homogeneous transformation matrix
"""
N = t.shape[1]
assert N == 3, "Not a valid translation"
mat = torch.stack([torch.eye(4, device=t.device)] * t.shape[0])
mat[:, 0, 3] = t[:, 0]
mat[:, 1, 3] = t[:, 1]
mat[:, 2, 3] = t[:, 2]
return mat
def mat2xyzrpy(rotmatrix):
"""
Decompose transformation matrix into components
Args:
rotmatrix (torch.Tensor/np.ndarray): [4x4] transformation matrix
Returns:
torch.Tensor: shape=[6], contains xyzrpy
"""
roll = math.atan2(-rotmatrix[1, 2], rotmatrix[2, 2])
pitch = math.asin ( rotmatrix[0, 2])
yaw = math.atan2(-rotmatrix[0, 1], rotmatrix[0, 0])
x = rotmatrix[:3, 3][0]
y = rotmatrix[:3, 3][1]
z = rotmatrix[:3, 3][2]
return torch.tensor([x, y, z, roll, pitch, yaw], device=rotmatrix.device, dtype=rotmatrix.dtype)
def to_rotation_matrix(R, T):
R = quat2mat(R)
T = tvector2mat(T)
RT = torch.mm(T, R)
return RT
def overlay_imgs(rgb, lidar, idx=0):
std = [0.229, 0.224, 0.225]
mean = [0.485, 0.456, 0.406]
rgb = rgb.clone().cpu().permute(1,2,0).numpy()
rgb = rgb*std+mean
lidar = lidar.clone()
lidar[lidar == 0] = 1000.
lidar = -lidar
#lidar = F.max_pool2d(lidar, 3, 1, 1)
lidar = F.max_pool2d(lidar, 3, 1, 1)
lidar = -lidar
lidar[lidar == 1000.] = 0.
#lidar = lidar.squeeze()
lidar = lidar[0][0]
lidar = (lidar*255).int().cpu().numpy()
lidar_color = cm.jet(lidar)
lidar_color[:, :, 3] = 0.5
lidar_color[lidar == 0] = [0, 0, 0, 0]
blended_img = lidar_color[:, :, :3] * (np.expand_dims(lidar_color[:, :, 3], 2)) + \
rgb * (1. - np.expand_dims(lidar_color[:, :, 3], 2))
blended_img = blended_img.clip(min=0., max=1.)
#io.imshow(blended_img)
#io.show()
#plt.figure()
#plt.imshow(blended_img)
#io.imsave(f'./IMGS/{idx:06d}.png', blended_img)
return blended_img