loading.py 37 KB
Newer Older
dingchang's avatar
dingchang committed
1
# Copyright (c) OpenMMLab. All rights reserved.
2
3
import copy
from typing import List, Optional, Union
4

zhangwenwei's avatar
zhangwenwei committed
5
import mmcv
6
import mmengine
zhangwenwei's avatar
zhangwenwei committed
7
import numpy as np
8
from mmcv.transforms import LoadImageFromFile
9
from mmcv.transforms.base import BaseTransform
10
from mmdet.datasets.transforms import LoadAnnotations
zhangwenwei's avatar
zhangwenwei committed
11

12
from mmdet3d.registry import TRANSFORMS
zhangshilong's avatar
zhangshilong committed
13
from mmdet3d.structures.points import BasePoints, get_points_type
zhangwenwei's avatar
zhangwenwei committed
14
15


16
@TRANSFORMS.register_module()
17
class LoadMultiViewImageFromFiles(BaseTransform):
zhangwenwei's avatar
zhangwenwei committed
18
    """Load multi channel images from a list of separate channel files.
zhangwenwei's avatar
zhangwenwei committed
19

liyinhao's avatar
liyinhao committed
20
21
22
    Expects results['img_filename'] to be a list of filenames.

    Args:
23
        to_float32 (bool): Whether to convert the img to float32.
liyinhao's avatar
liyinhao committed
24
            Defaults to False.
25
26
27
28
29
30
31
32
33
        color_type (str): Color type of the file. Defaults to 'unchanged'.
        file_client_args (dict): Arguments to instantiate a FileClient.
            See :class:`mmengine.fileio.FileClient` for details.
            Defaults to dict(backend='disk').
        num_views (int): Number of view in a frame. Defaults to 5.
        num_ref_frames (int): Number of frame in loading. Defaults to -1.
        test_mode (bool): Whether is test mode in loading. Defaults to False.
        set_default_scale (bool): Whether to set default scale.
            Defaults to True.
zhangwenwei's avatar
zhangwenwei committed
34
    """
zhangwenwei's avatar
zhangwenwei committed
35

36
37
    def __init__(self,
                 to_float32: bool = False,
38
39
40
41
42
43
                 color_type: str = 'unchanged',
                 file_client_args: dict = dict(backend='disk'),
                 num_views: int = 5,
                 num_ref_frames: int = -1,
                 test_mode: bool = False,
                 set_default_scale: bool = True) -> None:
zhangwenwei's avatar
zhangwenwei committed
44
45
        self.to_float32 = to_float32
        self.color_type = color_type
46
47
48
49
50
51
52
53
54
55
56
        self.file_client_args = file_client_args.copy()
        self.file_client = None
        self.num_views = num_views
        # num_ref_frames is used for multi-sweep loading
        self.num_ref_frames = num_ref_frames
        # when test_mode=False, we randomly select previous frames
        # otherwise, select the earliest one
        self.test_mode = test_mode
        self.set_default_scale = set_default_scale

    def transform(self, results: dict) -> Optional[dict]:
57
58
59
60
61
62
        """Call function to load multi-view image from files.

        Args:
            results (dict): Result dict containing multi-view image filenames.

        Returns:
63
            dict: The result dict containing the multi-view image data.
64
            Added keys and values are described below.
65
66
67
68
69
70
71
72
73

                - filename (str): Multi-view image filenames.
                - img (np.ndarray): Multi-view image arrays.
                - img_shape (tuple[int]): Shape of multi-view image arrays.
                - ori_shape (tuple[int]): Shape of original image arrays.
                - pad_shape (tuple[int]): Shape of padded image arrays.
                - scale_factor (float): Scale factor.
                - img_norm_cfg (dict): Normalization configuration of images.
        """
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
        # TODO: consider split the multi-sweep part out of this pipeline
        # Derive the mask and transform for loading of multi-sweep data
        if self.num_ref_frames > 0:
            # init choice with the current frame
            init_choice = np.array([0], dtype=np.int64)
            num_frames = len(results['img_filename']) // self.num_views - 1
            if num_frames == 0:  # no previous frame, then copy cur frames
                choices = np.random.choice(
                    1, self.num_ref_frames, replace=True)
            elif num_frames >= self.num_ref_frames:
                # NOTE: suppose the info is saved following the order
                # from latest to earlier frames
                if self.test_mode:
                    choices = np.arange(num_frames - self.num_ref_frames,
                                        num_frames) + 1
                # NOTE: +1 is for selecting previous frames
                else:
                    choices = np.random.choice(
                        num_frames, self.num_ref_frames, replace=False) + 1
            elif num_frames > 0 and num_frames < self.num_ref_frames:
                if self.test_mode:
                    base_choices = np.arange(num_frames) + 1
                    random_choices = np.random.choice(
                        num_frames,
                        self.num_ref_frames - num_frames,
                        replace=True) + 1
                    choices = np.concatenate([base_choices, random_choices])
                else:
                    choices = np.random.choice(
                        num_frames, self.num_ref_frames, replace=True) + 1
            else:
                raise NotImplementedError
            choices = np.concatenate([init_choice, choices])
            select_filename = []
            for choice in choices:
                select_filename += results['img_filename'][choice *
                                                           self.num_views:
                                                           (choice + 1) *
                                                           self.num_views]
            results['img_filename'] = select_filename
            for key in ['cam2img', 'lidar2cam']:
                if key in results:
                    select_results = []
                    for choice in choices:
                        select_results += results[key][choice *
                                                       self.num_views:(choice +
                                                                       1) *
                                                       self.num_views]
                    results[key] = select_results
            for key in ['ego2global']:
                if key in results:
                    select_results = []
                    for choice in choices:
                        select_results += [results[key][choice]]
                    results[key] = select_results
            # Transform lidar2cam to
            # [cur_lidar]2[prev_img] and [cur_lidar]2[prev_cam]
            for key in ['lidar2cam']:
                if key in results:
                    # only change matrices of previous frames
                    for choice_idx in range(1, len(choices)):
                        pad_prev_ego2global = np.eye(4)
                        prev_ego2global = results['ego2global'][choice_idx]
                        pad_prev_ego2global[:prev_ego2global.
                                            shape[0], :prev_ego2global.
                                            shape[1]] = prev_ego2global
                        pad_cur_ego2global = np.eye(4)
                        cur_ego2global = results['ego2global'][0]
                        pad_cur_ego2global[:cur_ego2global.
                                           shape[0], :cur_ego2global.
                                           shape[1]] = cur_ego2global
                        cur2prev = np.linalg.inv(pad_prev_ego2global).dot(
                            pad_cur_ego2global)
                        for result_idx in range(choice_idx * self.num_views,
                                                (choice_idx + 1) *
                                                self.num_views):
                            results[key][result_idx] = \
                                results[key][result_idx].dot(cur2prev)
        # Support multi-view images with different shapes
        # TODO: record the origin shape and padded shape
        filename, cam2img, lidar2cam = [], [], []
        for _, cam_item in results['images'].items():
            filename.append(cam_item['img_path'])
            cam2img.append(cam_item['cam2img'])
            lidar2cam.append(cam_item['lidar2cam'])
        results['filename'] = filename
        results['cam2img'] = cam2img
        results['lidar2cam'] = lidar2cam

        results['ori_cam2img'] = copy.deepcopy(results['cam2img'])

        if self.file_client is None:
