kitti_dataset.py 27.2 KB
Newer Older
dingchang's avatar
dingchang committed
1
# Copyright (c) OpenMMLab. All rights reserved.
zhangwenwei's avatar
zhangwenwei committed
2
import copy
zhangwenwei's avatar
zhangwenwei committed
3
import tempfile
4
from os import path as osp
jshilong's avatar
jshilong committed
5
from typing import Callable, List, Optional, Union
6
7
8

import mmcv
import numpy as np
zhangwenwei's avatar
zhangwenwei committed
9
import torch
zhangwenwei's avatar
zhangwenwei committed
10
from mmcv.utils import print_log
zhangwenwei's avatar
zhangwenwei committed
11

jshilong's avatar
jshilong committed
12
from mmdet3d.datasets import DATASETS
13
from ..core import show_multi_modality_result, show_result
14
from ..core.bbox import (Box3DMode, CameraInstance3DBoxes, Coord3DMode,
15
                         LiDARInstance3DBoxes, points_cam2img)
jshilong's avatar
jshilong committed
16
from .det3d_dataset import Det3DDataset
17
from .pipelines import Compose
zhangwenwei's avatar
zhangwenwei committed
18
19


20
@DATASETS.register_module()
jshilong's avatar
jshilong committed
21
class KittiDataset(Det3DDataset):
zhangwenwei's avatar
zhangwenwei committed
22
    r"""KITTI Dataset.
wangtai's avatar
wangtai committed
23

zhangwenwei's avatar
zhangwenwei committed
24
25
    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
26
27
28
29
30
31
32

    Args:
        data_root (str): Path of dataset root.
        ann_file (str): Path of annotation file.
        pipeline (list[dict], optional): Pipeline used for data processing.
            Defaults to None.
        modality (dict, optional): Modality to specify the sensor data used
jshilong's avatar
jshilong committed
33
            as input. Defaults to `dict(use_lidar=True)`.
wangtai's avatar
wangtai committed
34
35
36
37
38
        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
39
40
41
            - 'LiDAR': Box in LiDAR coordinates.
            - 'Depth': Box in depth coordinates, usually for indoor dataset.
            - 'Camera': Box in camera coordinates.
wangtai's avatar
wangtai committed
42
43
44
45
        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.
46
47
48
        pcd_limit_range (list, optional): The range of point cloud used to
            filter invalid predicted boxes.
            Default: [0, -40, -3, 70.4, 40, 0.0].
wangtai's avatar
wangtai committed
49
    """
jshilong's avatar
jshilong committed
50
51
    # TODO: use full classes of kitti
    METAINFO = {'CLASSES': ('Pedestrian', 'Cyclist', 'Car')}
zhangwenwei's avatar
zhangwenwei committed
52
53

    def __init__(self,
jshilong's avatar
jshilong committed
54
55
56
                 data_root: str,
                 ann_file: str,
                 pipeline: List[Union[dict, Callable]] = [],
jshilong's avatar
jshilong committed
57
                 modality: Optional[dict] = dict(use_lidar=True),
jshilong's avatar
jshilong committed
58
59
60
61
                 box_type_3d: str = 'LiDAR',
                 filter_empty_gt: bool = True,
                 test_mode: bool = False,
                 pcd_limit_range: List[float] = [0, -40, -3, 70.4, 40, 0.0],
62
                 **kwargs):
jshilong's avatar
jshilong committed
63
64

        self.pcd_limit_range = pcd_limit_range
zhangwenwei's avatar
zhangwenwei committed
65
66
67
68
69
        super().__init__(
            data_root=data_root,
            ann_file=ann_file,
            pipeline=pipeline,
            modality=modality,
70
71
            box_type_3d=box_type_3d,
            filter_empty_gt=filter_empty_gt,
72
73
            test_mode=test_mode,
            **kwargs)
zhangwenwei's avatar
zhangwenwei committed
74
        assert self.modality is not None
