Skip to content
GitLab
Menu
Projects
Groups
Snippets
Loading...
Help
Help
Support
Community forum
Keyboard shortcuts
?
Submit feedback
Contribute to GitLab
Sign in / Register
Toggle navigation
Menu
Open sidebar
OpenDAS
mmdetection3d
Commits
a79b105b
"mmdet3d/vscode:/vscode.git/clone" did not exist on "fab3db2ea9805715096009580219f11087d047b7"
Commit
a79b105b
authored
May 26, 2022
by
jshilong
Committed by
ChaimZhu
Jul 20, 2022
Browse files
Refactor kitti dataset
parent
3fa5a430
Changes
14
Expand all
Show whitespace changes
Inline
Side-by-side
Showing
14 changed files
with
950 additions
and
198 deletions
+950
-198
mmdet3d/datasets/__init__.py
mmdet3d/datasets/__init__.py
+2
-2
mmdet3d/datasets/det3d_dataset.py
mmdet3d/datasets/det3d_dataset.py
+393
-0
mmdet3d/datasets/kitti2d_dataset.py
mmdet3d/datasets/kitti2d_dataset.py
+2
-2
mmdet3d/datasets/kitti_dataset.py
mmdet3d/datasets/kitti_dataset.py
+64
-181
mmdet3d/datasets/lyft_dataset.py
mmdet3d/datasets/lyft_dataset.py
+2
-2
mmdet3d/datasets/nuscenes_dataset.py
mmdet3d/datasets/nuscenes_dataset.py
+2
-2
mmdet3d/datasets/s3dis_dataset.py
mmdet3d/datasets/s3dis_dataset.py
+2
-2
mmdet3d/datasets/scannet_dataset.py
mmdet3d/datasets/scannet_dataset.py
+2
-2
mmdet3d/datasets/semantickitti_dataset.py
mmdet3d/datasets/semantickitti_dataset.py
+2
-2
mmdet3d/datasets/sunrgbd_dataset.py
mmdet3d/datasets/sunrgbd_dataset.py
+2
-2
tests/data/kitti/kitti_infos_train.pkl
tests/data/kitti/kitti_infos_train.pkl
+0
-0
tests/test_data/test_datasets/test_kitti_dataset.py
tests/test_data/test_datasets/test_kitti_dataset.py
+133
-0
tools/data_converter/__init__.py
tools/data_converter/__init__.py
+0
-1
tools/data_converter/update_infos_to_v2.py
tools/data_converter/update_infos_to_v2.py
+344
-0
No files found.
mmdet3d/datasets/__init__.py
View file @
a79b105b
# Copyright (c) OpenMMLab. All rights reserved.
from
.builder
import
DATASETS
,
PIPELINES
,
build_dataset
from
.custom_3d
import
Custom3DDataset
from
.custom_3d_seg
import
Custom3DSegDataset
from
.det3d_dataset
import
Det3DDataset
from
.kitti_dataset
import
KittiDataset
from
.kitti_mono_dataset
import
KittiMonoDataset
from
.lyft_dataset
import
LyftDataset
...
...
@@ -36,7 +36,7 @@ __all__ = [
'IndoorPatchPointSample'
,
'IndoorPointSample'
,
'PointSample'
,
'LoadAnnotations3D'
,
'GlobalAlignment'
,
'SUNRGBDDataset'
,
'ScanNetDataset'
,
'ScanNetSegDataset'
,
'ScanNetInstanceSegDataset'
,
'SemanticKITTIDataset'
,
'
Custom
3DDataset'
,
'Custom3DSegDataset'
,
'LoadPointsFromMultiSweeps'
,
'
Det
3DDataset'
,
'Custom3DSegDataset'
,
'LoadPointsFromMultiSweeps'
,
'WaymoDataset'
,
'BackgroundPointsFilter'
,
'VoxelBasedPointSampler'
,
'get_loading_pipeline'
,
'RandomDropPointsColor'
,
'RandomJitterPoints'
,
'ObjectNameFilter'
,
'AffineResize'
,
'RandomShiftScale'
,
...
...
mmdet3d/datasets/
custom_3d
.py
→
mmdet3d/datasets/
det3d_dataset
.py
View file @
a79b105b
This diff is collapsed.
Click to expand it.
mmdet3d/datasets/kitti2d_dataset.py
View file @
a79b105b
...
...
@@ -2,12 +2,12 @@
import
mmcv
import
numpy
as
np
from
mmdet3d.datasets
import
Custom
Dataset
from
mmdet3d.datasets
import
Det3D
Dataset
from
mmdet3d.registry
import
DATASETS
@
DATASETS
.
register_module
()
class
Kitti2DDataset
(
Custom
Dataset
):
class
Kitti2DDataset
(
Det3D
Dataset
):
r
"""KITTI 2D Dataset.
This class serves as the API for experiments on the `KITTI Dataset
...
...
mmdet3d/datasets/kitti_dataset.py
View file @
a79b105b
# Copyright (c) OpenMMLab. All rights reserved.
import
copy
import
os
import
tempfile
from
os
import
path
as
osp
from
typing
import
Callable
,
List
,
Optional
,
Union
import
mmcv
import
numpy
as
np
import
torch
from
mmcv.utils
import
print_log
from
mmdet3d.
registry
import
DATASETS
from
mmdet3d.
datasets
import
DATASETS
from
..core
import
show_multi_modality_result
,
show_result
from
..core.bbox
import
(
Box3DMode
,
CameraInstance3DBoxes
,
Coord3DMode
,
LiDARInstance3DBoxes
,
points_cam2img
)
from
.
custom_3d
import
Custom
3DDataset
from
.
det3d_dataset
import
Det
3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
KittiDataset
(
Custom
3DDataset
):
class
KittiDataset
(
Det
3DDataset
):
r
"""KITTI Dataset.
This class serves as the API for experiments on the `KITTI Dataset
...
...
@@ -28,12 +28,8 @@ class KittiDataset(Custom3DDataset):
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.
...
...
@@ -52,124 +48,55 @@ class KittiDataset(Custom3DDataset):
filter invalid predicted boxes.
Default: [0, -40, -3, 70.4, 40, 0.0].
"""
CLASSES
=
(
'car'
,
'pedestrian'
,
'cyclist'
)
# TODO: use full classes of kitti
METAINFO
=
{
'CLASSES'
:
(
'Pedestrian'
,
'Cyclist'
,
'Car'
)}
def
__init__
(
self
,
data_root
,
ann_file
,
split
,
pts_prefix
=
'velodyne'
,
pipeline
=
None
,
classes
=
None
,
modality
=
None
,
box_type_3d
=
'LiDAR'
,
filter_empty_gt
=
True
,
test_mode
=
False
,
pcd_limit_range
=
[
0
,
-
40
,
-
3
,
70.4
,
40
,
0.0
],
data_root
:
str
,
ann_file
:
str
,
pipeline
:
List
[
Union
[
dict
,
Callable
]]
=
[],
modality
:
Optional
[
dict
]
=
None
,
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
],
**
kwargs
):
self
.
pcd_limit_range
=
pcd_limit_range
super
().
__init__
(
data_root
=
data_root
,
ann_file
=
ann_file
,
pipeline
=
pipeline
,
classes
=
classes
,
modality
=
modality
,
box_type_3d
=
box_type_3d
,
filter_empty_gt
=
filter_empty_gt
,
test_mode
=
test_mode
,
**
kwargs
)
self
.
split
=
split
self
.
root_split
=
os
.
path
.
join
(
self
.
data_root
,
split
)
assert
self
.
modality
is
not
None
self
.
pcd_limit_range
=
pcd_limit_range
self
.
pts_prefix
=
pts_prefix
def
_get_pts_filename
(
self
,
idx
):
"""Get point cloud filename according to the given index.
Args:
index (int): Index of the point cloud file to get.
Returns:
str: Name of the point cloud file.
"""
pts_filename
=
osp
.
join
(
self
.
root_split
,
self
.
pts_prefix
,
f
'
{
idx
:
06
d
}
.bin'
)
return
pts_filename
def
get_data_info
(
self
,
index
):
"""Get data info according to the given index.
Args:
index (int): Index of the sample data to get.
assert
box_type_3d
.
lower
()
in
(
'lidar'
,
'camera'
)
Returns:
dict: Data information that will be passed to the data
preprocessing pipelines. It includes the following keys:
- sample_idx (str): Sample index.
- pts_filename (str): Filename of point clouds.
- img_prefix (str): 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.
"""
info
=
self
.
data_infos
[
index
]
sample_idx
=
info
[
'image'
][
'image_idx'
]
img_filename
=
os
.
path
.
join
(
self
.
data_root
,
info
[
'image'
][
'image_path'
])
def
parse_data_info
(
self
,
info
:
dict
)
->
dict
:
"""Process the raw data info.
# 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
pts_filename
=
self
.
_get_pts_filename
(
sample_idx
)
input_dict
=
dict
(
sample_idx
=
sample_idx
,
pts_filename
=
pts_filename
,
img_prefix
=
None
,
img_info
=
dict
(
filename
=
img_filename
),
lidar2img
=
lidar2img
)
if
not
self
.
test_mode
:
annos
=
self
.
get_ann_info
(
index
)
input_dict
[
'ann_info'
]
=
annos
return
input_dict
def
get_ann_info
(
self
,
index
):
"""Get annotation info according to the given index.
The only difference with it in `Det3DDataset`
is the specific process for `plane`.
Args:
in
dex (int): Index of the annotation data to ge
t.
in
fo (dict): Raw info dic
t.
Returns:
dict: annotation information consists of the following keys:
- gt_bboxes_3d (:obj:`LiDARInstance3DBoxes`):
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.
- difficulty (int): Difficulty defined by KITTI.
0, 1, 2 represent xxxxx respectively.
dict: Has `ann_info` in training stage. And
all path has been converted to absolute path.
"""
# Use index to get the annos, thus the evalhook could also use this api
info
=
self
.
data_infos
[
index
]
rect
=
info
[
'calib'
][
'R0_rect'
].
astype
(
np
.
float32
)
Trv2c
=
info
[
'calib'
][
'Tr_velo_to_cam'
].
astype
(
np
.
float32
)
if
self
.
modality
[
'use_lidar'
]:
if
'plane'
in
info
:
# convert ground plane to velodyne coordinates
reverse
=
np
.
linalg
.
inv
(
rect
@
Trv2c
)
plane
=
np
.
array
(
info
[
'plane'
])
lidar2cam
=
np
.
array
(
info
[
'lidar_points'
][
'lidar2cam'
])
reverse
=
np
.
linalg
.
inv
(
lidar2cam
)
(
plane_norm_cam
,
plane_off_cam
)
=
(
info
[
'plane'
][:
3
],
-
info
[
'plane'
][:
3
]
*
info
[
'plane'
][
3
])
(
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
=
(
...
...
@@ -181,91 +108,47 @@ class KittiDataset(Custom3DDataset):
else
:
plane_lidar
=
None
difficulty
=
info
[
'annos'
][
'difficulty'
]
annos
=
info
[
'annos'
]
# we need other objects to avoid collision when sample
annos
=
self
.
remove_dontcare
(
annos
)
loc
=
annos
[
'location'
]
dims
=
annos
[
'dimensions'
]
rots
=
annos
[
'rotation_y'
]
gt_names
=
annos
[
'name'
]
gt_bboxes_3d
=
np
.
concatenate
([
loc
,
dims
,
rots
[...,
np
.
newaxis
]],
axis
=
1
).
astype
(
np
.
float32
)
# convert gt_bboxes_3d to velodyne coordinates
gt_bboxes_3d
=
CameraInstance3DBoxes
(
gt_bboxes_3d
).
convert_to
(
self
.
box_mode_3d
,
np
.
linalg
.
inv
(
rect
@
Trv2c
))
gt_bboxes
=
annos
[
'bbox'
]
selected
=
self
.
drop_arrays_by_name
(
gt_names
,
[
'DontCare'
])
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
).
astype
(
np
.
int64
)
gt_labels_3d
=
copy
.
deepcopy
(
gt_labels
)
anns_results
=
dict
(
gt_bboxes_3d
=
gt_bboxes_3d
,
gt_labels_3d
=
gt_labels_3d
,
bboxes
=
gt_bboxes
,
labels
=
gt_labels
,
gt_names
=
gt_names
,
plane
=
plane_lidar
,
difficulty
=
difficulty
)
return
anns_results
def
drop_arrays_by_name
(
self
,
gt_names
,
used_classes
):
"""Drop irrelevant ground truths by name.
info
[
'plane'
]
=
plane_lidar
Args:
gt_names (list[str]): Names of ground truths.
used_classes (list[str]): Classes of interest.
info
=
super
().
parse_data_info
(
info
)
Returns:
np.ndarray: Indices of ground truths that will be dropped.
"""
inds
=
[
i
for
i
,
x
in
enumerate
(
gt_names
)
if
x
not
in
used_classes
]
inds
=
np
.
array
(
inds
,
dtype
=
np
.
int64
)
return
inds
return
info
def
keep_arrays_by_name
(
self
,
gt_names
,
used_classes
):
"""
Keep useful ground truths by name
.
def
parse_ann_info
(
self
,
info
):
"""
Get annotation info according to the given index
.
Args:
gt_names (list[str]): Names of ground truths.
used_classes (list[str]): Classes of interest.
info (dict): Data information of single data sample.
Returns:
np.ndarray: Indices of ground truths that will be keeped.
dict: annotation information consists of the following keys:
- bboxes_3d (:obj:`LiDARInstance3DBoxes`):
3D ground truth bboxes.
- bbox_labels_3d (np.ndarray): Labels of ground truths.
- gt_bboxes (np.ndarray): 2D ground truth bboxes.
- gt_labels (np.ndarray): Labels of ground truths.
- difficulty (int): Difficulty defined by KITTI.
0, 1, 2 represent xxxxx respectively.
"""
inds
=
[
i
for
i
,
x
in
enumerate
(
gt_names
)
if
x
in
used_classes
]
inds
=
np
.
array
(
inds
,
dtype
=
np
.
int64
)
return
inds
def
remove_dontcare
(
self
,
ann_info
):
"""Remove annotations that do not need to be cared.
ann_info
=
super
().
parse_ann_info
(
info
)
Args:
ann_info (dict): Dict of annotation infos. The ``'DontCare'``
annotations will be removed according to ann_file['name'].
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
)
Returns:
dict: Annotations after filtering.
"""
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
# 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
return
ann_info
def
format_results
(
self
,
outputs
,
...
...
mmdet3d/datasets/lyft_dataset.py
View file @
a79b105b
...
...
@@ -14,12 +14,12 @@ from mmdet3d.core.evaluation.lyft_eval import lyft_eval
from
mmdet3d.registry
import
DATASETS
from
..core
import
show_result
from
..core.bbox
import
Box3DMode
,
Coord3DMode
,
LiDARInstance3DBoxes
from
.
custom_3d
import
Custom
3DDataset
from
.
det3d_dataset
import
Det
3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
LyftDataset
(
Custom
3DDataset
):
class
LyftDataset
(
Det
3DDataset
):
r
"""Lyft Dataset.
This class serves as the API for experiments on the Lyft Dataset.
...
...
mmdet3d/datasets/nuscenes_dataset.py
View file @
a79b105b
...
...
@@ -10,12 +10,12 @@ from nuscenes.utils.data_classes import Box as NuScenesBox
from
mmdet3d.registry
import
DATASETS
from
..core
import
show_result
from
..core.bbox
import
Box3DMode
,
Coord3DMode
,
LiDARInstance3DBoxes
from
.
custom_3d
import
Custom
3DDataset
from
.
det3d_dataset
import
Det
3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
NuScenesDataset
(
Custom
3DDataset
):
class
NuScenesDataset
(
Det
3DDataset
):
r
"""NuScenes Dataset.
This class serves as the API for experiments on the NuScenes Dataset.
...
...
mmdet3d/datasets/s3dis_dataset.py
View file @
a79b105b
...
...
@@ -6,13 +6,13 @@ import numpy as np
from
mmdet3d.core
import
show_seg_result
from
mmdet3d.core.bbox
import
DepthInstance3DBoxes
from
mmdet3d.registry
import
DATASETS
from
.custom_3d
import
Custom3DDataset
from
.custom_3d_seg
import
Custom3DSegDataset
from
.det3d_dataset
import
Det3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
S3DISDataset
(
Custom
3DDataset
):
class
S3DISDataset
(
Det
3DDataset
):
r
"""S3DIS Dataset for Detection Task.
This class is the inner dataset for S3DIS. Since S3DIS has 6 areas, we
...
...
mmdet3d/datasets/scannet_dataset.py
View file @
a79b105b
...
...
@@ -8,13 +8,13 @@ import numpy as np
from
mmdet3d.core
import
instance_seg_eval
,
show_result
,
show_seg_result
from
mmdet3d.core.bbox
import
DepthInstance3DBoxes
from
mmdet3d.registry
import
DATASETS
from
.custom_3d
import
Custom3DDataset
from
.custom_3d_seg
import
Custom3DSegDataset
from
.det3d_dataset
import
Det3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
ScanNetDataset
(
Custom
3DDataset
):
class
ScanNetDataset
(
Det
3DDataset
):
r
"""ScanNet Dataset for Detection Task.
This class serves as the API for experiments on the ScanNet Dataset.
...
...
mmdet3d/datasets/semantickitti_dataset.py
View file @
a79b105b
...
...
@@ -2,11 +2,11 @@
from
os
import
path
as
osp
from
mmdet3d.registry
import
DATASETS
from
.
custom_3d
import
Custom
3DDataset
from
.
det3d_dataset
import
Det
3DDataset
@
DATASETS
.
register_module
()
class
SemanticKITTIDataset
(
Custom
3DDataset
):
class
SemanticKITTIDataset
(
Det
3DDataset
):
r
"""SemanticKITTI Dataset.
This class serves as the API for experiments on the SemanticKITTI Dataset
...
...
mmdet3d/datasets/sunrgbd_dataset.py
View file @
a79b105b
...
...
@@ -8,12 +8,12 @@ from mmdet3d.core import show_multi_modality_result, show_result
from
mmdet3d.core.bbox
import
DepthInstance3DBoxes
from
mmdet3d.registry
import
DATASETS
from
mmdet.core
import
eval_map
from
.
custom_3d
import
Custom
3DDataset
from
.
det3d_dataset
import
Det
3DDataset
from
.pipelines
import
Compose
@
DATASETS
.
register_module
()
class
SUNRGBDDataset
(
Custom
3DDataset
):
class
SUNRGBDDataset
(
Det
3DDataset
):
r
"""SUNRGBD Dataset.
This class serves as the API for experiments on the SUNRGBD Dataset.
...
...
tests/data/kitti/kitti_infos_train.pkl
View file @
a79b105b
No preview for this file type
tests/test_data/test_datasets/test_kitti_dataset.py
0 → 100644
View file @
a79b105b
# Copyright (c) OpenMMLab. All rights reserved.
import
numpy
as
np
from
mmdet3d.core
import
LiDARInstance3DBoxes
from
mmdet3d.datasets
import
KittiDataset
def
_generate_kitti_dataset_config
():
data_root
=
'tests/data/kitti'
ann_file
=
'kitti_infos_train.pkl'
classes
=
[
'Pedestrian'
,
'Cyclist'
,
'Car'
]
# wait for pipline refactor
pipeline
=
[
dict
(
type
=
'LoadPointsFromFile'
,
coord_type
=
'LIDAR'
,
load_dim
=
4
,
use_dim
=
4
,
file_client_args
=
dict
(
backend
=
'disk'
)),
dict
(
type
=
'MultiScaleFlipAug3D'
,
img_scale
=
(
1333
,
800
),
pts_scale_ratio
=
1
,
flip
=
False
,
transforms
=
[
dict
(
type
=
'GlobalRotScaleTrans'
,
rot_range
=
[
0
,
0
],
scale_ratio_range
=
[
1.0
,
1.0
],
translation_std
=
[
0
,
0
,
0
]),
dict
(
type
=
'RandomFlip3D'
),
dict
(
type
=
'PointsRangeFilter'
,
point_cloud_range
=
[
0
,
-
40
,
-
3
,
70.4
,
40
,
1
]),
dict
(
type
=
'DefaultFormatBundle3D'
,
class_names
=
classes
,
with_label
=
False
),
dict
(
type
=
'Collect3D'
,
keys
=
[
'points'
])
])
]
modality
=
dict
(
use_lidar
=
True
,
use_camera
=
False
)
data_prefix
=
dict
(
pts
=
'training/velodyne_reduced'
,
img
=
'training/image_2'
)
return
data_root
,
ann_file
,
classes
,
data_prefix
,
pipeline
,
modality
def
test_getitem
():
np
.
random
.
seed
(
0
)
data_root
,
ann_file
,
classes
,
data_prefix
,
\
_
,
modality
,
=
_generate_kitti_dataset_config
()
modality
[
'use_camera'
]
=
True
from
mmcv.transforms.base
import
BaseTransform
from
mmengine.registry
import
TRANSFORMS
@
TRANSFORMS
.
register_module
()
class
Identity
(
BaseTransform
):
def
transform
(
self
,
info
):
if
'ann_info'
in
info
:
info
[
'gt_labels_3d'
]
=
info
[
'ann_info'
][
'gt_labels_3d'
]
return
info
pipeline
=
[
dict
(
type
=
'Identity'
),
]
kitti_dataset
=
KittiDataset
(
data_root
,
ann_file
,
data_prefix
=
dict
(
pts
=
'training/velodyne_reduced'
,
img
=
'training/image_2'
,
),
pipeline
=
pipeline
,
metainfo
=
dict
(
CLASSES
=
classes
),
modality
=
modality
)
kitti_dataset
.
prepare_data
(
0
)
input_dict
=
kitti_dataset
.
get_data_info
(
0
)
kitti_dataset
[
0
]
# assert the the path should contains data_prefix and data_root
assert
data_prefix
[
'pts'
]
in
input_dict
[
'lidar_points'
][
'lidar_path'
]
assert
data_root
in
input_dict
[
'lidar_points'
][
'lidar_path'
]
for
cam_id
,
img_info
in
input_dict
[
'images'
].
items
():
if
'img_path'
in
img_info
:
assert
data_prefix
[
'img'
]
in
img_info
[
'img_path'
]
assert
data_root
in
img_info
[
'img_path'
]
ann_info
=
kitti_dataset
.
parse_ann_info
(
input_dict
)
# assert the keys in ann_info and the type
assert
'gt_labels'
in
ann_info
assert
ann_info
[
'gt_labels'
].
dtype
==
np
.
int64
# only one instance
assert
len
(
ann_info
[
'gt_labels'
])
==
1
assert
'gt_labels_3d'
in
ann_info
assert
ann_info
[
'gt_labels_3d'
].
dtype
==
np
.
int64
assert
'gt_bboxes'
in
ann_info
assert
ann_info
[
'gt_bboxes'
].
dtype
==
np
.
float64
assert
'gt_bboxes_3d'
in
ann_info
assert
isinstance
(
ann_info
[
'gt_bboxes_3d'
],
LiDARInstance3DBoxes
)
assert
'group_id'
in
ann_info
assert
ann_info
[
'group_id'
].
dtype
==
np
.
int64
assert
'occluded'
in
ann_info
assert
ann_info
[
'occluded'
].
dtype
==
np
.
int64
assert
'difficulty'
in
ann_info
assert
ann_info
[
'difficulty'
].
dtype
==
np
.
int64
assert
'num_lidar_pts'
in
ann_info
assert
ann_info
[
'num_lidar_pts'
].
dtype
==
np
.
int64
assert
'truncated'
in
ann_info
assert
ann_info
[
'truncated'
].
dtype
==
np
.
int64
car_kitti_dataset
=
KittiDataset
(
data_root
,
ann_file
,
data_prefix
=
dict
(
pts
=
'training/velodyne_reduced'
,
img
=
'training/image_2'
,
),
pipeline
=
pipeline
,
metainfo
=
dict
(
CLASSES
=
[
'Car'
]),
modality
=
modality
)
input_dict
=
car_kitti_dataset
.
get_data_info
(
0
)
ann_info
=
car_kitti_dataset
.
parse_ann_info
(
input_dict
)
# assert the keys in ann_info and the type
assert
'gt_labels'
in
ann_info
assert
ann_info
[
'gt_labels'
].
dtype
==
np
.
int64
# all instance have been filtered by classes
assert
len
(
ann_info
[
'gt_labels'
])
==
0
assert
len
(
car_kitti_dataset
.
metainfo
[
'CLASSES'
])
==
1
tools/data_converter/__init__.py
deleted
100644 → 0
View file @
3fa5a430
# Copyright (c) OpenMMLab. All rights reserved.
tools/data_converter/update_infos_to_v2.py
0 → 100644
View file @
a79b105b
# Copyright (c) OpenMMLab. All rights reserved.
"""Convert the annotation pkl to the standard format in OpenMMLab V2.0.
Example:
python tools/data_converter/update_infos_to_v2.py
--pkl ./data/kitti/kitti_infos_train.pkl
--out-dir ./kitti_v2/
"""
import
argparse
import
copy
import
time
from
os
import
path
as
osp
import
mmcv
import
numpy
as
np
def
get_empty_instance
():
"""Empty annotation for single instance."""
instance
=
dict
(
# (list[float], required): list of 4 numbers representing
# the bounding box of the instance, in (x1, y1, x2, y2) order.
bbox
=
None
,
# (int, required): an integer in the range
# [0, num_categories-1] representing the category label.
bbox_label
=
None
,
# (list[float], optional): list of 7 (or 9) numbers representing
# the 3D bounding box of the instance,
# in [x, y, z, w, h, l, yaw]
# (or [x, y, z, w, h, l, yaw, vx, vy]) order.
bbox_3d
=
None
,
# (bool, optional): Whether to use the
# 3D bounding box during training.
bbox_3d_isvalid
=
None
,
# (int, optional): 3D category label
# (typically the same as label).
bbox_label_3d
=
None
,
# (float, optional): Projected center depth of the
# 3D bounding box compared to the image plane.
depth
=
None
,
# (list[float], optional): Projected
# 2D center of the 3D bounding box.
center_2d
=
None
,
# (int, optional): Attribute labels
# (fine-grained labels such as stopping, moving, ignore, crowd).
attr_label
=
None
,
# (int, optional): The number of LiDAR
# points in the 3D bounding box.
num_lidar_pts
=
None
,
# (int, optional): The number of Radar
# points in the 3D bounding box.
num_radar_pts
=
None
,
# (int, optional): Difficulty level of
# detecting the 3D bounding box.
difficulty
=
None
,
unaligned_bbox_3d
=
None
)
return
instance
def
get_empty_lidar_points
():
lidar_points
=
dict
(
# (int, optional) : Number of features for each point.
num_pts_feats
=
None
,
# (str, optional): Path of LiDAR data file.
lidar_path
=
None
,
# (list[list[float]]): Transformation matrix from lidar
# or depth to image with shape [4, 4].
lidar2img
=
None
,
# (list[list[float]], optional): Transformation matrix
# from lidar to ego-vehicle
# with shape [4, 4].
# (Referenced camera coordinate system is ego in KITTI.)
lidar2ego
=
None
,
)
return
lidar_points
def
get_empty_radar_points
():
radar_points
=
dict
(
# (int, optional) : Number of features for each point.
num_pts_feats
=
None
,
# (str, optional): Path of RADAR data file.
radar_path
=
None
,
# Transformation matrix from lidar to
# ego-vehicle with shape [4, 4].
# (Referenced camera coordinate system is ego in KITTI.)
radar2ego
=
None
,
)
return
radar_points
def
get_empty_img_info
():
img_info
=
dict
(
# (str, required): the path to the image file.
img_path
=
None
,
# (int) The height of the image.
height
=
None
,
# (int) The width of the image.
width
=
None
,
# (str, optional): Path of the depth map file
depth_map
=
None
,
# (list[list[float]], optional) : Transformation
# matrix from camera to image with
# shape [3, 3], [3, 4] or [4, 4].
cam2img
=
None
,
# (list[list[float]], optional) : Transformation
# matrix from camera to ego-vehicle
# with shape [4, 4].
cam2ego
=
None
)
return
img_info
def
get_single_image_sweep
():
single_image_sweep
=
dict
(
# (float, optional) : Timestamp of the current frame.
timestamp
=
None
,
# (list[list[float]], optional) : Transformation matrix
# from ego-vehicle to the global
ego2global
=
None
,
# (dict): Information of images captured by multiple cameras
images
=
dict
(
CAM0
=
get_empty_img_info
(),
CAM1
=
get_empty_img_info
(),
CAM2
=
get_empty_img_info
(),
CAM3
=
get_empty_img_info
(),
))
return
single_image_sweep
def
get_single_lidar_sweep
():
single_lidar_sweep
=
dict
(
# (float, optional) : Timestamp of the current frame.
timestamp
=
None
,
# (list[list[float]], optional) : Transformation matrix
# from ego-vehicle to the global
ego2global
=
None
,
# (dict): Information of images captured by multiple cameras
lidar_points
=
get_empty_lidar_points
())
return
single_lidar_sweep
def
get_empty_standard_data_info
():
data_info
=
dict
(
# (str): Sample id of the frame.
sample_id
=
None
,
# (str, optional): '000010'
token
=
None
,
**
get_single_image_sweep
(),
# (dict, optional): dict contains information
# of LiDAR point cloud frame.
lidar_points
=
get_empty_lidar_points
(),
# (dict, optional) Each dict contains
# information of Radar point cloud frame.
radar_points
=
get_empty_radar_points
(),
# (list[dict], optional): Image sweeps data.
image_sweeps
=
[],
instances
=
[],
# (list[dict], optional): Required by object
# detection, instance to be ignored during training.
instances_ignore
=
[],
# (str, optional): Path of semantic labels for each point.
pts_semantic_mask_path
=
None
,
# (str, optional): Path of instance labels for each point.
pts_instance_mask_path
=
None
)
return
data_info
def
clear_instance_unused_keys
(
instance
):
keys
=
list
(
instance
.
keys
())
for
k
in
keys
:
if
instance
[
k
]
is
None
:
del
instance
[
k
]
return
instance
def
clear_data_info_unused_keys
(
data_info
):
keys
=
list
(
data_info
.
keys
())
empty_flag
=
True
for
key
in
keys
:
# we allow no annotations in datainfo
if
key
==
'instances'
:
empty_flag
=
False
continue
if
isinstance
(
data_info
[
key
],
list
):
if
len
(
data_info
[
key
])
==
0
:
del
data_info
[
key
]
else
:
empty_flag
=
False
elif
data_info
[
key
]
is
None
:
del
data_info
[
key
]
elif
isinstance
(
data_info
[
key
],
dict
):
_
,
sub_empty_flag
=
clear_data_info_unused_keys
(
data_info
[
key
])
if
sub_empty_flag
is
False
:
empty_flag
=
False
else
:
# sub field is empty
del
data_info
[
key
]
else
:
empty_flag
=
False
return
data_info
,
empty_flag
def
update_kitti_infos
(
pkl_path
,
out_dir
):
print
(
f
'
{
pkl_path
}
will be modified.'
)
if
out_dir
in
pkl_path
:
print
(
f
'Warning, you may overwriting '
f
'the original data
{
pkl_path
}
.'
)
time
.
sleep
(
5
)
# TODO update to full label
# TODO discuss how to process 'Van', 'DontCare'
METAINFO
=
{
'CLASSES'
:
(
'Pedestrian'
,
'Cyclist'
,
'Car'
),
}
print
(
f
'Reading from input file:
{
pkl_path
}
.'
)
data_list
=
mmcv
.
load
(
pkl_path
)
print
(
'Start updating:'
)
converted_list
=
[]
for
ori_info_dict
in
mmcv
.
track_iter_progress
(
data_list
):
temp_data_info
=
get_empty_standard_data_info
()
if
'plane'
in
ori_info_dict
:
temp_data_info
[
'plane'
]
=
ori_info_dict
[
'plane'
]
temp_data_info
[
'sample_id'
]
=
ori_info_dict
[
'image'
][
'image_idx'
]
temp_data_info
[
'images'
][
'CAM0'
][
'cam2img'
]
=
ori_info_dict
[
'calib'
][
'P0'
].
tolist
()
temp_data_info
[
'images'
][
'CAM1'
][
'cam2img'
]
=
ori_info_dict
[
'calib'
][
'P1'
].
tolist
()
temp_data_info
[
'images'
][
'CAM2'
][
'cam2img'
]
=
ori_info_dict
[
'calib'
][
'P2'
].
tolist
()
temp_data_info
[
'images'
][
'CAM3'
][
'cam2img'
]
=
ori_info_dict
[
'calib'
][
'P3'
].
tolist
()
temp_data_info
[
'images'
][
'CAM2'
][
'img_path'
]
=
ori_info_dict
[
'image'
][
'image_path'
].
split
(
'/'
)[
-
1
]
h
,
w
=
ori_info_dict
[
'image'
][
'image_shape'
]
temp_data_info
[
'images'
][
'CAM2'
][
'height'
]
=
h
temp_data_info
[
'images'
][
'CAM2'
][
'width'
]
=
w
temp_data_info
[
'lidar_points'
][
'num_pts_feats'
]
=
ori_info_dict
[
'point_cloud'
][
'num_features'
]
temp_data_info
[
'lidar_points'
][
'lidar_path'
]
=
ori_info_dict
[
'point_cloud'
][
'velodyne_path'
].
split
(
'/'
)[
-
1
]
rect
=
ori_info_dict
[
'calib'
][
'R0_rect'
].
astype
(
np
.
float32
)
Trv2c
=
ori_info_dict
[
'calib'
][
'Tr_velo_to_cam'
].
astype
(
np
.
float32
)
lidar2cam
=
rect
@
Trv2c
temp_data_info
[
'images'
][
'CAM2'
][
'lidar2cam'
]
=
lidar2cam
.
tolist
()
temp_data_info
[
'lidar_points'
][
'Tr_velo_to_cam'
]
=
Trv2c
.
tolist
()
# for potential usage
temp_data_info
[
'images'
][
'R0_rect'
]
=
ori_info_dict
[
'calib'
][
'R0_rect'
].
astype
(
np
.
float32
).
tolist
()
temp_data_info
[
'lidar_points'
][
'Tr_imu_to_velo'
]
=
ori_info_dict
[
'calib'
][
'Tr_imu_to_velo'
].
astype
(
np
.
float32
).
tolist
()
anns
=
ori_info_dict
[
'annos'
]
num_instances
=
len
(
anns
[
'name'
])
ignore_class_name
=
set
()
instance_list
=
[]
for
instance_id
in
range
(
num_instances
):
empty_instance
=
get_empty_instance
()
empty_instance
[
'bbox'
]
=
anns
[
'bbox'
][
instance_id
].
tolist
()
if
anns
[
'name'
][
instance_id
]
in
METAINFO
[
'CLASSES'
]:
empty_instance
[
'bbox_label'
]
=
METAINFO
[
'CLASSES'
].
index
(
anns
[
'name'
][
instance_id
])
else
:
ignore_class_name
.
add
(
anns
[
'name'
][
instance_id
])
empty_instance
[
'bbox_label'
]
=
-
1
empty_instance
[
'bbox'
]
=
anns
[
'bbox'
][
instance_id
].
tolist
()
loc
=
anns
[
'location'
][
instance_id
]
dims
=
anns
[
'dimensions'
][
instance_id
]
rots
=
anns
[
'rotation_y'
][:,
None
][
instance_id
]
gt_bboxes_3d
=
np
.
concatenate
([
loc
,
dims
,
rots
]).
astype
(
np
.
float32
).
tolist
()
empty_instance
[
'bbox_3d'
]
=
gt_bboxes_3d
empty_instance
[
'bbox_label_3d'
]
=
copy
.
deepcopy
(
empty_instance
[
'bbox_label'
])
empty_instance
[
'bbox'
]
=
anns
[
'bbox'
][
instance_id
].
tolist
()
empty_instance
[
'truncated'
]
=
int
(
anns
[
'truncated'
][
instance_id
].
tolist
())
empty_instance
[
'occluded'
]
=
anns
[
'occluded'
][
instance_id
].
tolist
()
empty_instance
[
'alpha'
]
=
anns
[
'alpha'
][
instance_id
].
tolist
()
empty_instance
[
'score'
]
=
anns
[
'score'
][
instance_id
].
tolist
()
empty_instance
[
'index'
]
=
anns
[
'index'
][
instance_id
].
tolist
()
empty_instance
[
'group_id'
]
=
anns
[
'group_ids'
][
instance_id
].
tolist
(
)
empty_instance
[
'difficulty'
]
=
anns
[
'difficulty'
][
instance_id
].
tolist
()
empty_instance
[
'num_lidar_pts'
]
=
anns
[
'num_points_in_gt'
][
instance_id
].
tolist
()
empty_instance
=
clear_instance_unused_keys
(
empty_instance
)
instance_list
.
append
(
empty_instance
)
temp_data_info
[
'instances'
]
=
instance_list
temp_data_info
,
_
=
clear_data_info_unused_keys
(
temp_data_info
)
converted_list
.
append
(
temp_data_info
)
pkl_name
=
pkl_path
.
split
(
'/'
)[
-
1
]
out_path
=
osp
.
join
(
out_dir
,
pkl_name
)
print
(
f
'Writing to output file:
{
out_path
}
.'
)
print
(
f
'ignore classes:
{
ignore_class_name
}
'
)
converted_data_info
=
dict
(
metainfo
=
{
'DATASET'
:
'KITTI'
},
data_list
=
converted_list
)
mmcv
.
dump
(
converted_data_info
,
out_path
,
'pkl'
)
def
parse_args
():
parser
=
argparse
.
ArgumentParser
(
description
=
'Arg parser for data coords '
'update due to coords sys refactor.'
)
parser
.
add_argument
(
'--dataset'
,
type
=
str
,
default
=
'kitti'
,
help
=
'name of dataset'
)
parser
.
add_argument
(
'--pkl'
,
type
=
str
,
default
=
'./data/kitti/kitti_infos_train.pkl '
,
help
=
'specify the root dir of dataset'
)
parser
.
add_argument
(
'--out-dir'
,
type
=
str
,
default
=
'converted_annotations'
,
required
=
False
,
help
=
'output direction of info pkl'
)
args
=
parser
.
parse_args
()
return
args
def
main
():
args
=
parse_args
()
if
args
.
out_dir
is
None
:
args
.
out_dir
=
args
.
root_dir
if
args
.
dataset
==
'kitti'
:
update_kitti_infos
(
pkl_path
=
args
.
pkl
,
out_dir
=
args
.
out_dir
)
if
__name__
==
'__main__'
:
main
()
Write
Preview
Markdown
is supported
0%
Try again
or
attach a new file
.
Attach a file
Cancel
You are about to add
0
people
to the discussion. Proceed with caution.
Finish editing this message first!
Cancel
Please
register
or
sign in
to comment