kitti_dataset.py 26.5 KB
Newer Older
zhangwenwei's avatar
zhangwenwei committed
1
2
3
import copy
import mmcv
import numpy as np
zhangwenwei's avatar
zhangwenwei committed
4
5
import os
import tempfile
zhangwenwei's avatar
zhangwenwei committed
6
import torch
zhangwenwei's avatar
zhangwenwei committed
7
from mmcv.utils import print_log
zhangwenwei's avatar
zhangwenwei committed
8
from os import path as osp
zhangwenwei's avatar
zhangwenwei committed
9

zhangwenwei's avatar
zhangwenwei committed
10
from mmdet.datasets import DATASETS
liyinhao's avatar
liyinhao committed
11
from ..core import show_result
zhangwenwei's avatar
zhangwenwei committed
12
from ..core.bbox import Box3DMode, CameraInstance3DBoxes, points_cam2img
zhangwenwei's avatar
zhangwenwei committed
13
from .custom_3d import Custom3DDataset
zhangwenwei's avatar
zhangwenwei committed
14
15


16
@DATASETS.register_module()
zhangwenwei's avatar
zhangwenwei committed
17
class KittiDataset(Custom3DDataset):
zhangwenwei's avatar
zhangwenwei committed
18
    r"""KITTI Dataset.
wangtai's avatar
wangtai committed
19

zhangwenwei's avatar
zhangwenwei committed
20
21
    This class serves as the API for experiments on the `KITTI Dataset
    <http://www.cvlibs.net/datasets/kitti/eval_object.php?obj_benchmark=3d>`_.
wangtai's avatar
wangtai committed
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39

    Args:
        data_root (str): Path of dataset root.
        ann_file (str): Path of annotation file.
        split (str): Split of input data.
        pts_prefix (str, optional): Prefix of points files.
            Defaults to 'velodyne'.
        pipeline (list[dict], optional): Pipeline used for data processing.
            Defaults to None.
        classes (tuple[str], optional): Classes used in the dataset.
            Defaults to None.
        modality (dict, optional): Modality to specify the sensor data used
            as input. Defaults to None.
        box_type_3d (str, optional): Type of 3D box of this dataset.
            Based on the `box_type_3d`, the dataset will encapsulate the box
            to its original format then converted them to `box_type_3d`.
            Defaults to 'LiDAR' in this dataset. Available options includes

wangtai's avatar
wangtai committed
40
41
42
            - 'LiDAR': Box in LiDAR coordinates.
            - 'Depth': Box in depth coordinates, usually for indoor dataset.
            - 'Camera': Box in camera coordinates.
wangtai's avatar
wangtai committed
43
44
45
46
47
        filter_empty_gt (bool, optional): Whether to filter empty GT.
            Defaults to True.
        test_mode (bool, optional): Whether the dataset is in test mode.
            Defaults to False.
    """
zhangwenwei's avatar
zhangwenwei committed
48
49
50
    CLASSES = ('car', 'pedestrian', 'cyclist')

    def __init__(self,
zhangwenwei's avatar
zhangwenwei committed
51
                 data_root,
zhangwenwei's avatar
zhangwenwei committed
52
53
                 ann_file,
                 split,
zhangwenwei's avatar
zhangwenwei committed
54
                 pts_prefix='velodyne',
zhangwenwei's avatar
zhangwenwei committed
55
                 pipeline=None,
zhangwenwei's avatar
zhangwenwei committed
56
                 classes=None,
zhangwenwei's avatar
zhangwenwei committed
57
                 modality=None,
58
59
                 box_type_3d='LiDAR',
                 filter_empty_gt=True,
zhangwenwei's avatar
zhangwenwei committed
60
                 test_mode=False):
zhangwenwei's avatar
zhangwenwei committed
61
62
63
64
65
66
        super().__init__(
            data_root=data_root,
            ann_file=ann_file,
            pipeline=pipeline,
            classes=classes,
            modality=modality,
67
68
            box_type_3d=box_type_3d,
            filter_empty_gt=filter_empty_gt,
zhangwenwei's avatar
zhangwenwei committed
69
70
71
            test_mode=test_mode)

        self.root_split = os.path.join(self.data_root, split)
