-
Notifications
You must be signed in to change notification settings - Fork 113
/
Copy pathkitti_dataset.py
1395 lines (1247 loc) · 59.6 KB
/
kitti_dataset.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
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
"""This file defines a class to interact with KITTI dataset. """
import os
import time
from os.path import isfile, join
import random
from collections import namedtuple, defaultdict
import numpy as np
import open3d
import cv2
Points = namedtuple('Points', ['xyz', 'attr'])
def downsample_by_average_voxel(points, voxel_size):
"""Voxel downsampling using average function.
points: a Points namedtuple containing "xyz" and "attr".
voxel_size: the size of voxel cells used for downsampling.
"""
# create voxel grid
xmax, ymax, zmax = np.amax(points.xyz, axis=0)
xmin, ymin, zmin = np.amin(points.xyz, axis=0)
xyz_offset = np.asarray([[xmin, ymin, zmin]])
xyz_zeros = np.asarray([0, 0, 0], dtype=np.float32)
xyz_idx = (points.xyz - xyz_offset) // voxel_size
xyz_idx = xyz_idx.astype(np.int32)
dim_x, dim_y, dim_z = np.amax(xyz_idx, axis=0) + 1
keys = xyz_idx[:, 0] + xyz_idx[:, 1]*dim_x + xyz_idx[:, 2]*dim_y*dim_x
order = np.argsort(keys)
keys = keys[order]
points_xyz = points.xyz[order]
unique_keys, lens = np.unique(keys, return_counts=True)
indices = np.hstack([[0], lens[:-1]]).cumsum()
downsampled_xyz = np.add.reduceat(
points_xyz, indices, axis=0)/lens[:,np.newaxis]
include_attr = points.attr is not None
if include_attr:
attr = points.attr[order]
downsampled_attr = np.add.reduceat(
attr, indices, axis=0)/lens[:,np.newaxis]
if include_attr:
return Points(xyz=downsampled_xyz,
attr=downsampled_attr)
else:
return Points(xyz=downsampled_xyz,
attr=None)
def downsample_by_random_voxel(points, voxel_size, add_rnd3d=False):
"""Downsample the points using base_voxel_size at different scales"""
xmax, ymax, zmax = np.amax(points.xyz, axis=0)
xmin, ymin, zmin = np.amin(points.xyz, axis=0)
xyz_offset = np.asarray([[xmin, ymin, zmin]])
xyz_zeros = np.asarray([0, 0, 0], dtype=np.float32)
if not add_rnd3d:
xyz_idx = (points.xyz - xyz_offset) // voxel_size
else:
xyz_idx = (points.xyz - xyz_offset +
voxel_size*np.random.random((1,3))) // voxel_size
dim_x, dim_y, dim_z = np.amax(xyz_idx, axis=0) + 1
keys = xyz_idx[:, 0] + xyz_idx[:, 1]*dim_x + xyz_idx[:, 2]*dim_y*dim_x
num_points = xyz_idx.shape[0]
voxels_idx = {}
for pidx in range(len(points.xyz)):
key = keys[pidx]
if key in voxels_idx:
voxels_idx[key].append(pidx)
else:
voxels_idx[key] = [pidx]
downsampled_xyz = []
downsampled_attr = []
for key in voxels_idx:
center_idx = random.choice(voxels_idx[key])
downsampled_xyz.append(points.xyz[center_idx])
downsampled_attr.append(points.attr[center_idx])
return Points(xyz=np.array(downsampled_xyz),
attr=np.array(downsampled_attr))
def box3d_to_cam_points(label, expend_factor=(1.0, 1.0, 1.0)):
"""Project 3D box into camera coordinates.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw", "height"
"width", "length".
Returns: a numpy array [8, 3] representing the corners of the 3d box in
camera coordinates.
"""
yaw = label['yaw']
R = np.array([[np.cos(yaw), 0, np.sin(yaw)],
[0, 1, 0 ],
[-np.sin(yaw), 0, np.cos(yaw)]]);
h = label['height']
delta_h = h*(expend_factor[0]-1)
w = label['width']*expend_factor[1]
l = label['length']*expend_factor[2]
corners = np.array([[ l/2, delta_h/2, w/2], # front up right
[ l/2, delta_h/2, -w/2], # front up left
[-l/2, delta_h/2, -w/2], # back up left
[-l/2, delta_h/2, w/2], # back up right
[ l/2, -h-delta_h/2, w/2], # front down right
[ l/2, -h-delta_h/2, -w/2], # front down left
[-l/2, -h-delta_h/2, -w/2], # back down left
[-l/2, -h-delta_h/2, w/2]]) # back down right
r_corners = corners.dot(np.transpose(R))
tx = label['x3d']
ty = label['y3d']
tz = label['z3d']
cam_points_xyz = r_corners+np.array([tx, ty, tz])
return Points(xyz = cam_points_xyz, attr = None)
def box3d_to_normals(label, expend_factor=(1.0, 1.0, 1.0)):
"""Project a 3D box into camera coordinates, compute the center
of the box and normals.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a numpy array [3, 3] containing [wx, wy, wz]^T, a [3] lower
bound and a [3] upper bound.
"""
box3d_points = box3d_to_cam_points(label, expend_factor)
box3d_points_xyz = box3d_points.xyz
wx = box3d_points_xyz[[0], :] - box3d_points_xyz[[4], :]
lx = np.matmul(wx, box3d_points_xyz[4, :])
ux = np.matmul(wx, box3d_points_xyz[0, :])
wy = box3d_points_xyz[[0], :] - box3d_points_xyz[[1], :]
ly = np.matmul(wy, box3d_points_xyz[1, :])
uy = np.matmul(wy, box3d_points_xyz[0, :])
wz = box3d_points_xyz[[0], :] - box3d_points_xyz[[3], :]
lz = np.matmul(wz, box3d_points_xyz[3, :])
uz = np.matmul(wz, box3d_points_xyz[0, :])
return(np.concatenate([wx, wy, wz], axis=0),
np.concatenate([lx, ly, lz]), np.concatenate([ux, uy, uz]))
def sel_xyz_in_box3d(label, xyz, expend_factor=(1.0, 1.0, 1.0)):
"""Select points in a 3D box.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a bool mask indicating points inside a 3D box.
"""
normals, lower, upper = box3d_to_normals(label, expend_factor)
projected = np.matmul(xyz, np.transpose(normals))
points_in_x = np.logical_and(projected[:, 0] > lower[0],
projected[:, 0] < upper[0])
points_in_y = np.logical_and(projected[:, 1] > lower[1],
projected[:, 1] < upper[1])
points_in_z = np.logical_and(projected[:, 2] > lower[2],
projected[:, 2] < upper[2])
mask = np.logical_and.reduce((points_in_x, points_in_y, points_in_z))
return mask
def sel_xyz_in_box2d(label, xyz, expend_factor=(1.0, 1.0, 1.0)):
"""Select points in a 3D box.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a bool mask indicating points inside a 3D box.
"""
normals, lower, upper = box3d_to_normals(label, expend_factor)
normals, lower, upper = normals[1:], lower[1:], upper[1:]
projected = np.matmul(xyz, np.transpose(normals))
points_in_y = np.logical_and(projected[:, 0] > lower[0],
projected[:, 0] < upper[0])
points_in_z = np.logical_and(projected[:, 1] > lower[1],
projected[:, 1] < upper[1])
mask = np.logical_and.reduce((points_in_y, points_in_z))
return mask
class KittiDataset(object):
"""A class to interact with KITTI dataset."""
def __init__(self, image_dir, point_dir, calib_dir, label_dir,
index_filename=None, is_training=True, is_raw=False, difficulty=-100,
num_classes=8):
"""
Args:
image_dir: a string of the path to image folder.
point_dir: a string of the path to point cloud data folder.
calib_dir: a string of the path to the calibration matrices.
label_dir: a string of the path to the label folder.
index_filename: a string containing a path an index file.
"""
self._image_dir = image_dir
self._point_dir = point_dir
self._calib_dir = calib_dir
self._label_dir = label_dir
self._index_filename = index_filename
if index_filename:
self._file_list = self._read_index_file(index_filename)
else:
self._file_list = self._get_file_list(self._image_dir)
self._verify_file_list(
self._image_dir, self._point_dir, self._label_dir, self._calib_dir,
self._file_list, is_training, is_raw)
self._is_training = is_training
self._is_raw = is_raw
self.num_classes = num_classes
self.difficulty = difficulty
self._max_image_height = 376
self._max_image_width = 1242
def __str__(self):
"""Generate a string summary of the dataset"""
summary_string = ('Dataset Summary:\n'
+'image_dir=%s\n' % self._image_dir
+'point_dir=%s\n' % self._point_dir
+'calib_dir=%s\n' % self._calib_dir
+'label_dir=%s\n' % self._label_dir
+'index_filename=%s\n' % self._index_filename
+'Total number of sampels: %d\n' % self.num_files)
statics = self.get_statics()
return summary_string + statics
def get_statics(self):
import matplotlib.pyplot as plt
"""Get statics of objects inside the dataset"""
x_dict = defaultdict(list)
y_dict = defaultdict(list)
z_dict = defaultdict(list)
h_dict = defaultdict(list)
w_dict = defaultdict(list)
l_dict = defaultdict(list)
view_angle_dict = defaultdict(list)
yaw_dict = defaultdict(list)
for frame_idx in range(self.num_files):
labels = self.get_label(frame_idx)
for label in labels:
if label['ymin'] > 0:
if label['ymax'] - label['ymin'] > 25:
object_name = label['name']
h_dict[object_name].append(label['height'])
w_dict[object_name].append(label['width'])
l_dict[object_name].append(label['length'])
x_dict[object_name].append(label['x3d'])
y_dict[object_name].append(label['y3d'])
z_dict[object_name].append(label['z3d'])
view_angle_dict[object_name].append(
np.arctan(label['x3d']/label['z3d']))
yaw_dict[object_name].append(label['yaw'])
plt.scatter(z_dict['Pedestrian'], np.array(l_dict['Pedestrian']))
plt.title('Scatter plot pythonspot.com')
plt.show()
# compute ingore statics
import nms
truncation_rates = []
no_truncation_rates = []
image_height = []
image_width = []
for frame_idx in range(self.num_files):
labels = self.get_label(frame_idx)
calib = self.get_calib(frame_idx)
image = self.get_image(frame_idx)
image_height.append(image.shape[0])
image_width.append(image.shape[1])
for label in labels:
if label['name'] == 'Car':
# too small
if label['ymax'] - label['ymin'] < 25:
object_name = label['name']
h_dict['ignored_by_height'].append(label['height'])
w_dict['ignored_by_height'].append(label['width'])
l_dict['ignored_by_height'].append(label['length'])
x_dict['ignored_by_height'].append(label['x3d'])
y_dict['ignored_by_height'].append(label['y3d'])
z_dict['ignored_by_height'].append(label['z3d'])
view_angle_dict['ignored_by_height'].append(
np.arctan(label['x3d']/label['z3d']))
yaw_dict['ignored_by_height'].append(label['yaw'])
if label['truncation'] > 0.5:
h_dict['ignored_by_truncation'].append(label['height'])
w_dict['ignored_by_truncation'].append(label['width'])
l_dict['ignored_by_truncation'].append(label['length'])
x_dict['ignored_by_truncation'].append(label['x3d'])
y_dict['ignored_by_truncation'].append(label['y3d'])
z_dict['ignored_by_truncation'].append(label['z3d'])
view_angle_dict['ignored_by_truncation'].append(
np.arctan(label['x3d']/label['z3d']))
yaw_dict['ignored_by_truncation'].append(label['yaw'])
detection_boxes_3d = np.array(
[[label['x3d'], label['y3d'], label['z3d'],
label['length'], label['height'], label['width'],
label['yaw']]])
detection_boxes_3d_corners = nms.boxes_3d_to_corners(
detection_boxes_3d)
corners_cam_points = Points(
xyz=detection_boxes_3d_corners[0], attr=None)
corners_img_points = self.cam_points_to_image(
corners_cam_points, calib)
corners_xy = corners_img_points.xyz[:, :2]
xmin, ymin = np.amin(corners_xy, axis=0)
xmax, ymax = np.amax(corners_xy, axis=0)
clip_xmin = max(xmin, 0.0)
clip_ymin = max(ymin, 0.0)
clip_xmax = min(xmax, 1242.0)
clip_ymax = min(ymax, 375.0)
height = clip_ymax - clip_ymin
truncation_rate = 1.0 - \
(clip_ymax - clip_ymin)*(clip_xmax - clip_xmin)\
/((ymax - ymin)*(xmax - xmin))
if label['truncation'] > 0.5:
truncation_rates.append(truncation_rate)
else:
no_truncation_rates.append(truncation_rate)
if label['occlusion'] > 2:
h_dict['ignored_by_occlusion'].append(label['height'])
w_dict['ignored_by_occlusion'].append(label['width'])
l_dict['ignored_by_occlusion'].append(label['length'])
x_dict['ignored_by_occlusion'].append(label['x3d'])
y_dict['ignored_by_occlusion'].append(label['y3d'])
z_dict['ignored_by_occlusion'].append(label['z3d'])
view_angle_dict['ignored_by_occlusion'].append(
np.arctan(label['x3d']/label['z3d']))
yaw_dict['ignored_by_occlusion'].append(label['yaw'])
statics = ""
for object_name in h_dict:
print(object_name+"l="+str(
np.histogram(l_dict[object_name], 10, density=True)))
if len(h_dict[object_name]) == 0:
continue
statics += (str(len(h_dict[object_name]))+ " "+ str(object_name)
+ " "
+ "mh=" + str(np.min(h_dict[object_name])) + " "
+ str(np.median(h_dict[object_name])) + " "
+ str(np.max(h_dict[object_name])) + "; "
+ "mw=" + str(np.min(w_dict[object_name])) + " "
+ str(np.median(w_dict[object_name])) + " "
+ str(np.max(w_dict[object_name])) + "; "
+ "ml=" + str(np.min(l_dict[object_name])) + " "
+ str(np.median(l_dict[object_name])) + " "
+ str(np.max(l_dict[object_name])) + "; "
+ "mx=" + str(np.min(x_dict[object_name])) + " "
+ str(np.median(x_dict[object_name])) + " "
+ str(np.max(x_dict[object_name])) + "; "
+ "my=" + str(np.min(y_dict[object_name])) + " "
+ str(np.median(y_dict[object_name])) + " "
+ str(np.max(y_dict[object_name])) + "; "
+ "mz=" + str(np.min(z_dict[object_name])) + " "
+ str(np.median(z_dict[object_name])) + " "
+ str(np.max(z_dict[object_name])) + "; "
+ "mA=" + str(np.min(view_angle_dict[object_name]))
+ " "
+ str(np.median(view_angle_dict[object_name]))
+ " "
+ str(np.max(view_angle_dict[object_name])) + "; "
+ "mY=" + str(np.min(yaw_dict[object_name])) + " "
+ str(np.median(yaw_dict[object_name])) + " "
+ str(np.max(yaw_dict[object_name])) + "; "
+ "image_height" + str(np.min(image_height)) + " "
+ str(np.max(image_height)) +" "
+ "image_width" + str(np.min(image_width)) + " "
+ str(np.max(image_width)) + ";"
"\n")
return statics
@property
def num_files(self):
return len(self._file_list)
def _read_index_file(self, index_filename):
"""Read an index file containing the filenames.
Args:
index_filename: a string containing the path to an index file.
Returns: a list of filenames.
"""
file_list = []
with open(index_filename, 'r') as f:
for line in f:
file_list.append(line.rstrip('\n').split('.')[0])
return file_list
def _get_file_list(self, image_dir):
"""Load all filenames from image_dir.
Args:
image_dir: a string of path to the image folder.
Returns: a list of filenames.
"""
file_list = [f.split('.')[0]
for f in os.listdir(image_dir) if isfile(join(image_dir, f))]
file_list.sort()
return file_list
def _verify_file_list(
self, image_dir, point_dir, label_dir, calib_dir, file_list,
is_training, is_raw):
"""Varify the files in file_list exist.
Args:
image_dir: a string of the path to image folder.
point_dir: a string of the path to point cloud data folder.
label_dir: a string of the path to the label folder.
calib_dir: a string of the path to the calibration folder.
file_list: a list of filenames.
is_training: if False, label_dir is not verified.
Raise: assertion error when file in file_list is not complete.
"""
for f in file_list:
image_file = join(image_dir, f)+'.png'
point_file = join(point_dir, f)+'.bin'
label_file = join(label_dir, f)+'.txt'
calib_file = join(calib_dir, f)+'.txt'
assert isfile(image_file), "Image %s does not exist" % image_file
assert isfile(point_file), "Point %s does not exist" % point_file
if not is_raw:
assert isfile(calib_file), \
"Calib %s does not exist" % calib_file
if is_training:
assert isfile(label_file), \
"Label %s does not exist" % label_file
def downsample_by_voxel(self, points, voxel_size, method='AVERAGE'):
"""Downsample point cloud by voxel.
points: a Points namedtuple containing "xyz" and "attr".
voxel_size: the size of voxel cells used for downsampling.
method: 'AVERAGE', all points inside a voxel cell are averaged
including xyz and attr.
"""
# create voxel grid
xmax, ymax, zmax = np.amax(points.xyz, axis=0)
xmin, ymin, zmin = np.amin(points.xyz, axis=0)
dim_x = int((xmax - xmin) / voxel_size + 1)
dim_y = int((ymax - ymin) / voxel_size + 1)
dim_z = int((zmax - zmin) / voxel_size + 1)
voxel_account = {}
xyz_idx = np.int32(
(points.xyz - np.asarray([[xmin, ymin, zmin]])) / voxel_size)
for pidx in range(xyz_idx.shape[0]):
x_idx = xyz_idx[pidx, 0]
y_idx = xyz_idx[pidx, 1]
z_idx = xyz_idx[pidx, 2]
# TODO check bug impact
key = x_idx + y_idx*dim_x + z_idx*dim_y*dim_x
if key in voxel_account:
voxel_account[key].append(pidx)
else:
voxel_account[key] = [pidx]
# compute voxel points
downsampled_xyz_list = []
if points.attr is not None:
downsampled_attr_list = []
if method == 'AVERAGE':
for idx, pidx_list in voxel_account.iteritems():
if len(pidx_list) > 0:
downsampled_xyz_list.append(
np.mean(points.xyz[pidx_list, :],
axis=0, keepdims=True))
if points.attr is not None:
downsampled_attr_list.append(
np.mean(points.attr[pidx_list, :],
axis=0, keepdims=True))
if points.attr is not None:
return Points(xyz=np.vstack(downsampled_xyz_list),
attr=np.vstack(downsampled_attr_list))
else:
return Points(xyz=np.vstack(downsampled_xyz_list),
attr=None)
def get_calib(self, frame_idx):
"""Load calibration matrices and compute calibrations.
Args:
frame_idx: the index of the frame to read.
Returns: a dictionary of calibrations.
"""
calib_file = join(self._calib_dir, self._file_list[frame_idx])+'.txt'
with open(calib_file, 'r') as f:
calib = {}
for line in f:
fields = line.split(' ')
matrix_name = fields[0].rstrip(':')
matrix = np.array(fields[1:], dtype=np.float32)
calib[matrix_name] = matrix
calib['P2'] = calib['P2'].reshape(3, 4)
calib['R0_rect'] = calib['R0_rect'].reshape(3,3)
calib['Tr_velo_to_cam'] = calib['Tr_velo_to_cam'].reshape(3,4)
R0_rect = np.eye(4)
R0_rect[:3, :3] = calib['R0_rect']
calib['velo_to_rect'] = np.vstack([calib['Tr_velo_to_cam'],[0,0,0,1]])
calib['cam_to_image'] = np.hstack([calib['P2'][:, 0:3], [[0],[0],[0]]])
calib['rect_to_cam'] = np.hstack([
calib['R0_rect'],
np.matmul(
np.linalg.inv(calib['P2'][:, 0:3]), calib['P2'][:, [3]])])
calib['rect_to_cam'] = np.vstack([calib['rect_to_cam'],
[0,0,0,1]])
calib['velo_to_cam'] = np.matmul(calib['rect_to_cam'],
calib['velo_to_rect'])
calib['cam_to_velo'] = np.linalg.inv(calib['velo_to_cam'])
# senity check
calib['velo_to_image'] = np.matmul(calib['cam_to_image'],
calib['velo_to_cam'])
assert np.isclose(calib['velo_to_image'],
np.matmul(np.matmul(calib['P2'], R0_rect),
calib['velo_to_rect'])).all()
return calib
def get_raw_calib(self, calib_velo_to_cam_path, calib_cam_to_cam_path):
"""Read calibrations in kitti raw dataset."""
with open(calib_cam_to_cam_path, 'r') as f:
calib = {}
for line in f:
line = line.rstrip('\n')
fields = line.split(':')
calib[fields[0]] = fields[1]
calib['corner_dist'] = np.array(
calib['corner_dist'], dtype=np.float32)
for i in range(4):
calib['S_0%d'%i] = np.array(
calib['S_0%d'%i].split(' ')[1:], dtype=np.float32).reshape(1,2)
calib['K_0%d'%i] = np.array(
calib['K_0%d'%i].split(' ')[1:], dtype=np.float32).reshape(3,3)
calib['D_0%d'%i] = np.array(
calib['D_0%d'%i].split(' ')[1:], dtype=np.float32).reshape(1,5)
calib['R_0%d'%i] = np.array(
calib['R_0%d'%i].split(' ')[1:], dtype=np.float32).reshape(3,3)
calib['T_0%d'%i] = np.array(
calib['T_0%d'%i].split(' ')[1:], dtype=np.float32).reshape(3,1)
calib['S_rect_0%d'%i] = np.array(
calib['S_rect_0%d'%i].split(' ')[1:],
dtype=np.float32).reshape(1,2)
calib['R_rect_0%d'%i] = np.array(
calib['R_rect_0%d'%i].split(' ')[1:],
dtype=np.float32).reshape(3,3)
calib['P_rect_0%d'%i] = np.array(
calib['P_rect_0%d'%i].split(' ')[1:],
dtype=np.float32).reshape(3,4)
with open(calib_velo_to_cam_path, 'r') as f:
for line in f:
line = line.rstrip('\n')
fields = line.split(':')
calib[fields[0]] = fields[1]
calib['R'] = np.array(
calib['R'].split(' ')[1:], dtype=np.float32).reshape(3,3)
calib['T'] = np.array(
calib['T'].split(' ')[1:], dtype=np.float32).reshape(3,1)
calib['Tr_velo_to_cam'] = np.vstack(
[np.hstack([calib['R'], calib['T']]),[0,0,0,1]])
R0_rect = np.eye(4)
R0_rect[:3, :3] = calib['R_rect_00']
T2 = np.eye(4)
T2[0, 3] = calib['P_rect_02'][0, 3]/calib['P_rect_02'][0, 0]
calib['velo_to_cam'] = T2.dot(R0_rect.dot(calib['Tr_velo_to_cam']))
calib['cam_to_image'] = np.hstack(
[calib['P_rect_02'][:, 0:3], [[0],[0],[0]]])
calib['velo_to_image'] = np.matmul(calib['cam_to_image'],
calib['velo_to_cam'])
return calib
def get_filename(self, frame_idx):
"""Get the filename based on frame_idx.
Args:
frame_idx: the index of the frame to get.
Returns: a string containing the filename.
"""
return self._file_list[frame_idx]
def get_velo_points(self, frame_idx, xyz_range=None):
"""Load velo points from frame_idx.
Args:
frame_idx: the index of the frame to read.
Returns: Points.
"""
point_file = join(self._point_dir, self._file_list[frame_idx])+'.bin'
velo_data = np.fromfile(point_file, dtype=np.float32).reshape(-1, 4)
velo_points = velo_data[:,:3]
reflections = velo_data[:,[3]]
if xyz_range is not None:
x_range, y_range, z_range = xyz_range
mask =(
velo_points[:, 0] > x_range[0])*(velo_points[:, 0] < x_range[1])
mask *=(
velo_points[:, 1] > y_range[0])*(velo_points[:, 1] < y_range[1])
mask *=(
velo_points[:, 2] > z_range[0])*(velo_points[:, 2] < z_range[1])
return Points(xyz = velo_points[mask], attr = reflections[mask])
return Points(xyz = velo_points, attr = reflections)
def get_cam_points(self, frame_idx,
downsample_voxel_size=None, calib=None, xyz_range=None):
"""Load velo points and convert them to camera coordinates.
Args:
frame_idx: the index of the frame to read.
Returns: Points.
"""
velo_points = self.get_velo_points(frame_idx, xyz_range=xyz_range)
if calib is None:
calib = self.get_calib(frame_idx)
cam_points = self.velo_points_to_cam(velo_points, calib)
if downsample_voxel_size is not None:
cam_points = downsample_by_average_voxel(cam_points,
downsample_voxel_size)
return cam_points
def calc_distances(self, p0, points):
return ((p0 - points)**2).sum(axis=1)
def farthest_first(self, pts, K):
farthest_pts = np.zeros((K, 3))
farthest_pts[0] = pts[np.random.randint(len(pts))]
distances = self.calc_distances(farthest_pts[0], pts)
for i in range(1, K):
farthest_pts[i] = pts[np.argmax(distances)]
distances = np.minimum(distances,
self.calc_distances(farthest_pts[i], pts))
return farthest_pts
def get_cam_points_in_image(self, frame_idx, downsample_voxel_size=None,
calib=None, xyz_range=None):
"""Load velo points and remove points that are not observed by camera.
"""
if calib is None:
calib = self.get_calib(frame_idx)
cam_points = self.get_cam_points(frame_idx, downsample_voxel_size,
calib=calib, xyz_range=xyz_range)
image = self.get_image(frame_idx)
height = image.shape[0]
width = image.shape[1]
front_cam_points_idx = cam_points.xyz[:,2] > 0.1
front_cam_points = Points(cam_points.xyz[front_cam_points_idx, :],
cam_points.attr[front_cam_points_idx, :])
img_points = self.cam_points_to_image(front_cam_points, calib)
img_points_in_image_idx = np.logical_and.reduce(
[img_points.xyz[:,0]>0, img_points.xyz[:,0]<width,
img_points.xyz[:,1]>0, img_points.xyz[:,1]<height])
cam_points_in_img = Points(
xyz = front_cam_points.xyz[img_points_in_image_idx,:],
attr = front_cam_points.attr[img_points_in_image_idx,:])
return cam_points_in_img
def get_cam_points_in_image_with_rgb(self, frame_idx,
downsample_voxel_size=None, calib=None, xyz_range=None):
"""Get camera points that are visible in image and append image color
to the points as attributes."""
if calib is None:
calib = self.get_calib(frame_idx)
cam_points = self.get_cam_points(frame_idx, downsample_voxel_size,
calib = calib, xyz_range=xyz_range)
front_cam_points_idx = cam_points.xyz[:,2] > 0.1
front_cam_points = Points(cam_points.xyz[front_cam_points_idx, :],
cam_points.attr[front_cam_points_idx, :])
image = self.get_image(frame_idx)
height = image.shape[0]
width = image.shape[1]
img_points = self.cam_points_to_image(front_cam_points, calib)
img_points_in_image_idx = np.logical_and.reduce(
[img_points.xyz[:,0]>0, img_points.xyz[:,0]<width,
img_points.xyz[:,1]>0, img_points.xyz[:,1]<height])
cam_points_in_img = Points(
xyz = front_cam_points.xyz[img_points_in_image_idx,:],
attr = front_cam_points.attr[img_points_in_image_idx,:])
cam_points_in_img_with_rgb = self.rgb_to_cam_points(cam_points_in_img,
image, calib)
return cam_points_in_img_with_rgb
def get_image(self, frame_idx):
"""Load the image from frame_idx.
Args:
frame_idx: the index of the frame to read.
Returns: cv2.matrix
"""
image_file = join(self._image_dir, self._file_list[frame_idx])+'.png'
return cv2.imread(image_file)
def get_label(self, frame_idx, no_orientation=False):
"""Load bbox labels from frame_idx frame.
Args:
frame_idx: the index of the frame to read.
Returns: a list of object label dictionaries.
"""
MIN_HEIGHT = [40, 25, 25]
MAX_OCCLUSION = [0, 1, 2]
MAX_TRUNCATION = [0.15, 0.3, 0.5]
label_file = join(self._label_dir, self._file_list[frame_idx])+'.txt'
label_list = []
with open(label_file, 'r') as f:
for line in f:
label={}
line = line.strip()
if line == '':
continue
fields = line.split(' ')
label['name'] = fields[0]
# 0=visible 1=partly occluded, 2=fully occluded, 3=unknown
label['truncation'] = float(fields[1])
label['occlusion'] = int(fields[2])
label['alpha'] = float(fields[3])
label['xmin'] = float(fields[4])
label['ymin'] = float(fields[5])
label['xmax'] = float(fields[6])
label['ymax'] = float(fields[7])
label['height'] = float(fields[8])
label['width'] = float(fields[9])
label['length'] = float(fields[10])
label['x3d'] = float(fields[11])
label['y3d'] = float(fields[12])
label['z3d'] = float(fields[13])
label['yaw'] = float(fields[14])
if len(fields) > 15:
label['score'] = float(fields[15])
if self.difficulty > -1:
if label['truncation'] > MAX_TRUNCATION[self.difficulty]:
continue
if label['occlusion'] > MAX_OCCLUSION[self.difficulty]:
continue
if (label['ymax'] - label['ymin']
) < MIN_HEIGHT[self.difficulty]:
continue
label_list.append(label)
return label_list
def box3d_to_cam_points(self, label, expend_factor=(1.0, 1.0, 1.0)):
"""Project 3D box into camera coordinates.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw", "height"
"width", "length".
Returns: a numpy array [8, 3] representing the corners of the 3d box in
camera coordinates.
"""
yaw = label['yaw']
R = np.array([[np.cos(yaw), 0, np.sin(yaw)],
[0, 1, 0 ],
[-np.sin(yaw), 0, np.cos(yaw)]]);
h = label['height']
delta_h = h*(expend_factor[0]-1)
w = label['width']*expend_factor[1]
l = label['length']*expend_factor[2]
corners = np.array([[ l/2, delta_h/2, w/2], # front up right
[ l/2, delta_h/2, -w/2], # front up left
[-l/2, delta_h/2, -w/2], # back up left
[-l/2, delta_h/2, w/2], # back up right
[ l/2, -h-delta_h/2, w/2], # front down right
[ l/2, -h-delta_h/2, -w/2], # front down left
[-l/2, -h-delta_h/2, -w/2], # back down left
[-l/2, -h-delta_h/2, w/2]]) # back down right
r_corners = corners.dot(np.transpose(R))
tx = label['x3d']
ty = label['y3d']
tz = label['z3d']
cam_points_xyz = r_corners+np.array([tx, ty, tz])
return Points(xyz = cam_points_xyz, attr = None)
def boxes_3d_to_line_set(self, boxes_3d, boxes_color=None):
points = []
edges = []
colors = []
for i, box_3d in enumerate(boxes_3d):
x3d, y3d, z3d, l, h, w, yaw = box_3d
R = np.array([[np.cos(yaw), 0, np.sin(yaw)],
[0, 1, 0 ],
[-np.sin(yaw), 0, np.cos(yaw)]]);
corners = np.array([[ l/2, 0.0, w/2], # front up right
[ l/2, 0.0, -w/2], # front up left
[-l/2, 0.0, -w/2], # back up left
[-l/2, 0.0, w/2], # back up right
[ l/2, -h, w/2], # front down right
[ l/2, -h, -w/2], # front down left
[-l/2, -h, -w/2], # back down left
[-l/2, -h, w/2]]) # back down right
r_corners = corners.dot(np.transpose(R))
cam_points_xyz = r_corners+np.array([x3d, y3d, z3d])
points.append(cam_points_xyz)
edges.append(
np.array([[0, 1], [0, 4], [0, 3],
[1, 2], [1, 5], [2, 3],
[2, 6], [3, 7], [4, 5],
[4, 7], [5, 6], [6, 7]])+i*8)
if boxes_color is None:
colors.append(np.tile([[1.0, 0.0, 0.0]], [12, 1]))
else:
colors.append(np.tile(boxes_color[[i], :], [12, 1]))
if len(points) == 0:
return None, None, None
return np.vstack(points), np.vstack(edges), np.vstack(colors)
def draw_open3D_box(self, label, expend_factor=(1.0, 1.0, 1.0)):
"""Draw a 3d box using open3d.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
returns: a open3d mesh object.
"""
yaw = label['yaw']
R = np.array([[np.cos(yaw), 0, np.sin(yaw)],
[0, 1, 0 ],
[-np.sin(yaw), 0, np.cos(yaw)]]);
Rh = np.array([ [1, 0, 0],
[0, 0, 1],
[0, 1, 0]])
Rl = np.array([ [0, 0, 1],
[0, 1, 0],
[1, 0, 0]])
h = label['height']
delta_h = h*(expend_factor[0]-1)
w = label['width']*expend_factor[1]
l = label['length']*expend_factor[2]
print((l, w, h))
tx = label['x3d']
ty = label['y3d']
tz = label['z3d']
box_offset = np.array([ [ l/2, -h/2-delta_h/2, w/2],
[ l/2, -h/2-delta_h/2, -w/2],
[-l/2, -h/2-delta_h/2, -w/2],
[-l/2, -h/2-delta_h/2, w/2],
[ l/2, delta_h/2, 0],
[ -l/2, delta_h/2, 0],
[l/2, -h-delta_h/2, 0],
[-l/2, -h-delta_h/2, 0],
[0, delta_h/2, w/2],
[0, delta_h/2, -w/2],
[0, -h-delta_h/2, w/2],
[0, -h-delta_h/2, -w/2]])
transform = np.matmul(R, np.transpose(box_offset))
transform = transform + np.array([[tx], [ty], [tz]])
transform = np.vstack((transform, np.ones((1, 12))))
hrotation = np.vstack((R.dot(Rh), np.zeros((1,3))))
lrotation = np.vstack((R.dot(Rl), np.zeros((1,3))))
wrotation = np.vstack((R, np.zeros((1,3))))
h1_cylinder = open3d.create_mesh_cylinder(radius = h/100, height = h)
h1_cylinder.paint_uniform_color([0.1, 0.9, 0.1])
h1_cylinder.transform(np.hstack((hrotation, transform[:, [0]])))
h2_cylinder = open3d.create_mesh_cylinder(radius = h/100, height = h)
h2_cylinder.paint_uniform_color([0.1, 0.9, 0.1])
h2_cylinder.transform(np.hstack((hrotation, transform[:, [1]])))
h3_cylinder = open3d.create_mesh_cylinder(radius = h/100, height = h)
h3_cylinder.paint_uniform_color([0.1, 0.9, 0.1])
h3_cylinder.transform(np.hstack((hrotation, transform[:, [2]])))
h4_cylinder = open3d.create_mesh_cylinder(radius = h/100, height = h)
h4_cylinder.paint_uniform_color([0.1, 0.9, 0.1])
h4_cylinder.transform(np.hstack((hrotation, transform[:, [3]])))
w1_cylinder = open3d.create_mesh_cylinder(radius = w/100, height = w)
w1_cylinder.paint_uniform_color([0.9, 0.1, 0.1])
w1_cylinder.transform(np.hstack((wrotation, transform[:, [4]])))
w2_cylinder = open3d.create_mesh_cylinder(radius = w/100, height = w)
w2_cylinder.paint_uniform_color([0.9, 0.1, 0.1])
w2_cylinder.transform(np.hstack((wrotation, transform[:, [5]])))
w3_cylinder = open3d.create_mesh_cylinder(radius = w/100, height = w)
w3_cylinder.paint_uniform_color([0.9, 0.1, 0.1])
w3_cylinder.transform(np.hstack((wrotation, transform[:, [6]])))
w4_cylinder = open3d.create_mesh_cylinder(radius = w/100, height = w)
w4_cylinder.paint_uniform_color([0.9, 0.1, 0.1])
w4_cylinder.transform(np.hstack((wrotation, transform[:, [7]])))
l1_cylinder = open3d.create_mesh_cylinder(radius = l/100, height = l)
l1_cylinder.paint_uniform_color([0.1, 0.1, 0.9])
l1_cylinder.transform(np.hstack((lrotation, transform[:, [8]])))
l2_cylinder = open3d.create_mesh_cylinder(radius = l/100, height = l)
l2_cylinder.paint_uniform_color([0.1, 0.1, 0.9])
l2_cylinder.transform(np.hstack((lrotation, transform[:, [9]])))
l3_cylinder = open3d.create_mesh_cylinder(radius = l/100, height = l)
l3_cylinder.paint_uniform_color([0.1, 0.1, 0.9])
l3_cylinder.transform(np.hstack((lrotation, transform[:, [10]])))
l4_cylinder = open3d.create_mesh_cylinder(radius = l/100, height = l)
l4_cylinder.paint_uniform_color([0.1, 0.1, 0.9])
l4_cylinder.transform(np.hstack((lrotation, transform[:, [11]])))
return [h1_cylinder, h2_cylinder, h3_cylinder, h4_cylinder,
w1_cylinder, w2_cylinder, w3_cylinder, w4_cylinder,
l1_cylinder, l2_cylinder, l3_cylinder, l4_cylinder]
def box3d_to_normals(self, label, expend_factor=(1.0, 1.0, 1.0)):
"""Project a 3D box into camera coordinates, compute the center
of the box and normals.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a numpy array [3, 3] containing [wx, wy, wz]^T, a [3] lower
bound and a [3] upper bound.
"""
box3d_points = self.box3d_to_cam_points(label, expend_factor)
box3d_points_xyz = box3d_points.xyz
wx = box3d_points_xyz[[0], :] - box3d_points_xyz[[4], :]
lx = np.matmul(wx, box3d_points_xyz[4, :])
ux = np.matmul(wx, box3d_points_xyz[0, :])
wy = box3d_points_xyz[[0], :] - box3d_points_xyz[[1], :]
ly = np.matmul(wy, box3d_points_xyz[1, :])
uy = np.matmul(wy, box3d_points_xyz[0, :])
wz = box3d_points_xyz[[0], :] - box3d_points_xyz[[3], :]
lz = np.matmul(wz, box3d_points_xyz[3, :])
uz = np.matmul(wz, box3d_points_xyz[0, :])
return(np.concatenate([wx, wy, wz], axis=0),
np.concatenate([lx, ly, lz]), np.concatenate([ux, uy, uz]))
def sel_points_in_box3d(self, label, points, expend_factor=(1.0, 1.0, 1.0)):
"""Select points in a 3D box.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a bool mask indicating points inside a 3D box.
"""
normals, lower, upper = self.box3d_to_normals(label, expend_factor)
projected = np.matmul(points.xyz, np.transpose(normals))
points_in_x = np.logical_and(projected[:, 0] > lower[0],
projected[:, 0] < upper[0])
points_in_y = np.logical_and(projected[:, 1] > lower[1],
projected[:, 1] < upper[1])
points_in_z = np.logical_and(projected[:, 2] > lower[2],
projected[:, 2] < upper[2])
mask = np.logical_and.reduce((points_in_x, points_in_y, points_in_z))
return mask
def sel_xyz_in_box3d(self, label, xyz, expend_factor=(1.0, 1.0, 1.0)):
"""Select points in a 3D box.
Args:
label: a dictionary containing "x3d", "y3d", "z3d", "yaw",
"height", "width", "lenth".
Returns: a bool mask indicating points inside a 3D box.
"""
normals, lower, upper = self.box3d_to_normals(label, expend_factor)
projected = np.matmul(xyz, np.transpose(normals))
points_in_x = np.logical_and(projected[:, 0] > lower[0],
projected[:, 0] < upper[0])
points_in_y = np.logical_and(projected[:, 1] > lower[1],
projected[:, 1] < upper[1])
points_in_z = np.logical_and(projected[:, 2] > lower[2],
projected[:, 2] < upper[2])
mask = np.logical_and.reduce((points_in_x, points_in_y, points_in_z))
return mask
def rgb_to_cam_points(self, points, image, calib):
"""Append rgb info to camera points"""
img_points = self.cam_points_to_image(points, calib)
rgb = image[np.int32(img_points.xyz[:,1]),
np.int32(img_points.xyz[:,0]),::-1].astype(np.float32)/255
return Points(points.xyz, np.hstack([points.attr, rgb]))
def velo_points_to_cam(self, points, calib):
"""Convert points in velodyne coordinates to camera coordinates.