166
            self.file_client = mmengine.FileClient(**self.file_client_args)
167

168
        # img is of shape (h, w, c, num_views)
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
        # h and w can be different for different views
        img_bytes = [self.file_client.get(name) for name in filename]
        imgs = [
            mmcv.imfrombytes(img_byte, flag=self.color_type)
            for img_byte in img_bytes
        ]
        # handle the image with different shape
        img_shapes = np.stack([img.shape for img in imgs], axis=0)
        img_shape_max = np.max(img_shapes, axis=0)
        img_shape_min = np.min(img_shapes, axis=0)
        assert img_shape_min[-1] == img_shape_max[-1]
        if not np.all(img_shape_max == img_shape_min):
            pad_shape = img_shape_max[:2]
        else:
            pad_shape = None
        if pad_shape is not None:
            imgs = [
                mmcv.impad(img, shape=pad_shape, pad_val=0) for img in imgs
            ]
        img = np.stack(imgs, axis=-1)
zhangwenwei's avatar
zhangwenwei committed
189
190
        if self.to_float32:
            img = img.astype(np.float32)
191

zhangwenwei's avatar
zhangwenwei committed
192
        results['filename'] = filename
193
        # unravel to list, see `DefaultFormatBundle` in formating.py
194
195
        # which will transpose each image separately and then stack into array
        results['img'] = [img[..., i] for i in range(img.shape[-1])]
196
197
        results['img_shape'] = img.shape[:2]
        results['ori_shape'] = img.shape[:2]
zhangwenwei's avatar
zhangwenwei committed
198
        # Set initial values for default meta_keys
199
        results['pad_shape'] = img.shape[:2]
200
201
        if self.set_default_scale:
            results['scale_factor'] = 1.0
zhangwenwei's avatar
zhangwenwei committed
202
203
204
205
206
        num_channels = 1 if len(img.shape) < 3 else img.shape[2]
        results['img_norm_cfg'] = dict(
            mean=np.zeros(num_channels, dtype=np.float32),
            std=np.ones(num_channels, dtype=np.float32),
            to_rgb=False)
207
208
        results['num_views'] = self.num_views
        results['num_ref_frames'] = self.num_ref_frames
zhangwenwei's avatar
zhangwenwei committed
209
210
        return results

211
    def __repr__(self) -> str:
212
        """str: Return a string that describes the module."""
213
214
        repr_str = self.__class__.__name__
        repr_str += f'(to_float32={self.to_float32}, '
215
216
217
218
        repr_str += f"color_type='{self.color_type}', "
        repr_str += f'num_views={self.num_views}, '
        repr_str += f'num_ref_frames={self.num_ref_frames}, '
        repr_str += f'test_mode={self.test_mode})'
219
        return repr_str
zhangwenwei's avatar
zhangwenwei committed
220
221


222
@TRANSFORMS.register_module()
223
224
225
226
227
class LoadImageFromFileMono3D(LoadImageFromFile):
    """Load an image from file in monocular 3D object detection. Compared to 2D
    detection, additional camera parameters need to be loaded.

    Args:
228
        kwargs (dict): Arguments are the same as those in
229
230
231
            :class:`LoadImageFromFile`.
    """

ZCMax's avatar
ZCMax committed
232
    def transform(self, results: dict) -> dict:
233
234
235
236
237
238
239
240
        """Call functions to load image and get image meta information.

        Args:
            results (dict): Result dict from :obj:`mmdet.CustomDataset`.

        Returns:
            dict: The dict contains loaded image and meta information.
        """