zhangwenwei's avatar
zhangwenwei committed
72
73
        assert self.modality is not None
        self.pcd_limit_range = [0, -40, -3, 70.4, 40, 0.0]
zhangwenwei's avatar
zhangwenwei committed
74
        self.pts_prefix = pts_prefix
zhangwenwei's avatar
zhangwenwei committed
75

zhangwenwei's avatar
zhangwenwei committed
76
77
78
79
    def _get_pts_filename(self, idx):
        pts_filename = osp.join(self.root_split, self.pts_prefix,
                                f'{idx:06d}.bin')
        return pts_filename
zhangwenwei's avatar
zhangwenwei committed
80

zhangwenwei's avatar
zhangwenwei committed
81
    def get_data_info(self, index):
82
83
84
85
86
87
        """Get data info according to the given index.

        Args:
            index (int): Index of the sample data to get.

        Returns:
zhangwenwei's avatar
zhangwenwei committed
88
89
            dict: Data information that will be passed to the data \
                preprocessing pipelines. It includes the following keys:
90

wangtai's avatar
wangtai committed
91
92
93
94
95
96
97
                - sample_idx (str): Sample index.
                - pts_filename (str): Filename of point clouds.
                - img_prefix (str | None): Prefix of image files.
                - img_info (dict): Image info.
                - lidar2img (list[np.ndarray], optional): Transformations \
                    from lidar to different cameras.
                - ann_info (dict): Annotation info.
98
        """
zhangwenwei's avatar
zhangwenwei committed
99
        info = self.data_infos[index]
zhangwenwei's avatar
zhangwenwei committed
100
        sample_idx = info['image']['image_idx']
zhangwenwei's avatar
zhangwenwei committed
101
        img_filename = os.path.join(self.data_root,
zhangwenwei's avatar
zhangwenwei committed
102
103
                                    info['image']['image_path'])

zhangwenwei's avatar
zhangwenwei committed
104
105
106
107
108
109
        # TODO: consider use torch.Tensor only
        rect = info['calib']['R0_rect'].astype(np.float32)
        Trv2c = info['calib']['Tr_velo_to_cam'].astype(np.float32)
        P2 = info['calib']['P2'].astype(np.float32)
        lidar2img = P2 @ rect @ Trv2c

zhangwenwei's avatar
zhangwenwei committed
110
        pts_filename = self._get_pts_filename(sample_idx)
zhangwenwei's avatar
zhangwenwei committed
111
112
        input_dict = dict(
            sample_idx=sample_idx,
zhangwenwei's avatar
zhangwenwei committed
113
            pts_filename=pts_filename,
zhangwenwei's avatar
zhangwenwei committed
114
115
            img_prefix=None,
            img_info=dict(filename=img_filename),
zhangwenwei's avatar
zhangwenwei committed
116
117
118
            lidar2img=lidar2img)

        if not self.test_mode:
zhangwenwei's avatar
zhangwenwei committed
119
            annos = self.get_ann_info(index)
zhangwenwei's avatar
zhangwenwei committed
120
            input_dict['ann_info'] = annos
zhangwenwei's avatar
zhangwenwei committed
121
122
123
124

        return input_dict

    def get_ann_info(self, index):
125
126
127
128
129
130
        """Get annotation info according to the given index.

        Args:
            index (int): Index of the annotation data to get.

        Returns:
zhangwenwei's avatar
zhangwenwei committed
131
            dict: annotation information consists of the following keys:
132

zhangwenwei's avatar
zhangwenwei committed
133
                - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`): \
wangtai's avatar
wangtai committed
134
135
136
137
138
                    3D ground truth bboxes.
                - gt_labels_3d (np.ndarray): Labels of ground truths.
                - gt_bboxes (np.ndarray): 2D ground truth bboxes.
                - gt_labels (np.ndarray): Labels of ground truths.
                - gt_names (list[str]): Class names of ground truths.
139
        """
zhangwenwei's avatar
zhangwenwei committed
140
        # Use index to get the annos, thus the evalhook could also use this api
zhangwenwei's avatar
zhangwenwei committed
141
        info = self.data_infos[index]