jshilong's avatar
jshilong committed
75
        assert box_type_3d.lower() in ('lidar', 'camera')
zhangwenwei's avatar
zhangwenwei committed
76

jshilong's avatar
jshilong committed
77
78
    def parse_data_info(self, info: dict) -> dict:
        """Process the raw data info.
zhangwenwei's avatar
zhangwenwei committed
79

jshilong's avatar
jshilong committed
80
81
        The only difference with it in `Det3DDataset`
        is the specific process for `plane`.
82
83

        Args:
jshilong's avatar
jshilong committed
84
            info (dict): Raw info dict.
85
86

        Returns:
jshilong's avatar
jshilong committed
87
88
            dict: Has `ann_info` in training stage. And
            all path has been converted to absolute path.
89
        """
jshilong's avatar
jshilong committed
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
        if self.modality['use_lidar']:
            if 'plane' in info:
                # convert ground plane to velodyne coordinates
                plane = np.array(info['plane'])
                lidar2cam = np.array(info['lidar_points']['lidar2cam'])
                reverse = np.linalg.inv(lidar2cam)

                (plane_norm_cam, plane_off_cam) = (plane[:3],
                                                   -plane[:3] * plane[3])
                plane_norm_lidar = \
                    (reverse[:3, :3] @ plane_norm_cam[:, None])[:, 0]
                plane_off_lidar = (
                    reverse[:3, :3] @ plane_off_cam[:, None][:, 0] +
                    reverse[:3, 3])
                plane_lidar = np.zeros_like(plane_norm_lidar, shape=(4, ))
                plane_lidar[:3] = plane_norm_lidar
                plane_lidar[3] = -plane_norm_lidar.T @ plane_off_lidar
            else:
                plane_lidar = None
zhangwenwei's avatar
zhangwenwei committed
109

jshilong's avatar
jshilong committed
110
            info['plane'] = plane_lidar
zhangwenwei's avatar
zhangwenwei committed
111

jshilong's avatar
jshilong committed
112
        info = super().parse_data_info(info)
zhangwenwei's avatar
zhangwenwei committed
113

jshilong's avatar
jshilong committed
114
        return info
zhangwenwei's avatar
zhangwenwei committed
115

jshilong's avatar
jshilong committed
116
    def parse_ann_info(self, info):
117
118
119
        """Get annotation info according to the given index.

        Args:
jshilong's avatar
jshilong committed
120
            info (dict): Data information of single data sample.
121
122

        Returns:
zhangwenwei's avatar
zhangwenwei committed
123
            dict: annotation information consists of the following keys:
124

jshilong's avatar
jshilong committed
125
                - bboxes_3d (:obj:`LiDARInstance3DBoxes`):
wangtai's avatar
wangtai committed
126
                    3D ground truth bboxes.
jshilong's avatar
jshilong committed
127
                - bbox_labels_3d (np.ndarray): Labels of ground truths.
wangtai's avatar
wangtai committed
128
129
                - gt_bboxes (np.ndarray): 2D ground truth bboxes.
                - gt_labels (np.ndarray): Labels of ground truths.
130
131
                - difficulty (int): Difficulty defined by KITTI.
                    0, 1, 2 represent xxxxx respectively.
132
        """
133

jshilong's avatar
jshilong committed
134
        ann_info = super().parse_ann_info(info)
135

jshilong's avatar
jshilong committed
136
137
138
139
140
        bbox_labels_3d = ann_info['gt_labels_3d']
        bbox_labels_3d = np.array(bbox_labels_3d)
        ann_info['gt_labels_3d'] = bbox_labels_3d
        ann_info['gt_labels'] = copy.deepcopy(ann_info['gt_labels_3d'])
        ann_info = self._remove_dontcare(ann_info)
zhangwenwei's avatar
zhangwenwei committed
141