ZCMax's avatar
ZCMax committed
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
        # TODO: load different camera image from data info,
        # for kitti dataset, we load 'CAM2' image.
        # for nuscenes dataset, we load 'CAM_FRONT' image.

        if 'CAM2' in results['images']:
            filename = results['images']['CAM2']['img_path']
            results['cam2img'] = results['images']['CAM2']['cam2img']
        elif len(list(results['images'].keys())) == 1:
            camera_type = list(results['images'].keys())[0]
            filename = results['images'][camera_type]['img_path']
            results['cam2img'] = results['images'][camera_type]['cam2img']
        else:
            raise NotImplementedError(
                'Currently we only support load image from kitti and'
                'nuscenes datasets')

        img_bytes = self.file_client.get(filename)
        img = mmcv.imfrombytes(
            img_bytes, flag=self.color_type, backend=self.imdecode_backend)
        if self.to_float32:
            img = img.astype(np.float32)

        results['img'] = img
        results['img_shape'] = img.shape[:2]
        results['ori_shape'] = img.shape[:2]

267
268
269
        return results


270
@TRANSFORMS.register_module()
VVsssssk's avatar
VVsssssk committed
271
class LoadPointsFromMultiSweeps(BaseTransform):
zhangwenwei's avatar
zhangwenwei committed
272
    """Load points from multiple sweeps.
zhangwenwei's avatar
zhangwenwei committed
273

zhangwenwei's avatar
zhangwenwei committed
274
275
276
    This is usually used for nuScenes dataset to utilize previous sweeps.

    Args:
277
278
279
280
281
282
283
        sweeps_num (int): Number of sweeps. Defaults to 10.
        load_dim (int): Dimension number of the loaded points. Defaults to 5.
        use_dim (list[int]): Which dimension to use. Defaults to [0, 1, 2, 4].
        file_client_args (dict): Arguments to instantiate a FileClient.
            See :class:`mmengine.fileio.FileClient` for details.
            Defaults to dict(backend='disk').
        pad_empty_sweeps (bool): Whether to repeat keyframe when
284
            sweeps is empty. Defaults to False.
285
286
287
        remove_close (bool): Whether to remove close points. Defaults to False.
        test_mode (bool): If `test_mode=True`, it will not randomly sample
            sweeps but select the nearest N frames. Defaults to False.
zhangwenwei's avatar
zhangwenwei committed
288
289
    """

290
291
292
293
294
295
296
297
    def __init__(self,
                 sweeps_num: int = 10,
                 load_dim: int = 5,
                 use_dim: List[int] = [0, 1, 2, 4],
                 file_client_args: dict = dict(backend='disk'),
                 pad_empty_sweeps: bool = False,
                 remove_close: bool = False,
                 test_mode: bool = False) -> None:
zhangwenwei's avatar
zhangwenwei committed
298
        self.load_dim = load_dim
zhangwenwei's avatar
zhangwenwei committed
299
        self.sweeps_num = sweeps_num
300
301
302
303
        if isinstance(use_dim, int):
            use_dim = list(range(use_dim))
        assert max(use_dim) < load_dim, \
            f'Expect all used dimensions < {load_dim}, got {use_dim}'
304
        self.use_dim = use_dim
zhangwenwei's avatar
zhangwenwei committed
305
        self.file_client_args = file_client_args.copy()
306
        self.file_client = mmengine.FileClient(**self.file_client_args)
307
308
309
        self.pad_empty_sweeps = pad_empty_sweeps
        self.remove_close = remove_close
        self.test_mode = test_mode
zhangwenwei's avatar
zhangwenwei committed
310

311
    def _load_points(self, pts_filename: str) -> np.ndarray:
312
313
314
315
316
317
318
319
        """Private function to load point clouds data.

        Args:
            pts_filename (str): Filename of point clouds data.

        Returns:
            np.ndarray: An array containing point clouds data.
        """
zhangwenwei's avatar
zhangwenwei committed
320
        if self.file_client is None:
321
            self.file_client = mmengine.FileClient(**self.file_client_args)
zhangwenwei's avatar
zhangwenwei committed
322
323
324
325
        try:
            pts_bytes = self.file_client.get(pts_filename)
            points = np.frombuffer(pts_bytes, dtype=np.float32)
        except ConnectionError:
326
            mmengine.check_file_exist(pts_filename)
zhangwenwei's avatar
zhangwenwei committed
327
328
329
330
331
            if pts_filename.endswith('.npy'):
                points = np.load(pts_filename)
            else:
                points = np.fromfile(pts_filename, dtype=np.float32)
        return points
zhangwenwei's avatar
zhangwenwei committed
332

333
334
335
    def _remove_close(self,
                      points: Union[np.ndarray, BasePoints],
                      radius: float = 1.0) -> Union[np.ndarray, BasePoints]:
336
        """Remove point too close within a certain radius from origin.
337
338

        Args:
339
            points (np.ndarray | :obj:`BasePoints`): Sweep points.
340
            radius (float): Radius below which points are removed.
341
342
343
                Defaults to 1.0.

        Returns:
344
            np.ndarray | :obj:`BasePoints`: Points after removing.
345
        """
346
347
348
349
350
351
352
353
        if isinstance(points, np.ndarray):
            points_numpy = points
        elif isinstance(points, BasePoints):
            points_numpy = points.tensor.numpy()
        else:
            raise NotImplementedError
        x_filt = np.abs(points_numpy[:, 0]) < radius
        y_filt = np.abs(points_numpy[:, 1]) < radius
354
        not_close = np.logical_not(np.logical_and(x_filt, y_filt))
355
        return points[not_close]
356

357
    def transform(self, results: dict) -> dict:
358
359
360
        """Call function to load multi-sweep point clouds from files.

        Args:
361
            results (dict): Result dict containing multi-sweep point cloud
362
363
364
                filenames.

        Returns:
365
            dict: The result dict containing the multi-sweep points data.
366
            Updated key and value are described below.
367

368
                - points (np.ndarray | :obj:`BasePoints`): Multi-sweep point
369
                  cloud arrays.
370
        """