zhangwenwei's avatar
zhangwenwei committed
142
143
144
145
146
        rect = info['calib']['R0_rect'].astype(np.float32)
        Trv2c = info['calib']['Tr_velo_to_cam'].astype(np.float32)

        annos = info['annos']
        # we need other objects to avoid collision when sample
147
        annos = self.remove_dontcare(annos)
zhangwenwei's avatar
zhangwenwei committed
148
149
150
151
152
153
154
        loc = annos['location']
        dims = annos['dimensions']
        rots = annos['rotation_y']
        gt_names = annos['name']
        # print(gt_names, len(loc))
        gt_bboxes_3d = np.concatenate([loc, dims, rots[..., np.newaxis]],
                                      axis=1).astype(np.float32)
155
156
157

        # convert gt_bboxes_3d to velodyne coordinates
        gt_bboxes_3d = CameraInstance3DBoxes(gt_bboxes_3d).convert_to(
158
            self.box_mode_3d, np.linalg.inv(rect @ Trv2c))
zhangwenwei's avatar
zhangwenwei committed
159
160
161
        gt_bboxes = annos['bbox']

        selected = self.drop_arrays_by_name(gt_names, ['DontCare'])
162
        # gt_bboxes_3d = gt_bboxes_3d[selected].astype('float32')
zhangwenwei's avatar
zhangwenwei committed
163
164
165
166
167
168
169
170
171
172
173
        gt_bboxes = gt_bboxes[selected].astype('float32')
        gt_names = gt_names[selected]

        gt_labels = []
        for cat in gt_names:
            if cat in self.CLASSES:
                gt_labels.append(self.CLASSES.index(cat))
            else:
                gt_labels.append(-1)
        gt_labels = np.array(gt_labels)
        gt_labels_3d = copy.deepcopy(gt_labels)
zhangwenwei's avatar
zhangwenwei committed
174
175
176

        anns_results = dict(
            gt_bboxes_3d=gt_bboxes_3d,
zhangwenwei's avatar
zhangwenwei committed
177
            gt_labels_3d=gt_labels_3d,
zhangwenwei's avatar
zhangwenwei committed
178
            bboxes=gt_bboxes,
liyinhao's avatar
liyinhao committed
179
180
            labels=gt_labels,
            gt_names=gt_names)
zhangwenwei's avatar
zhangwenwei committed
181
182
183
        return anns_results

    def drop_arrays_by_name(self, gt_names, used_classes):
184
185
186
187
188
189
190
191
192
        """Drop irrelevant ground truths by name.

        Args:
            gt_names (list[str]): Names of ground truths.
            used_classes (list[str]): Classes of interest.

        Returns:
            np.ndarray: Indices of ground truths that will be dropped.
        """
zhangwenwei's avatar
zhangwenwei committed
193
194
195
196
197
        inds = [i for i, x in enumerate(gt_names) if x not in used_classes]
        inds = np.array(inds, dtype=np.int64)
        return inds

    def keep_arrays_by_name(self, gt_names, used_classes):
198
199
200
201
202
203
204
205
206
        """Keep useful ground truths by name.

        Args:
            gt_names (list[str]): Names of ground truths.
            used_classes (list[str]): Classes of interest.

        Returns:
            np.ndarray: Indices of ground truths that will be keeped.
        """
zhangwenwei's avatar
zhangwenwei committed
207
208
209
210
        inds = [i for i, x in enumerate(gt_names) if x in used_classes]
        inds = np.array(inds, dtype=np.int64)
        return inds

211
    def remove_dontcare(self, ann_info):
212
213
214
215
216
217
218
219
220
        """Remove annotations that do not need to be cared.

        Args:
            ann_info (dict): Dict of annotation infos. The ``'DontCare'``
                annotations will be removed according to ann_file['name'].

        Returns:
            dict: Annotations after filtering.
        """
221
222
223
224
225
226
227
228
229
        img_filtered_annotations = {}
        relevant_annotation_indices = [
            i for i, x in enumerate(ann_info['name']) if x != 'DontCare'
        ]
        for key in ann_info.keys():
            img_filtered_annotations[key] = (
                ann_info[key][relevant_annotation_indices])
        return img_filtered_annotations