jshilong's avatar
jshilong committed
142
143
144
145
146
147
148
        # in kitti, lidar2cam = R0_rect @ Tr_velo_to_cam
        lidar2cam = np.array(info['images']['CAM2']['lidar2cam'])
        # convert gt_bboxes_3d to velodyne coordinates with `lidar2cam`
        gt_bboxes_3d = CameraInstance3DBoxes(
            ann_info['gt_bboxes_3d']).convert_to(self.box_mode_3d,
                                                 np.linalg.inv(lidar2cam))
        ann_info['gt_bboxes_3d'] = gt_bboxes_3d
zhangwenwei's avatar
zhangwenwei committed
149

jshilong's avatar
jshilong committed
150
        return ann_info
151

152
153
154
155
    def format_results(self,
                       outputs,
                       pklfile_prefix=None,
                       submission_prefix=None):
156
157
158
159
        """Format the results to pkl file.

        Args:
            outputs (list[dict]): Testing results of the dataset.
160
            pklfile_prefix (str): The prefix of pkl files. It includes
161
162
                the file path and the prefix of filename, e.g., "a/b/prefix".
                If not specified, a temp file will be created. Default: None.
163
            submission_prefix (str): The prefix of submitted files. It
164
165
166
167
168
                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:
169
170
            tuple: (result_files, tmp_dir), result_files is a dict containing
                the json filepaths, tmp_dir is the temporal directory created
171
172
                for saving json files when jsonfile_prefix is not specified.
        """
173
174
175
176
177
178
        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
179
        if not isinstance(outputs[0], dict):