zhangwenwei's avatar
zhangwenwei committed
371
        points = results['points']
372
        points.tensor[:, 4] = 0
zhangwenwei's avatar
zhangwenwei committed
373
374
        sweep_points_list = [points]
        ts = results['timestamp']
VVsssssk's avatar
VVsssssk committed
375
376
377
378
379
380
381
        if 'lidar_sweeps' not in results:
            if self.pad_empty_sweeps:
                for i in range(self.sweeps_num):
                    if self.remove_close:
                        sweep_points_list.append(self._remove_close(points))
                    else:
                        sweep_points_list.append(points)
382
        else:
VVsssssk's avatar
VVsssssk committed
383
384
            if len(results['lidar_sweeps']) <= self.sweeps_num:
                choices = np.arange(len(results['lidar_sweeps']))
385
386
387
388
            elif self.test_mode:
                choices = np.arange(self.sweeps_num)
            else:
                choices = np.random.choice(
VVsssssk's avatar
VVsssssk committed
389
390
391
                    len(results['lidar_sweeps']),
                    self.sweeps_num,
                    replace=False)
392
            for idx in choices:
VVsssssk's avatar
VVsssssk committed
393
394
395
                sweep = results['lidar_sweeps'][idx]
                points_sweep = self._load_points(
                    sweep['lidar_points']['lidar_path'])
396
397
398
                points_sweep = np.copy(points_sweep).reshape(-1, self.load_dim)
                if self.remove_close:
                    points_sweep = self._remove_close(points_sweep)
VVsssssk's avatar
VVsssssk committed
399
400
                # bc-breaking: Timestamp has divided 1e6 in pkl infos.
                sweep_ts = sweep['timestamp']
401
402
403
404
                lidar2sensor = np.array(sweep['lidar_points']['lidar2sensor'])
                points_sweep[:, :
                             3] = points_sweep[:, :3] @ lidar2sensor[:3, :3]
                points_sweep[:, :3] -= lidar2sensor[:3, 3]
405
                points_sweep[:, 4] = ts - sweep_ts
406
                points_sweep = points.new_point(points_sweep)
407
408
                sweep_points_list.append(points_sweep)

409
410
        points = points.cat(sweep_points_list)
        points = points[:, self.use_dim]
zhangwenwei's avatar
zhangwenwei committed
411
412
413
        results['points'] = points
        return results

414
    def __repr__(self) -> str:
415
        """str: Return a string that describes the module."""
zhangwenwei's avatar
zhangwenwei committed
416
        return f'{self.__class__.__name__}(sweeps_num={self.sweeps_num})'
wuyuefeng's avatar
wuyuefeng committed
417
418


419
@TRANSFORMS.register_module()
420
class PointSegClassMapping(BaseTransform):
wuyuefeng's avatar
wuyuefeng committed
421
422
    """Map original semantic class to valid category ids.

423
424
    Required Keys:

425
426
    - seg_label_mapping (np.ndarray)
    - pts_semantic_mask (np.ndarray)
427
428
429
430
431

    Added Keys:

    - points (np.float32)

wuyuefeng's avatar
wuyuefeng committed
432
433
434
435
    Map valid classes as 0~len(valid_cat_ids)-1 and
    others as len(valid_cat_ids).
    """

436
    def transform(self, results: dict) -> dict:
437
438
439
440
441
442
        """Call function to map original semantic class to valid category ids.

        Args:
            results (dict): Result dict containing point semantic masks.

        Returns:
443
            dict: The result dict containing the mapped category ids.
444
            Updated key and value are described below.
445
446
447

                - pts_semantic_mask (np.ndarray): Mapped semantic masks.
        """
wuyuefeng's avatar
wuyuefeng committed
448
449
450
        assert 'pts_semantic_mask' in results
        pts_semantic_mask = results['pts_semantic_mask']

451
452
453
        assert 'seg_label_mapping' in results
        label_mapping = results['seg_label_mapping']
        converted_pts_sem_mask = label_mapping[pts_semantic_mask]
wuyuefeng's avatar
wuyuefeng committed
454

455
        results['pts_semantic_mask'] = converted_pts_sem_mask
ZCMax's avatar
ZCMax committed
456
457
458
459
460
461
462

        # 'eval_ann_info' will be passed to evaluator
        if 'eval_ann_info' in results:
            assert 'pts_semantic_mask' in results['eval_ann_info']
            results['eval_ann_info']['pts_semantic_mask'] = \
                converted_pts_sem_mask

wuyuefeng's avatar
wuyuefeng committed
463
464
        return results

465
    def __repr__(self) -> str:
466
        """str: Return a string that describes the module."""
wuyuefeng's avatar
wuyuefeng committed
467
468
469
470
        repr_str = self.__class__.__name__
        return repr_str


471
@TRANSFORMS.register_module()
ZCMax's avatar
ZCMax committed
472
class NormalizePointsColor(BaseTransform):
zhangwenwei's avatar
zhangwenwei committed
473
    """Normalize color of points.
wuyuefeng's avatar
wuyuefeng committed
474
475
476
477
478

    Args:
        color_mean (list[float]): Mean color of the point cloud.
    """

ZCMax's avatar
ZCMax committed
479
    def __init__(self, color_mean: List[float]) -> None:
wuyuefeng's avatar
wuyuefeng committed
480
481
        self.color_mean = color_mean

ZCMax's avatar
ZCMax committed
482
    def transform(self, input_dict: dict) -> dict:
483
484
485
486
487
488
        """Call function to normalize color of points.

        Args:
            results (dict): Result dict containing point clouds data.

        Returns:
489
            dict: The result dict containing the normalized points.
490
            Updated key and value are described below.
491

492
                - points (:obj:`BasePoints`): Points after color normalization.
493
        """
ZCMax's avatar
ZCMax committed
494
        points = input_dict['points']
495
        assert points.attribute_dims is not None and \
496
497
               'color' in points.attribute_dims.keys(), \
               'Expect points have color attribute'
498
499
        if self.color_mean is not None:
            points.color = points.color - \
500
                           points.color.new_tensor(self.color_mean)
501
        points.color = points.color / 255.0
ZCMax's avatar
ZCMax committed
502
503
        input_dict['points'] = points
        return input_dict
wuyuefeng's avatar
wuyuefeng committed
504

505
    def __repr__(self) -> str:
506
        """str: Return a string that describes the module."""
wuyuefeng's avatar
wuyuefeng committed
507
        repr_str = self.__class__.__name__
508
        repr_str += f'(color_mean={self.color_mean})'
wuyuefeng's avatar
wuyuefeng committed
509
510
511
        return repr_str


512
@TRANSFORMS.register_module()
jshilong's avatar
jshilong committed
513
class LoadPointsFromFile(BaseTransform):
wuyuefeng's avatar
wuyuefeng committed
514
515
    """Load Points From File.

jshilong's avatar
jshilong committed
516
517
518
519
520
521
522
523
524
    Required Keys:

    - lidar_points (dict)

        - lidar_path (str)

    Added Keys:

    - points (np.float32)
wuyuefeng's avatar
wuyuefeng committed
525
526

    Args:
527
528
        coord_type (str): The type of coordinates of points cloud.
            Available options includes:
529

530
531
532
            - 'LIDAR': Points in LiDAR coordinates.
            - 'DEPTH': Points in depth coordinates, usually for indoor dataset.
            - 'CAMERA': Points in camera coordinates.
533
534
535
        load_dim (int): The dimension of the loaded points. Defaults to 6.
        use_dim (list[int] | int): Which dimensions of the points to use.
            Defaults to [0, 1, 2]. For KITTI dataset, set use_dim=4
liyinhao's avatar
liyinhao committed
536
            or use_dim=[0, 1, 2, 3] to use the intensity dimension.
537
538
        shift_height (bool): Whether to use shifted height. Defaults to False.
        use_color (bool): Whether to use color features. Defaults to False.
539
540
        norm_intensity (bool): Whether to normlize the intensity. Defaults to
            False.
541
542
543
        file_client_args (dict): Arguments to instantiate a FileClient.
            See :class:`mmengine.fileio.FileClient` for details.
            Defaults to dict(backend='disk').
wuyuefeng's avatar
wuyuefeng committed
544
545
    """

jshilong's avatar
jshilong committed
546
547
548
549
    def __init__(
        self,
        coord_type: str,
        load_dim: int = 6,
550
        use_dim: Union[int, List[int]] = [0, 1, 2],
jshilong's avatar
jshilong committed
551
552
        shift_height: bool = False,
        use_color: bool = False,
553
        norm_intensity: bool = False,
jshilong's avatar
jshilong committed
554
555
        file_client_args: dict = dict(backend='disk')
    ) -> None:
wuyuefeng's avatar
wuyuefeng committed
556
        self.shift_height = shift_height
557
        self.use_color = use_color
wuyuefeng's avatar
wuyuefeng committed
558
559
560
561
        if isinstance(use_dim, int):
            use_dim = list(range(use_dim))
        assert max(use_dim) < load_dim, \
            f'Expect all used dimensions < {load_dim}, got {use_dim}'
562
        assert coord_type in ['CAMERA', 'LIDAR', 'DEPTH']
wuyuefeng's avatar
wuyuefeng committed
563

564
        self.coord_type = coord_type
wuyuefeng's avatar
wuyuefeng committed
565
566
        self.load_dim = load_dim
        self.use_dim = use_dim
567
        self.norm_intensity = norm_intensity
wuyuefeng's avatar
wuyuefeng committed
568
569
570
        self.file_client_args = file_client_args.copy()
        self.file_client = None

jshilong's avatar
jshilong committed
571
    def _load_points(self, pts_filename: str) -> np.ndarray:
572
573
574
575
576
577
578
579
        """Private function to load point clouds data.

        Args:
            pts_filename (str): Filename of point clouds data.

        Returns:
            np.ndarray: An array containing point clouds data.
        """
wuyuefeng's avatar
wuyuefeng committed
580
        if self.file_client is None:
581
            self.file_client = mmengine.FileClient(**self.file_client_args)
wuyuefeng's avatar
wuyuefeng committed
582
583
584
585
        try:
            pts_bytes = self.file_client.get(pts_filename)
            points = np.frombuffer(pts_bytes, dtype=np.float32)
        except ConnectionError:
586
            mmengine.check_file_exist(pts_filename)
wuyuefeng's avatar
wuyuefeng committed
587
588
589
590
            if pts_filename.endswith('.npy'):
                points = np.load(pts_filename)
            else:
                points = np.fromfile(pts_filename, dtype=np.float32)
591

wuyuefeng's avatar
wuyuefeng committed
592
593
        return points

jshilong's avatar
jshilong committed
594
595
    def transform(self, results: dict) -> dict:
        """Method to load points data from file.
596
597
598
599
600

        Args:
            results (dict): Result dict containing point clouds data.

        Returns:
601
            dict: The result dict containing the point clouds data.
602
            Added key and value are described below.
603

604
                - points (:obj:`BasePoints`): Point clouds data.
605
        """