230
231
232
233
    def format_results(self,
                       outputs,
                       pklfile_prefix=None,
                       submission_prefix=None):
234
235
236
237
238
239
240
241
242
243
244
245
246
        """Format the results to pkl file.

        Args:
            outputs (list[dict]): Testing results of the dataset.
            pklfile_prefix (str | None): The prefix of pkl files. It includes
                the file path and the prefix of filename, e.g., "a/b/prefix".
                If not specified, a temp file will be created. Default: None.
            submission_prefix (str | None): The prefix of submitted files. It
                includes the file path and the prefix of filename, e.g.,
                "a/b/prefix". If not specified, a temp file will be created.
                Default: None.

        Returns:
zhangwenwei's avatar
zhangwenwei committed
247
248
            tuple: (result_files, tmp_dir), result_files is a dict containing \
                the json filepaths, tmp_dir is the temporal directory created \
249
250
                for saving json files when jsonfile_prefix is not specified.
        """
251
252
253
254
255
256
        if pklfile_prefix is None:
            tmp_dir = tempfile.TemporaryDirectory()
            pklfile_prefix = osp.join(tmp_dir.name, 'results')
        else:
            tmp_dir = None

zhangwenwei's avatar
zhangwenwei committed
257
        if not isinstance(outputs[0], dict):