zhangwenwei's avatar
zhangwenwei committed
180
            result_files = self.bbox2result_kitti2d(outputs, self.CLASSES,
zhangwenwei's avatar
zhangwenwei committed
181
                                                    pklfile_prefix,
182
                                                    submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
        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
201
        else:
zhangwenwei's avatar
zhangwenwei committed
202
            result_files = self.bbox2result_kitti(outputs, self.CLASSES,
203
204
                                                  pklfile_prefix,
                                                  submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
205
        return result_files, tmp_dir
zhangwenwei's avatar
zhangwenwei committed
206

207
208
209
210
211
    def evaluate(self,
                 results,
                 metric=None,
                 logger=None,
                 pklfile_prefix=None,
liyinhao's avatar
liyinhao committed
212
213
                 submission_prefix=None,
                 show=False,
214
215
                 out_dir=None,
                 pipeline=None):
216
217
218
        """Evaluation in KITTI protocol.

        Args:
wangtai's avatar
wangtai committed
219
            results (list[dict]): Testing results of the dataset.
220
221
222
            metric (str | list[str], optional): Metrics to be evaluated.
                Default: None.
            logger (logging.Logger | str, optional): Logger used for printing
223
                related information during evaluation. Default: None.
224
            pklfile_prefix (str, optional): The prefix of pkl files, including
225
226
                the file path and the prefix of filename, e.g., "a/b/prefix".
                If not specified, a temp file will be created. Default: None.
227
            submission_prefix (str, optional): The prefix of submission data.
228
                If not specified, the submission data will not be generated.
229
                Default: None.
230
            show (bool, optional): Whether to visualize.
liyinhao's avatar
liyinhao committed
231
                Default: False.
232
            out_dir (str, optional): Path to save the visualization results.
liyinhao's avatar
liyinhao committed
233
                Default: None.
234
235
            pipeline (list[dict], optional): raw data loading for showing.
                Default: None.
236
237

        Returns:
wangtai's avatar
wangtai committed
238
            dict[str, float]: Results of each evaluation metric.
239
240
        """
        result_files, tmp_dir = self.format_results(results, pklfile_prefix)
zhangwenwei's avatar
zhangwenwei committed
241
        from mmdet3d.core.evaluation import kitti_eval
zhangwenwei's avatar
zhangwenwei committed
242
        gt_annos = [info['annos'] for info in self.data_infos]
zhangwenwei's avatar
zhangwenwei committed
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260

        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
261
        else:
zhangwenwei's avatar
zhangwenwei committed
262
263
264
265
266
267
268
269
            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)

270
271
        if tmp_dir is not None:
            tmp_dir.cleanup()
272
273
        if show or out_dir:
            self.show(results, out_dir, show=show, pipeline=pipeline)
274
        return ap_dict
275
276
277
278
279
280

    def bbox2result_kitti(self,
                          net_outputs,
                          class_names,
                          pklfile_prefix=None,
                          submission_prefix=None):
281
282
283
284
        """Convert 3D detection results to kitti format for evaluation and test
        submission.

        Args:
285
            net_outputs (list[np.ndarray]): List of array storing the
286
287
                inferenced bounding boxes and scores.
            class_names (list[String]): A list of class names.
288
289
            pklfile_prefix (str): The prefix of pkl file.
            submission_prefix (str): The prefix of submission file.
290
291
292
293

        Returns:
            list[dict]: A list of dictionaries with the kitti format.
        """
Wenwei Zhang's avatar
Wenwei Zhang committed
294
295
        assert len(net_outputs) == len(self.data_infos), \
            'invalid list length of network outputs'
296
297
        if submission_prefix is not None:
            mmcv.mkdir_or_exist(submission_prefix)
zhangwenwei's avatar
zhangwenwei committed
298
299

        det_annos = []
zhangwenwei's avatar
zhangwenwei committed
300
        print('\nConverting prediction to KITTI format')
zhangwenwei's avatar
zhangwenwei committed
301
302
303
        for idx, pred_dicts in enumerate(
                mmcv.track_iter_progress(net_outputs)):
            annos = []
zhangwenwei's avatar
zhangwenwei committed
304
            info = self.data_infos[idx]
zhangwenwei's avatar
zhangwenwei committed
305
            sample_idx = info['image']['image_idx']
zhangwenwei's avatar
zhangwenwei committed
306
            image_shape = info['image']['image_shape'][:2]
zhangwenwei's avatar
zhangwenwei committed
307
            box_dict = self.convert_valid_bboxes(pred_dicts, info)
xiliu8006's avatar
xiliu8006 committed
308
309
310
311
312
313
314
315
316
317
318
            anno = {
                'name': [],
                'truncated': [],
                'occluded': [],
                'alpha': [],
                'bbox': [],
                'dimensions': [],
                'location': [],
                'rotation_y': [],
                'score': []
            }
zhangwenwei's avatar
zhangwenwei committed
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
            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']

                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)
            else:
xiliu8006's avatar
xiliu8006 committed
345
                anno = {
zhangwenwei's avatar
zhangwenwei committed
346
347
348
349
350
351
352
353
354
                    '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([]),
xiliu8006's avatar
xiliu8006 committed
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
                }
                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)

zhangwenwei's avatar
zhangwenwei committed
378
379
            annos[-1]['sample_idx'] = np.array(
                [sample_idx] * len(annos[-1]['score']), dtype=np.int64)
zhangwenwei's avatar
zhangwenwei committed
380
381
382

            det_annos += annos

383
384
385
        if pklfile_prefix is not None:
            if not pklfile_prefix.endswith(('.pkl', '.pickle')):
                out = f'{pklfile_prefix}.pkl'
zhangwenwei's avatar
zhangwenwei committed
386
            mmcv.dump(det_annos, out)
Wenwei Zhang's avatar
Wenwei Zhang committed
387
            print(f'Result is saved to {out}.')
zhangwenwei's avatar
zhangwenwei committed
388
389
390
391
392
393

        return det_annos

    def bbox2result_kitti2d(self,
                            net_outputs,
                            class_names,
394
395
                            pklfile_prefix=None,
                            submission_prefix=None):