jshilong's avatar
jshilong committed
606
607
        pts_file_path = results['lidar_points']['lidar_path']
        points = self._load_points(pts_file_path)
wuyuefeng's avatar
wuyuefeng committed
608
609
        points = points.reshape(-1, self.load_dim)
        points = points[:, self.use_dim]
610
611
612
613
        if self.norm_intensity:
            assert len(self.use_dim) >= 4, \
                f'When using intensity norm, expect used dimensions >= 4, got {len(self.use_dim)}'  # noqa: E501
            points[:, 3] = np.tanh(points[:, 3])
614
        attribute_dims = None
wuyuefeng's avatar
wuyuefeng committed
615
616
617
618

        if self.shift_height:
            floor_height = np.percentile(points[:, 2], 0.99)
            height = points[:, 2] - floor_height
619
620
621
            points = np.concatenate(
                [points[:, :3],
                 np.expand_dims(height, 1), points[:, 3:]], 1)
622
623
            attribute_dims = dict(height=3)

624
625
626
627
628
629
630
631
632
633
634
        if self.use_color:
            assert len(self.use_dim) >= 6
            if attribute_dims is None:
                attribute_dims = dict()
            attribute_dims.update(
                dict(color=[
                    points.shape[1] - 3,
                    points.shape[1] - 2,
                    points.shape[1] - 1,
                ]))

635
636
637
        points_class = get_points_type(self.coord_type)
        points = points_class(
            points, points_dim=points.shape[-1], attribute_dims=attribute_dims)
wuyuefeng's avatar
wuyuefeng committed
638
        results['points'] = points
639

wuyuefeng's avatar
wuyuefeng committed
640
641
        return results

642
    def __repr__(self) -> str:
643
        """str: Return a string that describes the module."""
liyinhao's avatar
liyinhao committed
644
        repr_str = self.__class__.__name__ + '('
645
646
647
648
649
        repr_str += f'shift_height={self.shift_height}, '
        repr_str += f'use_color={self.use_color}, '
        repr_str += f'file_client_args={self.file_client_args}, '
        repr_str += f'load_dim={self.load_dim}, '
        repr_str += f'use_dim={self.use_dim})'
wuyuefeng's avatar
wuyuefeng committed
650
651
652
        return repr_str


653
@TRANSFORMS.register_module()
654
655
656
class LoadPointsFromDict(LoadPointsFromFile):
    """Load Points From Dict."""

ChaimZhu's avatar
ChaimZhu committed
657
    def transform(self, results: dict) -> dict:
658
659
660
661
        assert 'points' in results
        return results


662
@TRANSFORMS.register_module()
wuyuefeng's avatar
wuyuefeng committed
663
664
665
666
667
668
class LoadAnnotations3D(LoadAnnotations):
    """Load Annotations3D.

    Load instance mask and semantic mask of points and
    encapsulate the items into related fields.

jshilong's avatar
jshilong committed
669
670
671
    Required Keys:

    - ann_info (dict)
672

jshilong's avatar
jshilong committed
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
        - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes` |
          :obj:`DepthInstance3DBoxes` | :obj:`CameraInstance3DBoxes`):
          3D ground truth bboxes. Only when `with_bbox_3d` is True
        - gt_labels_3d (np.int64): Labels of ground truths.
          Only when `with_label_3d` is True.
        - gt_bboxes (np.float32): 2D ground truth bboxes.
          Only when `with_bbox` is True.
        - gt_labels (np.ndarray): Labels of ground truths.
          Only when `with_label` is True.
        - depths (np.ndarray): Only when
          `with_bbox_depth` is True.
        - centers_2d (np.ndarray): Only when
          `with_bbox_depth` is True.
        - attr_labels (np.ndarray): Attribute labels of instances.
          Only when `with_attr_label` is True.

    - pts_instance_mask_path (str): Path of instance mask file.
      Only when `with_mask_3d` is True.
    - pts_semantic_mask_path (str): Path of semantic mask file.
692
      Only when `with_seg_3d` is True.
jshilong's avatar
jshilong committed
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715

    Added Keys:

    - gt_bboxes_3d (:obj:`LiDARInstance3DBoxes` |
      :obj:`DepthInstance3DBoxes` | :obj:`CameraInstance3DBoxes`):
      3D ground truth bboxes. Only when `with_bbox_3d` is True
    - gt_labels_3d (np.int64): Labels of ground truths.
      Only when `with_label_3d` is True.
    - gt_bboxes (np.float32): 2D ground truth bboxes.
      Only when `with_bbox` is True.
    - gt_labels (np.int64): Labels of ground truths.
      Only when `with_label` is True.
    - depths (np.float32): Only when
      `with_bbox_depth` is True.
    - centers_2d (np.ndarray): Only when
      `with_bbox_depth` is True.
    - attr_labels (np.int64): Attribute labels of instances.
      Only when `with_attr_label` is True.
    - pts_instance_mask (np.int64): Instance mask of each point.
      Only when `with_mask_3d` is True.
    - pts_semantic_mask (np.int64): Semantic mask of each point.
      Only when `with_seg_3d` is True.

wuyuefeng's avatar
wuyuefeng committed
716
    Args:
717
718
719
        with_bbox_3d (bool): Whether to load 3D boxes. Defaults to True.
        with_label_3d (bool): Whether to load 3D labels. Defaults to True.
        with_attr_label (bool): Whether to load attribute label.
wuyuefeng's avatar
wuyuefeng committed
720
            Defaults to False.
721
        with_mask_3d (bool): Whether to load 3D instance masks for points.
wuyuefeng's avatar
wuyuefeng committed
722
            Defaults to False.
723
        with_seg_3d (bool): Whether to load 3D semantic masks for points.
wuyuefeng's avatar
wuyuefeng committed
724
            Defaults to False.
725
726
727
728
729
730
731
732
733
734
735
        with_bbox (bool): Whether to load 2D boxes. Defaults to False.
        with_label (bool): Whether to load 2D labels. Defaults to False.
        with_mask (bool): Whether to load 2D instance masks. Defaults to False.
        with_seg (bool): Whether to load 2D semantic masks. Defaults to False.
        with_bbox_depth (bool): Whether to load 2.5D boxes. Defaults to False.
        poly2mask (bool): Whether to convert polygon annotations to bitmasks.
            Defaults to True.
        seg_3d_dtype (dtype): Dtype of 3D semantic masks. Defaults to int64.
        file_client_args (dict): Arguments to instantiate a FileClient.
            See :class:`mmengine.fileio.FileClient` for details.
            Defaults to dict(backend='disk').
wuyuefeng's avatar
wuyuefeng committed
736
737
    """