zhangwenwei's avatar
zhangwenwei committed
258
            result_files = self.bbox2result_kitti2d(outputs, self.CLASSES,
zhangwenwei's avatar
zhangwenwei committed
259
                                                    pklfile_prefix,
260
                                                    submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
        elif 'pts_bbox' in outputs[0] or 'img_bbox' in outputs[0]:
            result_files = dict()
            for name in outputs[0]:
                results_ = [out[name] for out in outputs]
                pklfile_prefix_ = pklfile_prefix + name
                if submission_prefix is not None:
                    submission_prefix_ = submission_prefix + name
                else:
                    submission_prefix_ = None
                if 'img' in name:
                    result_files = self.bbox2result_kitti2d(
                        results_, self.CLASSES, pklfile_prefix_,
                        submission_prefix_)
                else:
                    result_files_ = self.bbox2result_kitti(
                        results_, self.CLASSES, pklfile_prefix_,
                        submission_prefix_)
                result_files[name] = result_files_
zhangwenwei's avatar
zhangwenwei committed
279
        else:
zhangwenwei's avatar
zhangwenwei committed
280
            result_files = self.bbox2result_kitti(outputs, self.CLASSES,
281
282
                                                  pklfile_prefix,
                                                  submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
283
        return result_files, tmp_dir
zhangwenwei's avatar
zhangwenwei committed
284

285
286
287
288
289
    def evaluate(self,
                 results,
                 metric=None,
                 logger=None,
                 pklfile_prefix=None,
liyinhao's avatar
liyinhao committed
290
291
292
                 submission_prefix=None,
                 show=False,
                 out_dir=None):
293
294
295
        """Evaluation in KITTI protocol.

        Args:
wangtai's avatar
wangtai committed
296
            results (list[dict]): Testing results of the dataset.
297
298
299
300
301
302
303
304
            metric (str | list[str]): Metrics to be evaluated.
            logger (logging.Logger | str | None): Logger used for printing
                related information during evaluation. Default: None.
            pklfile_prefix (str | None): The prefix of pkl files. It includes
                the file path and the prefix of filename, e.g., "a/b/prefix".
                If not specified, a temp file will be created. Default: None.
            submission_prefix (str | None): The prefix of submission datas.
                If not specified, the submission data will not be generated.
liyinhao's avatar
liyinhao committed
305
306
307
308
            show (bool): Whether to visualize.
                Default: False.
            out_dir (str): Path to save the visualization results.
                Default: None.
309
310

        Returns:
wangtai's avatar
wangtai committed
311
            dict[str, float]: Results of each evaluation metric.
312
313
        """
        result_files, tmp_dir = self.format_results(results, pklfile_prefix)
zhangwenwei's avatar
zhangwenwei committed
314
        from mmdet3d.core.evaluation import kitti_eval
zhangwenwei's avatar
zhangwenwei committed
315
        gt_annos = [info['annos'] for info in self.data_infos]
zhangwenwei's avatar
zhangwenwei committed
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333

        if isinstance(result_files, dict):
            ap_dict = dict()
            for name, result_files_ in result_files.items():
                eval_types = ['bbox', 'bev', '3d']
                if 'img' in name:
                    eval_types = ['bbox']
                ap_result_str, ap_dict_ = kitti_eval(
                    gt_annos,
                    result_files_,
                    self.CLASSES,
                    eval_types=eval_types)
                for ap_type, ap in ap_dict_.items():
                    ap_dict[f'{name}/{ap_type}'] = float('{:.4f}'.format(ap))

                print_log(
                    f'Results of {name}:\n' + ap_result_str, logger=logger)

zhangwenwei's avatar
zhangwenwei committed
334
        else:
zhangwenwei's avatar
zhangwenwei committed
335
336
337
338
339
340
341
342
            if metric == 'img_bbox':
                ap_result_str, ap_dict = kitti_eval(
                    gt_annos, result_files, self.CLASSES, eval_types=['bbox'])
            else:
                ap_result_str, ap_dict = kitti_eval(gt_annos, result_files,
                                                    self.CLASSES)
            print_log('\n' + ap_result_str, logger=logger)

343
344
        if tmp_dir is not None:
            tmp_dir.cleanup()
liyinhao's avatar
liyinhao committed
345
346
        if show:
            self.show(results, out_dir)
347
        return ap_dict
348
349
350
351
352
353

    def bbox2result_kitti(self,
                          net_outputs,
                          class_names,
                          pklfile_prefix=None,
                          submission_prefix=None):
zhangwenwei's avatar
zhangwenwei committed
354
        assert len(net_outputs) == len(self.data_infos)
355
356
        if submission_prefix is not None:
            mmcv.mkdir_or_exist(submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
357
358

        det_annos = []
zhangwenwei's avatar
zhangwenwei committed
359
        print('\nConverting prediction to KITTI format')
zhangwenwei's avatar
zhangwenwei committed
360
361
362
        for idx, pred_dicts in enumerate(
                mmcv.track_iter_progress(net_outputs)):
            annos = []
zhangwenwei's avatar
zhangwenwei committed
363
            info = self.data_infos[idx]
zhangwenwei's avatar
zhangwenwei committed
364
            sample_idx = info['image']['image_idx']
zhangwenwei's avatar
zhangwenwei committed
365
            image_shape = info['image']['image_shape'][:2]
zhangwenwei's avatar
zhangwenwei committed
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

            box_dict = self.convert_valid_bboxes(pred_dicts, info)
            if len(box_dict['bbox']) > 0:
                box_2d_preds = box_dict['bbox']
                box_preds = box_dict['box3d_camera']
                scores = box_dict['scores']
                box_preds_lidar = box_dict['box3d_lidar']
                label_preds = box_dict['label_preds']

                anno = {
                    'name': [],
                    'truncated': [],
                    'occluded': [],
                    'alpha': [],
                    'bbox': [],
                    'dimensions': [],
                    'location': [],
                    'rotation_y': [],
                    'score': []
                }

                for box, box_lidar, bbox, score, label in zip(
                        box_preds, box_preds_lidar, box_2d_preds, scores,
                        label_preds):
                    bbox[2:] = np.minimum(bbox[2:], image_shape[::-1])
                    bbox[:2] = np.maximum(bbox[:2], [0, 0])
                    anno['name'].append(class_names[int(label)])
                    anno['truncated'].append(0.0)
                    anno['occluded'].append(0)
                    anno['alpha'].append(
                        -np.arctan2(-box_lidar[1], box_lidar[0]) + box[6])
                    anno['bbox'].append(bbox)
                    anno['dimensions'].append(box[3:6])
                    anno['location'].append(box[:3])
                    anno['rotation_y'].append(box[6])
                    anno['score'].append(score)

                anno = {k: np.stack(v) for k, v in anno.items()}
                annos.append(anno)

                if submission_prefix is not None:
                    curr_file = f'{submission_prefix}/{sample_idx:06d}.txt'
                    with open(curr_file, 'w') as f:
                        bbox = anno['bbox']
                        loc = anno['location']
                        dims = anno['dimensions']  # lhw -> hwl

                        for idx in range(len(bbox)):
                            print(
                                '{} -1 -1 {:.4f} {:.4f} {:.4f} {:.4f} '
                                '{:.4f} {:.4f} {:.4f} '
                                '{:.4f} {:.4f} {:.4f} {:.4f} {:.4f} {:.4f}'.
                                format(anno['name'][idx], anno['alpha'][idx],
                                       bbox[idx][0], bbox[idx][1],
                                       bbox[idx][2], bbox[idx][3],
                                       dims[idx][1], dims[idx][2],
                                       dims[idx][0], loc[idx][0], loc[idx][1],
                                       loc[idx][2], anno['rotation_y'][idx],
                                       anno['score'][idx]),
                                file=f)
            else:
                annos.append({
                    'name': np.array([]),
                    'truncated': np.array([]),
                    'occluded': np.array([]),
                    'alpha': np.array([]),
                    'bbox': np.zeros([0, 4]),
                    'dimensions': np.zeros([0, 3]),
                    'location': np.zeros([0, 3]),
                    'rotation_y': np.array([]),
                    'score': np.array([]),
                })
            annos[-1]['sample_idx'] = np.array(
                [sample_idx] * len(annos[-1]['score']), dtype=np.int64)
zhangwenwei's avatar
zhangwenwei committed
440
441
442

            det_annos += annos

443
444
445
        if pklfile_prefix is not None:
            if not pklfile_prefix.endswith(('.pkl', '.pickle')):
                out = f'{pklfile_prefix}.pkl'
zhangwenwei's avatar
zhangwenwei committed
446
447
448
449
450
451
452
453
            mmcv.dump(det_annos, out)
            print('Result is saved to %s' % out)

        return det_annos

    def bbox2result_kitti2d(self,
                            net_outputs,
                            class_names,
454
455
                            pklfile_prefix=None,
                            submission_prefix=None):
zhangwenwei's avatar
zhangwenwei committed
456
457
        """Convert 2D detection results to kitti format for evaluation and test
        submission.
zhangwenwei's avatar
zhangwenwei committed
458
459

        Args:
460
            net_outputs (list[np.ndarray]): list of array storing the
wangtai's avatar
wangtai committed
461
                bbox and score
462
            class_nanes (list[String]): A list of class names
463
464
            pklfile_prefix (str | None): The prefix of pkl file.
            submission_prefix (str | None): The prefix of submission file.
zhangwenwei's avatar
zhangwenwei committed
465

466
        Returns:
467
            list[dict]: A list of dict have the kitti format
zhangwenwei's avatar
zhangwenwei committed
468
        """
zhangwenwei's avatar
zhangwenwei committed
469
        assert len(net_outputs) == len(self.data_infos)
zhangwenwei's avatar
zhangwenwei committed
470
471

        det_annos = []
zhangwenwei's avatar
zhangwenwei committed
472
        print('\nConverting prediction to KITTI format')
zhangwenwei's avatar
zhangwenwei committed
473
474
475
476
477
478
479
480
481
482
483
484
485
        for i, bboxes_per_sample in enumerate(
                mmcv.track_iter_progress(net_outputs)):
            annos = []
            anno = dict(
                name=[],
                truncated=[],
                occluded=[],
                alpha=[],
                bbox=[],
                dimensions=[],
                location=[],
                rotation_y=[],
                score=[])
zhangwenwei's avatar
zhangwenwei committed
486
            sample_idx = self.data_infos[i]['image']['image_idx']
zhangwenwei's avatar
zhangwenwei committed
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

            num_example = 0
            for label in range(len(bboxes_per_sample)):
                bbox = bboxes_per_sample[label]
                for i in range(bbox.shape[0]):
                    anno['name'].append(class_names[int(label)])
                    anno['truncated'].append(0.0)
                    anno['occluded'].append(0)
                    anno['alpha'].append(0.0)
                    anno['bbox'].append(bbox[i, :4])
                    # set dimensions (height, width, length) to zero
                    anno['dimensions'].append(
                        np.zeros(shape=[3], dtype=np.float32))
                    # set the 3D translation to (-1000, -1000, -1000)
                    anno['location'].append(
                        np.ones(shape=[3], dtype=np.float32) * (-1000.0))
                    anno['rotation_y'].append(0.0)
                    anno['score'].append(bbox[i, 4])
                    num_example += 1

            if num_example == 0:
                annos.append(
                    dict(
                        name=np.array([]),
                        truncated=np.array([]),
                        occluded=np.array([]),
                        alpha=np.array([]),
                        bbox=np.zeros([0, 4]),
                        dimensions=np.zeros([0, 3]),
                        location=np.zeros([0, 3]),
                        rotation_y=np.array([]),
                        score=np.array([]),
                    ))
            else:
                anno = {k: np.stack(v) for k, v in anno.items()}
                annos.append(anno)

            annos[-1]['sample_idx'] = np.array(
                [sample_idx] * num_example, dtype=np.int64)
            det_annos += annos

528
529
530
531
532
533
534
535
        if pklfile_prefix is not None:
            # save file in pkl format
            pklfile_path = (
                pklfile_prefix[:-4] if pklfile_prefix.endswith(
                    ('.pkl', '.pickle')) else pklfile_prefix)
            mmcv.dump(det_annos, pklfile_path)

        if submission_prefix is not None:
zhangwenwei's avatar
zhangwenwei committed
536
            # save file in submission format
537
538
            mmcv.mkdir_or_exist(submission_prefix)
            print(f'Saving KITTI submission to {submission_prefix}')
zhangwenwei's avatar
zhangwenwei committed
539
            for i, anno in enumerate(det_annos):
zhangwenwei's avatar
zhangwenwei committed
540
                sample_idx = self.data_infos[i]['image']['image_idx']
541
                cur_det_file = f'{submission_prefix}/{sample_idx:06d}.txt'
zhangwenwei's avatar
zhangwenwei committed
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
                with open(cur_det_file, 'w') as f:
                    bbox = anno['bbox']
                    loc = anno['location']
                    dims = anno['dimensions'][::-1]  # lhw -> hwl
                    for idx in range(len(bbox)):
                        print(
                            '{} -1 -1 {:4f} {:4f} {:4f} {:4f} {:4f} {:4f} '
                            '{:4f} {:4f} {:4f} {:4f} {:4f} {:4f} {:4f}'.format(
                                anno['name'][idx],
                                anno['alpha'][idx],
                                *bbox[idx],  # 4 float
                                *dims[idx],  # 3 float
                                *loc[idx],  # 3 float
                                anno['rotation_y'][idx],
                                anno['score'][idx]),
                            file=f,
                        )
559
            print('Result is saved to {}'.format(submission_prefix))
zhangwenwei's avatar
zhangwenwei committed
560
561
562
563
564

        return det_annos

    def convert_valid_bboxes(self, box_dict, info):
        # TODO: refactor this function
565
566
567
        box_preds = box_dict['boxes_3d']
        scores = box_dict['scores_3d']
        labels = box_dict['labels_3d']
zhangwenwei's avatar
zhangwenwei committed
568
        sample_idx = info['image']['image_idx']
569
570
571
        # TODO: remove the hack of yaw
        box_preds.tensor[:, -1] = box_preds.tensor[:, -1] - np.pi
        box_preds.limit_yaw(offset=0.5, period=np.pi * 2)
zhangwenwei's avatar
zhangwenwei committed
572

573
        if len(box_preds) == 0:
zhangwenwei's avatar
zhangwenwei committed
574
            return dict(
575
576
577
578
579
580
                bbox=np.zeros([0, 4]),
                box3d_camera=np.zeros([0, 7]),
                box3d_lidar=np.zeros([0, 7]),
                scores=np.zeros([0]),
                label_preds=np.zeros([0, 4]),
                sample_idx=sample_idx)
zhangwenwei's avatar
zhangwenwei committed
581
582
583
584
585

        rect = info['calib']['R0_rect'].astype(np.float32)
        Trv2c = info['calib']['Tr_velo_to_cam'].astype(np.float32)
        P2 = info['calib']['P2'].astype(np.float32)
        img_shape = info['image']['image_shape']
586
587
588
589
590
        P2 = box_preds.tensor.new_tensor(P2)

        box_preds_camera = box_preds.convert_to(Box3DMode.CAM, rect @ Trv2c)

        box_corners = box_preds_camera.corners
zhangwenwei's avatar
zhangwenwei committed
591
        box_corners_in_image = points_cam2img(box_corners, P2)
zhangwenwei's avatar
zhangwenwei committed
592
593
594
595
596
        # box_corners_in_image: [N, 8, 2]
        minxy = torch.min(box_corners_in_image, dim=1)[0]
        maxxy = torch.max(box_corners_in_image, dim=1)[0]
        box_2d_preds = torch.cat([minxy, maxxy], dim=1)
        # Post-processing
597
598
599
600
601
602
603
604
605
606
        # check box_preds_camera
        image_shape = box_preds.tensor.new_tensor(img_shape)
        valid_cam_inds = ((box_preds_camera.tensor[:, 0] < image_shape[1]) &
                          (box_preds_camera.tensor[:, 1] < image_shape[0]) &
                          (box_preds_camera.tensor[:, 2] > 0) &
                          (box_preds_camera.tensor[:, 3] > 0))
        # check box_preds
        limit_range = box_preds.tensor.new_tensor(self.pcd_limit_range)
        valid_pcd_inds = ((box_preds.center > limit_range[:3]) &
                          (box_preds.center < limit_range[3:]))
zhangwenwei's avatar
zhangwenwei committed
607
608
609
610
611
        valid_inds = valid_cam_inds & valid_pcd_inds.all(-1)

        if valid_inds.sum() > 0:
            return dict(
                bbox=box_2d_preds[valid_inds, :].numpy(),
612
613
614
615
                box3d_camera=box_preds_camera[valid_inds].tensor.numpy(),
                box3d_lidar=box_preds[valid_inds].tensor.numpy(),
                scores=scores[valid_inds].numpy(),
                label_preds=labels[valid_inds].numpy(),
zhangwenwei's avatar
zhangwenwei committed
616
617
618
619
                sample_idx=sample_idx,
            )
        else:
            return dict(
620
621
622
623
624
                bbox=np.zeros([0, 4]),
                box3d_camera=np.zeros([0, 7]),
                box3d_lidar=np.zeros([0, 7]),
                scores=np.zeros([0]),
                label_preds=np.zeros([0, 4]),
zhangwenwei's avatar
zhangwenwei committed
625
626
                sample_idx=sample_idx,
            )
liyinhao's avatar
liyinhao committed
627
628

    def show(self, results, out_dir):
629
630
631
        """Results visualization.

        Args:
wangtai's avatar
wangtai committed
632
            results (list[dict]): List of bounding boxes results.
633
634
            out_dir (str): Output directory of visualization result.
        """
liyinhao's avatar
liyinhao committed
635
636
        assert out_dir is not None, 'Expect out_dir, got none.'
        for i, result in enumerate(results):
liyinhao's avatar
liyinhao committed
637
            example = self.prepare_test_data(i)
liyinhao's avatar
liyinhao committed
638
639
640
            data_info = self.data_infos[i]
            pts_path = data_info['point_cloud']['velodyne_path']
            file_name = osp.split(pts_path)[-1].split('.')[0]
liyinhao's avatar
liyinhao committed
641
            # for now we convert points into depth mode
liyinhao's avatar
liyinhao committed
642
            points = example['points'][0]._data.numpy()
liyinhao's avatar
liyinhao committed
643
644
645
646
647
648
649
650
651
652
653
            points = points[..., [1, 0, 2]]
            points[..., 0] *= -1
            gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor
            gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
                                          Box3DMode.DEPTH)
            gt_bboxes[..., 2] += gt_bboxes[..., 5] / 2
            pred_bboxes = result['boxes_3d'].tensor.numpy()
            pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
                                            Box3DMode.DEPTH)
            pred_bboxes[..., 2] += pred_bboxes[..., 5] / 2
            show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)