zhangwenwei's avatar
zhangwenwei committed
396
397
        """Convert 2D detection results to kitti format for evaluation and test
        submission.
zhangwenwei's avatar
zhangwenwei committed
398
399

        Args:
400
            net_outputs (list[np.ndarray]): List of array storing the
401
402
                inferenced bounding boxes and scores.
            class_names (list[String]): A list of class names.
403
404
            pklfile_prefix (str): The prefix of pkl file.
            submission_prefix (str): The prefix of submission file.
zhangwenwei's avatar
zhangwenwei committed
405

406
        Returns:
407
            list[dict]: A list of dictionaries have the kitti format
zhangwenwei's avatar
zhangwenwei committed
408
        """
Wenwei Zhang's avatar
Wenwei Zhang committed
409
410
        assert len(net_outputs) == len(self.data_infos), \
            'invalid list length of network outputs'
zhangwenwei's avatar
zhangwenwei committed
411
        det_annos = []
zhangwenwei's avatar
zhangwenwei committed
412
        print('\nConverting prediction to KITTI format')
zhangwenwei's avatar
zhangwenwei committed
413
414
415
416
417
418
419
420
421
422
423
424
425
        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
426
            sample_idx = self.data_infos[i]['image']['image_idx']
zhangwenwei's avatar
zhangwenwei committed
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

            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

468
469
470
471
472
473
474
475
        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
476
            # save file in submission format
477
478
            mmcv.mkdir_or_exist(submission_prefix)
            print(f'Saving KITTI submission to {submission_prefix}')
zhangwenwei's avatar
zhangwenwei committed
479
            for i, anno in enumerate(det_annos):
zhangwenwei's avatar
zhangwenwei committed
480
                sample_idx = self.data_infos[i]['image']['image_idx']
481
                cur_det_file = f'{submission_prefix}/{sample_idx:06d}.txt'
zhangwenwei's avatar
zhangwenwei committed
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
                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,
                        )
499
            print(f'Result is saved to {submission_prefix}')
zhangwenwei's avatar
zhangwenwei committed
500
501
502
503

        return det_annos

    def convert_valid_bboxes(self, box_dict, info):
504
505
506
507
508
509
510
511
512
513
514
515
516
517
        """Convert the predicted boxes into valid ones.

        Args:
            box_dict (dict): Box dictionaries to be converted.

                - boxes_3d (:obj:`LiDARInstance3DBoxes`): 3D bounding boxes.
                - scores_3d (torch.Tensor): Scores of boxes.
                - labels_3d (torch.Tensor): Class labels of boxes.
            info (dict): Data info.

        Returns:
            dict: Valid predicted boxes.

                - bbox (np.ndarray): 2D bounding boxes.
518
                - box3d_camera (np.ndarray): 3D bounding boxes in
519
                    camera coordinate.
520
                - box3d_lidar (np.ndarray): 3D bounding boxes in
521
522
523
524
525
                    LiDAR coordinate.
                - scores (np.ndarray): Scores of boxes.
                - label_preds (np.ndarray): Class label predictions.
                - sample_idx (int): Sample index.
        """
zhangwenwei's avatar
zhangwenwei committed
526
        # TODO: refactor this function
527
528
529
        box_preds = box_dict['boxes_3d']
        scores = box_dict['scores_3d']
        labels = box_dict['labels_3d']
zhangwenwei's avatar
zhangwenwei committed
530
        sample_idx = info['image']['image_idx']
531
        box_preds.limit_yaw(offset=0.5, period=np.pi * 2)
zhangwenwei's avatar
zhangwenwei committed
532

533
        if len(box_preds) == 0:
zhangwenwei's avatar
zhangwenwei committed
534
            return dict(
535
536
537
538
539
540
                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
541
542
543
544
545

        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']
546
547
548
549
550
        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
551
        box_corners_in_image = points_cam2img(box_corners, P2)
zhangwenwei's avatar
zhangwenwei committed
552
553
554
555
556
        # 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
557
558
        # check box_preds_camera
        image_shape = box_preds.tensor.new_tensor(img_shape)
twang's avatar
twang committed
559
560
561
        valid_cam_inds = ((box_2d_preds[:, 0] < image_shape[1]) &
                          (box_2d_preds[:, 1] < image_shape[0]) &
                          (box_2d_preds[:, 2] > 0) & (box_2d_preds[:, 3] > 0))
562
563
564
565
        # 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
566
567
568
569
570
        valid_inds = valid_cam_inds & valid_pcd_inds.all(-1)

        if valid_inds.sum() > 0:
            return dict(
                bbox=box_2d_preds[valid_inds, :].numpy(),
571
572
573
574
                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(),
575
                sample_idx=sample_idx)
zhangwenwei's avatar
zhangwenwei committed
576
577
        else:
            return dict(
578
579
580
581
582
                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]),
583
                sample_idx=sample_idx)
liyinhao's avatar
liyinhao committed
584

585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
    def _build_default_pipeline(self):
        """Build the default pipeline for this dataset."""
        pipeline = [
            dict(
                type='LoadPointsFromFile',
                coord_type='LIDAR',
                load_dim=4,
                use_dim=4,
                file_client_args=dict(backend='disk')),
            dict(
                type='DefaultFormatBundle3D',
                class_names=self.CLASSES,
                with_label=False),
            dict(type='Collect3D', keys=['points'])
        ]
        if self.modality['use_camera']:
            pipeline.insert(0, dict(type='LoadImageFromFile'))
        return Compose(pipeline)

    def show(self, results, out_dir, show=True, pipeline=None):
605
606
607
        """Results visualization.

        Args:
wangtai's avatar
wangtai committed
608
            results (list[dict]): List of bounding boxes results.
609
            out_dir (str): Output directory of visualization result.
610
611
            show (bool): Whether to visualize the results online.
                Default: False.
612
613
            pipeline (list[dict], optional): raw data loading for showing.
                Default: None.
614
        """
liyinhao's avatar
liyinhao committed
615
        assert out_dir is not None, 'Expect out_dir, got none.'
616
        pipeline = self._get_pipeline(pipeline)
liyinhao's avatar
liyinhao committed
617
        for i, result in enumerate(results):
618
619
            if 'pts_bbox' in result.keys():
                result = result['pts_bbox']
liyinhao's avatar
liyinhao committed
620
621
622
            data_info = self.data_infos[i]
            pts_path = data_info['point_cloud']['velodyne_path']
            file_name = osp.split(pts_path)[-1].split('.')[0]
623
624
625
            points, img_metas, img = self._extract_data(
                i, pipeline, ['points', 'img_metas', 'img'])
            points = points.numpy()
liyinhao's avatar
liyinhao committed
626
            # for now we convert points into depth mode
627
628
            points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
                                               Coord3DMode.DEPTH)
629
630
631
            gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
            show_gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
                                               Box3DMode.DEPTH)
liyinhao's avatar
liyinhao committed
632
            pred_bboxes = result['boxes_3d'].tensor.numpy()
633
634
635
636
637
638
            show_pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
                                                 Box3DMode.DEPTH)
            show_result(points, show_gt_bboxes, show_pred_bboxes, out_dir,
                        file_name, show)

            # multi-modality visualization
639
640
641
642
            if self.modality['use_camera'] and 'lidar2img' in img_metas.keys():
                img = img.numpy()
                # need to transpose channel to first dim
                img = img.transpose(1, 2, 0)
643
644
645
646
647
648
649
650
                show_pred_bboxes = LiDARInstance3DBoxes(
                    pred_bboxes, origin=(0.5, 0.5, 0))
                show_gt_bboxes = LiDARInstance3DBoxes(
                    gt_bboxes, origin=(0.5, 0.5, 0))
                show_multi_modality_result(
                    img,
                    show_gt_bboxes,
                    show_pred_bboxes,
651
                    img_metas['lidar2img'],
652
653
                    out_dir,
                    file_name,
654
655
                    box_mode='lidar',
                    show=show)