jshilong's avatar
jshilong committed
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
    def __init__(
        self,
        with_bbox_3d: bool = True,
        with_label_3d: bool = True,
        with_attr_label: bool = False,
        with_mask_3d: bool = False,
        with_seg_3d: bool = False,
        with_bbox: bool = False,
        with_label: bool = False,
        with_mask: bool = False,
        with_seg: bool = False,
        with_bbox_depth: bool = False,
        poly2mask: bool = True,
        seg_3d_dtype: np.dtype = np.int64,
        file_client_args: dict = dict(backend='disk')
    ) -> None:
wuyuefeng's avatar
wuyuefeng committed
754
        super().__init__(
jshilong's avatar
jshilong committed
755
756
757
758
759
            with_bbox=with_bbox,
            with_label=with_label,
            with_mask=with_mask,
            with_seg=with_seg,
            poly2mask=poly2mask,
wuyuefeng's avatar
wuyuefeng committed
760
761
            file_client_args=file_client_args)
        self.with_bbox_3d = with_bbox_3d
762
        self.with_bbox_depth = with_bbox_depth
wuyuefeng's avatar
wuyuefeng committed
763
        self.with_label_3d = with_label_3d
764
        self.with_attr_label = with_attr_label
wuyuefeng's avatar
wuyuefeng committed
765
766
        self.with_mask_3d = with_mask_3d
        self.with_seg_3d = with_seg_3d
767
        self.seg_3d_dtype = seg_3d_dtype
768
        self.file_client = None
wuyuefeng's avatar
wuyuefeng committed
769

jshilong's avatar
jshilong committed
770
771
772
    def _load_bboxes_3d(self, results: dict) -> dict:
        """Private function to move the 3D bounding box annotation from
        `ann_info` field to the root of `results`.
773
774
775
776
777
778
779

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded 3D bounding box annotations.
        """
jshilong's avatar
jshilong committed
780

wuyuefeng's avatar
wuyuefeng committed
781
782
783
        results['gt_bboxes_3d'] = results['ann_info']['gt_bboxes_3d']
        return results

jshilong's avatar
jshilong committed
784
    def _load_bboxes_depth(self, results: dict) -> dict:
785
786
787
788
789
790
791
792
        """Private function to load 2.5D bounding box annotations.

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded 2.5D bounding box annotations.
        """
jshilong's avatar
jshilong committed
793

794
        results['depths'] = results['ann_info']['depths']
jshilong's avatar
jshilong committed
795
        results['centers_2d'] = results['ann_info']['centers_2d']
796
797
        return results

jshilong's avatar
jshilong committed
798
    def _load_labels_3d(self, results: dict) -> dict:
799
800
801
802
803
804
805
806
        """Private function to load label annotations.

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded label annotations.
        """
jshilong's avatar
jshilong committed
807

wuyuefeng's avatar
wuyuefeng committed
808
809
810
        results['gt_labels_3d'] = results['ann_info']['gt_labels_3d']
        return results

jshilong's avatar
jshilong committed
811
    def _load_attr_labels(self, results: dict) -> dict:
812
813
814
815
816
817
818
819
820
821
822
        """Private function to load label annotations.

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded label annotations.
        """
        results['attr_labels'] = results['ann_info']['attr_labels']
        return results

jshilong's avatar
jshilong committed
823
    def _load_masks_3d(self, results: dict) -> dict:
824
825
826
827
828
829
830
831
        """Private function to load 3D mask annotations.

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded 3D mask annotations.
        """
jshilong's avatar
jshilong committed
832
        pts_instance_mask_path = results['pts_instance_mask_path']
wuyuefeng's avatar
wuyuefeng committed
833
834

        if self.file_client is None:
835
            self.file_client = mmengine.FileClient(**self.file_client_args)
wuyuefeng's avatar
wuyuefeng committed
836
837
        try:
            mask_bytes = self.file_client.get(pts_instance_mask_path)
838
            pts_instance_mask = np.frombuffer(mask_bytes, dtype=np.int64)
wuyuefeng's avatar
wuyuefeng committed
839
        except ConnectionError:
840
            mmengine.check_file_exist(pts_instance_mask_path)
wuyuefeng's avatar
wuyuefeng committed
841
            pts_instance_mask = np.fromfile(
WRH's avatar
WRH committed
842
                pts_instance_mask_path, dtype=np.int64)
wuyuefeng's avatar
wuyuefeng committed
843
844

        results['pts_instance_mask'] = pts_instance_mask
jshilong's avatar
jshilong committed
845
846
847
        # 'eval_ann_info' will be passed to evaluator
        if 'eval_ann_info' in results:
            results['eval_ann_info']['pts_instance_mask'] = pts_instance_mask
wuyuefeng's avatar
wuyuefeng committed
848
849
        return results

jshilong's avatar
jshilong committed
850
    def _load_semantic_seg_3d(self, results: dict) -> dict:
851
852
853
854
855
856
857
858
        """Private function to load 3D semantic segmentation annotations.

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing the semantic segmentation annotations.
        """
jshilong's avatar
jshilong committed
859
        pts_semantic_mask_path = results['pts_semantic_mask_path']
wuyuefeng's avatar
wuyuefeng committed
860
861

        if self.file_client is None:
862
            self.file_client = mmengine.FileClient(**self.file_client_args)
wuyuefeng's avatar
wuyuefeng committed
863
864
865
        try:
            mask_bytes = self.file_client.get(pts_semantic_mask_path)
            # add .copy() to fix read-only bug
866
867
            pts_semantic_mask = np.frombuffer(
                mask_bytes, dtype=self.seg_3d_dtype).copy()
wuyuefeng's avatar
wuyuefeng committed
868
        except ConnectionError:
869
            mmengine.check_file_exist(pts_semantic_mask_path)
wuyuefeng's avatar
wuyuefeng committed
870
            pts_semantic_mask = np.fromfile(
WRH's avatar
WRH committed
871
                pts_semantic_mask_path, dtype=np.int64)
wuyuefeng's avatar
wuyuefeng committed
872
873

        results['pts_semantic_mask'] = pts_semantic_mask
jshilong's avatar
jshilong committed
874
875
876
        # 'eval_ann_info' will be passed to evaluator
        if 'eval_ann_info' in results:
            results['eval_ann_info']['pts_semantic_mask'] = pts_semantic_mask
wuyuefeng's avatar
wuyuefeng committed
877
878
        return results

zhangshilong's avatar
zhangshilong committed
879
880
881
882
883
884
885
    def _load_bboxes(self, results: dict) -> None:
        """Private function to load bounding box annotations.

        The only difference is it remove the proceess for
        `ignore_flag`

        Args:
886
887
            results (dict): Result dict from :obj:`mmcv.BaseDataset`.

zhangshilong's avatar
zhangshilong committed
888
889
890
891
        Returns:
            dict: The dict contains loaded bounding box annotations.
        """

892
        results['gt_bboxes'] = results['ann_info']['gt_bboxes']
zhangshilong's avatar
zhangshilong committed
893
894
895
896
897

    def _load_labels(self, results: dict) -> None:
        """Private function to load label annotations.

        Args:
898
            results (dict): Result dict from :obj :obj:`mmcv.BaseDataset`.
zhangshilong's avatar
zhangshilong committed
899
900
901
902

        Returns:
            dict: The dict contains loaded label annotations.
        """
903
        results['gt_bboxes_labels'] = results['ann_info']['gt_bboxes_labels']
zhangshilong's avatar
zhangshilong committed
904

jshilong's avatar
jshilong committed
905
906
    def transform(self, results: dict) -> dict:
        """Function to load multiple types annotations.
907
908
909
910
911
912

        Args:
            results (dict): Result dict from :obj:`mmdet3d.CustomDataset`.

        Returns:
            dict: The dict containing loaded 3D bounding box, label, mask and
jshilong's avatar
jshilong committed
913
            semantic segmentation annotations.
914
        """
jshilong's avatar
jshilong committed
915
        results = super().transform(results)
wuyuefeng's avatar
wuyuefeng committed
916
917
        if self.with_bbox_3d:
            results = self._load_bboxes_3d(results)
918
919
        if self.with_bbox_depth:
            results = self._load_bboxes_depth(results)
wuyuefeng's avatar
wuyuefeng committed
920
921
        if self.with_label_3d:
            results = self._load_labels_3d(results)
922
923
        if self.with_attr_label:
            results = self._load_attr_labels(results)
wuyuefeng's avatar
wuyuefeng committed
924
925
926
927
928
929
930
        if self.with_mask_3d:
            results = self._load_masks_3d(results)
        if self.with_seg_3d:
            results = self._load_semantic_seg_3d(results)

        return results

931
    def __repr__(self) -> str:
932
        """str: Return a string that describes the module."""
wuyuefeng's avatar
wuyuefeng committed
933
934
        indent_str = '    '
        repr_str = self.__class__.__name__ + '(\n'
liyinhao's avatar
liyinhao committed
935
936
        repr_str += f'{indent_str}with_bbox_3d={self.with_bbox_3d}, '
        repr_str += f'{indent_str}with_label_3d={self.with_label_3d}, '
937
        repr_str += f'{indent_str}with_attr_label={self.with_attr_label}, '
liyinhao's avatar
liyinhao committed
938
939
940
941
942
943
        repr_str += f'{indent_str}with_mask_3d={self.with_mask_3d}, '
        repr_str += f'{indent_str}with_seg_3d={self.with_seg_3d}, '
        repr_str += f'{indent_str}with_bbox={self.with_bbox}, '
        repr_str += f'{indent_str}with_label={self.with_label}, '
        repr_str += f'{indent_str}with_mask={self.with_mask}, '
        repr_str += f'{indent_str}with_seg={self.with_seg}, '
944
        repr_str += f'{indent_str}with_bbox_depth={self.with_bbox_depth}, '
wuyuefeng's avatar
wuyuefeng committed
945
946
        repr_str += f'{indent_str}poly2mask={self.poly2mask})'
        return repr_str