Unverified Commit 78c29c35 authored by Ziyi Wu's avatar Ziyi Wu Committed by GitHub
Browse files

[Enhance] Add pipeline for data loading (#430)

* reuse pipeline in scannet-det dataset

* reuse pipeline in kitti dataset

* reuse pipeline in lyft dataset

* reuse pipeline in sunrgbd dataset

* reuse pipeline in nuscenes dataset

* reuse pipeline in waymo dataset

* reuse pipeline in scannet-seg dataset

* add eval_pipeline in configs which have custom data pipelines

* move data loading via pipeline to dataset._extract_data() for clarity

* use eval_pipeline in tools/misc/visualize_results.py

* get_pipeline from self when no pipeline is provided

* fix small bugs

* fix small bugs

* simplify and clear code

* remove unnecessary eval_pipeline added

* add comment about why we set self.test_mode=False

* small fix

* modify docs about config
parent 80ef7fee
......@@ -260,6 +260,16 @@ test_pipeline = [
dict(type='Collect3D', keys=['points'])
])
]
# construct a pipeline for data and gt loading in show function
# please keep its loading function consistent with test_pipeline (e.g. client)
eval_pipeline = [
dict(type='LoadPointsFromFile', coord_type='LIDAR', load_dim=4, use_dim=4),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
data = dict(
samples_per_gpu=2,
......@@ -301,4 +311,5 @@ data = dict(
# Part-A2 uses a different learning rate from what SECOND uses.
lr = 0.001
optimizer = dict(lr=lr)
evaluation = dict(pipeline=eval_pipeline)
find_unused_parameters = True
......@@ -242,6 +242,22 @@ test_pipeline = [ # Testing pipeline, refer to mmdet3d.datasets.pipelines for m
dict(type='Collect3D', # Pipeline that decides which keys in the data should be passed to the detector, refer to mmdet3d.datasets.pipelines.formating for more details
keys=['points'])
]
eval_pipeline = [ # Pipeline used for evaluation or visualization, refer to mmdet3d.datasets.pipelines for more details
dict(
type='LoadPointsFromFile', # First pipeline to load points, refer to mmdet3d.datasets.pipelines.indoor_loading for more details
shift_height=True, # Whether to use shifted height
load_dim=6, # The dimension of the loaded points
use_dim=[0, 1, 2]), # Which dimensions of the points to be used
dict(
type='DefaultFormatBundle3D', # Default format bundle to gather data in the pipeline, refer to mmdet3d.datasets.pipelines.formating for more details
class_names=('cabinet', 'bed', 'chair', 'sofa', 'table', 'door',
'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet',
'sink', 'bathtub', 'garbagebin')),
with_label=False),
dict(type='Collect3D', # Pipeline that decides which keys in the data should be passed to the detector, refer to mmdet3d.datasets.pipelines.formating for more details
keys=['points'])
]
data = dict(
samples_per_gpu=8, # Batch size of a single GPU
workers_per_gpu=4, # Worker to pre-fetch data for each single GPU
......@@ -347,6 +363,22 @@ data = dict(
'refrigerator', 'showercurtrain', 'toilet', 'sink', 'bathtub',
'garbagebin'), # Names of classes
test_mode=True)) # Whether to use test mode
evaluation = dict(pipeline=[ # Pipeline is passed by eval_pipeline created before
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='DefaultFormatBundle3D',
class_names=('cabinet', 'bed', 'chair', 'sofa', 'table', 'door',
'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet',
'sink', 'bathtub', 'garbagebin'),
with_label=False),
dict(type='Collect3D', keys=['points'])
])
lr = 0.008 # Learning rate of optimizers
optimizer = dict( # Config used to build optimizer, support all the optimizers in PyTorch whose arguments are also the same as those in PyTorch
type='Adam', # Type of optimizers, # Type of optimizers, refer to https://github.com/open-mmlab/mmdetection/blob/master/mmdet/core/optimizer/default_constructor.py#L13 for more details
......
import mmcv
import numpy as np
import tempfile
import warnings
from os import path as osp
from torch.utils.data import Dataset
from mmdet.datasets import DATASETS
from ..core.bbox import get_box_type
from .pipelines import Compose
from .utils import get_loading_pipeline
@DATASETS.register_module()
......@@ -226,7 +228,8 @@ class Custom3DDataset(Dataset):
iou_thr=(0.25, 0.5),
logger=None,
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluate.
Evaluation in indoor protocol.
......@@ -239,6 +242,8 @@ class Custom3DDataset(Dataset):
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict: Evaluation results.
......@@ -262,10 +267,88 @@ class Custom3DDataset(Dataset):
box_type_3d=self.box_type_3d,
box_mode_3d=self.box_mode_3d)
if show:
self.show(results, out_dir)
self.show(results, out_dir, pipeline=pipeline)
return ret_dict
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
raise NotImplementedError('_build_default_pipeline is not implemented '
f'for dataset {self.__class__.__name__}')
def _get_pipeline(self, pipeline):
"""Get data loading pipeline in self.show/evaluate function.
Args:
pipeline (list[dict] | None): Input pipeline. If None is given, \
get from self.pipeline.
"""
if pipeline is None:
if not hasattr(self, 'pipeline') or self.pipeline is None:
warnings.warn(
'Use default pipeline for data loading, this may cause '
'errors when data is on ceph')
return self._build_default_pipeline()
loading_pipeline = get_loading_pipeline(self.pipeline.transforms)
return Compose(loading_pipeline)
return Compose(pipeline)
@staticmethod
def _get_data(results, key):
"""Extract and return the data corresponding to key in result dict.
Args:
results (dict): Data loaded using pipeline.
key (str): Key of the desired data.
Returns:
np.ndarray | torch.Tensor | None: Data term.
"""
if key not in results.keys():
return None
# results[key] may be data or list[data]
# data may be wrapped inside DataContainer
data = results[key]
if isinstance(data, list) or isinstance(data, tuple):
data = data[0]
if isinstance(data, mmcv.parallel.DataContainer):
data = data._data
return data
def _extract_data(self, index, pipeline, key, load_annos=False):
"""Load data using input pipeline and extract data according to key.
Args:
index (int): Index for accessing the target data.
pipeline (:obj:`Compose`): Composed data loading pipeline.
key (str | list[str]): One single or a list of data key.
load_annos (bool): Whether to load data annotations.
If True, need to set self.test_mode as False before loading.
Returns:
np.ndarray | torch.Tensor | list[np.ndarray | torch.Tensor]:
A single or a list of loaded data.
"""
assert pipeline is not None, 'data loading pipeline is not provided'
# when we want to load ground-truth via pipeline (e.g. bbox, seg mask)
# we need to set self.test_mode as False so that we have 'annos'
if load_annos:
original_test_mode = self.test_mode
self.test_mode = False
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = pipeline(input_dict)
# extract data items according to keys
if isinstance(key, str):
data = self._get_data(example, key)
else:
data = [self._get_data(example, k) for k in key]
if load_annos:
self.test_mode = original_test_mode
return data
def __len__(self):
"""Return the length of data infos.
......
import mmcv
import numpy as np
import tempfile
import torch
import warnings
from os import path as osp
from torch.utils.data import Dataset
from mmdet.datasets import DATASETS
from .pipelines import Compose
from .utils import get_loading_pipeline
@DATASETS.register_module()
......@@ -308,27 +309,13 @@ class Custom3DSegDataset(Dataset):
mmcv.dump(outputs, out)
return outputs, tmp_dir
def convert_to_label(self, mask):
"""Convert class_id in segmentation mask to label."""
# TODO: currently only support loading from local
# TODO: may need to consider ceph data storage in the future
if isinstance(mask, str):
if mask.endswith('npy'):
mask = np.load(mask)
else:
mask = np.fromfile(mask, dtype=np.long)
mask_copy = mask.copy()
for class_id, label in self.label_map.items():
mask_copy[mask == class_id] = label
return mask_copy
def evaluate(self,
results,
metric=None,
logger=None,
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluate.
Evaluation in semantic segmentation protocol.
......@@ -342,6 +329,8 @@ class Custom3DSegDataset(Dataset):
Defaults to False.
out_dir (str, optional): Path to save the visualization results.
Defaults to None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict: Evaluation results.
......@@ -354,13 +343,13 @@ class Custom3DSegDataset(Dataset):
assert isinstance(
results[0], dict
), f'Expect elements in results to be dict, got {type(results[0])}.'
load_pipeline = self._get_pipeline(pipeline)
pred_sem_masks = [result['semantic_mask'] for result in results]
gt_sem_masks = [
torch.from_numpy(
self.convert_to_label(
osp.join(self.data_root,
data_info['pts_semantic_mask_path'])))
for data_info in self.data_infos
self._extract_data(
i, load_pipeline, 'pts_semantic_mask', load_annos=True)
for i in range(len(self.data_infos))
]
ret_dict = seg_eval(
gt_sem_masks,
......@@ -368,8 +357,9 @@ class Custom3DSegDataset(Dataset):
self.label2cat,
self.ignore_index,
logger=logger)
if show:
self.show(pred_sem_masks, out_dir)
self.show(pred_sem_masks, out_dir, pipeline=pipeline)
return ret_dict
......@@ -382,6 +372,84 @@ class Custom3DSegDataset(Dataset):
pool = np.where(self.flag == self.flag[idx])[0]
return np.random.choice(pool)
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
raise NotImplementedError('_build_default_pipeline is not implemented '
f'for dataset {self.__class__.__name__}')
def _get_pipeline(self, pipeline):
"""Get data loading pipeline in self.show/evaluate function.
Args:
pipeline (list[dict] | None): Input pipeline. If None is given, \
get from self.pipeline.
"""
if pipeline is None:
if not hasattr(self, 'pipeline') or self.pipeline is None:
warnings.warn(
'Use default pipeline for data loading, this may cause '
'errors when data is on ceph')
return self._build_default_pipeline()
loading_pipeline = get_loading_pipeline(self.pipeline.transforms)
return Compose(loading_pipeline)
return Compose(pipeline)
@staticmethod
def _get_data(results, key):
"""Extract and return the data corresponding to key in result dict.
Args:
results (dict): Data loaded using pipeline.
key (str): Key of the desired data.
Returns:
np.ndarray | torch.Tensor | None: Data term.
"""
if key not in results.keys():
return None
# results[key] may be data or list[data]
# data may be wrapped inside DataContainer
data = results[key]
if isinstance(data, list) or isinstance(data, tuple):
data = data[0]
if isinstance(data, mmcv.parallel.DataContainer):
data = data._data
return data
def _extract_data(self, index, pipeline, key, load_annos=False):
"""Load data using input pipeline and extract data according to key.
Args:
index (int): Index for accessing the target data.
pipeline (:obj:`Compose`): Composed data loading pipeline.
key (str | list[str]): One single or a list of data key.
load_annos (bool): Whether to load data annotations.
If True, need to set self.test_mode as False before loading.
Returns:
np.ndarray | torch.Tensor | list[np.ndarray | torch.Tensor]:
A single or a list of loaded data.
"""
assert pipeline is not None, 'data loading pipeline is not provided'
# when we want to load ground-truth via pipeline (e.g. bbox, seg mask)
# we need to set self.test_mode as False so that we have 'annos'
if load_annos:
original_test_mode = self.test_mode
self.test_mode = False
input_dict = self.get_data_info(index)
self.pre_pipeline(input_dict)
example = pipeline(input_dict)
# extract data items according to keys
if isinstance(key, str):
data = self._get_data(example, key)
else:
data = [self._get_data(example, k) for k in key]
if load_annos:
self.test_mode = original_test_mode
return data
def __len__(self):
"""Return the length of scene_idxs.
......
......@@ -12,6 +12,7 @@ from ..core import show_multi_modality_result, show_result
from ..core.bbox import (Box3DMode, CameraInstance3DBoxes, Coord3DMode,
LiDARInstance3DBoxes, points_cam2img)
from .custom_3d import Custom3DDataset
from .pipelines import Compose
@DATASETS.register_module()
......@@ -300,7 +301,8 @@ class KittiDataset(Custom3DDataset):
pklfile_prefix=None,
submission_prefix=None,
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluation in KITTI protocol.
Args:
......@@ -317,6 +319,8 @@ class KittiDataset(Custom3DDataset):
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict[str, float]: Results of each evaluation metric.
......@@ -354,7 +358,7 @@ class KittiDataset(Custom3DDataset):
if tmp_dir is not None:
tmp_dir.cleanup()
if show:
self.show(results, out_dir)
self.show(results, out_dir, pipeline=pipeline)
return ap_dict
def bbox2result_kitti(self,
......@@ -668,22 +672,47 @@ class KittiDataset(Custom3DDataset):
label_preds=np.zeros([0, 4]),
sample_idx=sample_idx)
def show(self, results, out_dir, show=True):
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):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
example = self.prepare_test_data(i)
if 'pts_bbox' in result.keys():
result = result['pts_bbox']
data_info = self.data_infos[i]
pts_path = data_info['point_cloud']['velodyne_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
points, img_metas, img = self._extract_data(
i, pipeline, ['points', 'img_metas', 'img'])
points = points.numpy()
# for now we convert points into depth mode
points = example['points'][0]._data.numpy()
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
......@@ -696,9 +725,10 @@ class KittiDataset(Custom3DDataset):
file_name, show)
# multi-modality visualization
if self.modality['use_camera'] and \
'lidar2img' in example['img_metas'][0]._data.keys():
img = mmcv.imread(example['img_metas'][0]._data['filename'])
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)
show_pred_bboxes = LiDARInstance3DBoxes(
pred_bboxes, origin=(0.5, 0.5, 0))
show_gt_bboxes = LiDARInstance3DBoxes(
......@@ -707,7 +737,7 @@ class KittiDataset(Custom3DDataset):
img,
show_gt_bboxes,
show_pred_bboxes,
example['img_metas'][0]._data['lidar2img'],
img_metas['lidar2img'],
out_dir,
file_name,
show=False)
......@@ -12,6 +12,7 @@ from mmdet.datasets import DATASETS
from ..core import show_result
from ..core.bbox import Box3DMode, Coord3DMode, LiDARInstance3DBoxes
from .custom_3d import Custom3DDataset
from .pipelines import Compose
@DATASETS.register_module()
......@@ -356,7 +357,8 @@ class LyftDataset(Custom3DDataset):
csv_savepath=None,
result_names=['pts_bbox'],
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluation in Lyft protocol.
Args:
......@@ -375,6 +377,8 @@ class LyftDataset(Custom3DDataset):
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict[str, float]: Evaluation results.
......@@ -395,33 +399,60 @@ class LyftDataset(Custom3DDataset):
tmp_dir.cleanup()
if show:
self.show(results, out_dir)
self.show(results, out_dir, pipeline=pipeline)
return results_dict
def show(self, results, out_dir):
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=dict(backend='disk')),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=dict(backend='disk')),
dict(
type='DefaultFormatBundle3D',
class_names=self.CLASSES,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
return Compose(pipeline)
def show(self, results, out_dir, show=True, pipeline=None):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
example = self.prepare_test_data(i)
points = example['points'][0]._data.numpy()
if 'pts_bbox' in result.keys():
result = result['pts_bbox']
data_info = self.data_infos[i]
pts_path = data_info['lidar_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
# for now we convert points into depth mode
points = self._extract_data(i, pipeline, 'points').numpy()
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
inds = result['pts_bbox']['scores_3d'] > 0.1
inds = result['scores_3d'] > 0.1
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes = result['pts_bbox']['boxes_3d'][inds].tensor.numpy()
pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
show_gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes = result['boxes_3d'][inds].tensor.numpy()
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)
def json2csv(self, json_path, csv_savepath):
"""Convert the json file to csv format for submission.
......
......@@ -9,6 +9,7 @@ from mmdet.datasets import DATASETS
from ..core import show_result
from ..core.bbox import Box3DMode, Coord3DMode, LiDARInstance3DBoxes
from .custom_3d import Custom3DDataset
from .pipelines import Compose
@DATASETS.register_module()
......@@ -453,7 +454,8 @@ class NuScenesDataset(Custom3DDataset):
jsonfile_prefix=None,
result_names=['pts_bbox'],
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluation in nuScenes protocol.
Args:
......@@ -468,6 +470,8 @@ class NuScenesDataset(Custom3DDataset):
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict[str, float]: Results of each evaluation metric.
......@@ -487,33 +491,61 @@ class NuScenesDataset(Custom3DDataset):
tmp_dir.cleanup()
if show:
self.show(results, out_dir)
self.show(results, out_dir, pipeline=pipeline)
return results_dict
def show(self, results, out_dir):
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=dict(backend='disk')),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=dict(backend='disk')),
dict(
type='DefaultFormatBundle3D',
class_names=self.CLASSES,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
return Compose(pipeline)
def show(self, results, out_dir, show=True, pipeline=None):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
example = self.prepare_test_data(i)
points = example['points'][0]._data.numpy()
if 'pts_bbox' in result.keys():
result = result['pts_bbox']
data_info = self.data_infos[i]
pts_path = data_info['lidar_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
points = self._extract_data(i, pipeline, 'points').numpy()
# for now we convert points into depth mode
points = Coord3DMode.convert_point(points, Coord3DMode.LIDAR,
Coord3DMode.DEPTH)
inds = result['pts_bbox']['scores_3d'] > 0.1
inds = result['scores_3d'] > 0.1
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes = result['pts_bbox']['boxes_3d'][inds].tensor.numpy()
pred_bboxes = Box3DMode.convert(pred_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name)
show_gt_bboxes = Box3DMode.convert(gt_bboxes, Box3DMode.LIDAR,
Box3DMode.DEPTH)
pred_bboxes = result['boxes_3d'][inds].tensor.numpy()
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)
def output_to_nusc_box(detection):
......
from mmdet.datasets.pipelines import Compose
from .dbsampler import DataBaseSampler
from .formating import Collect3D, DefaultFormatBundle, DefaultFormatBundle3D
from .loading import (LoadAnnotations3D, LoadMultiViewImageFromFiles,
LoadPointsFromFile, LoadPointsFromMultiSweeps,
NormalizePointsColor, PointSegClassMapping)
from .loading import (LoadAnnotations3D, LoadImageFromFileMono3D,
LoadMultiViewImageFromFiles, LoadPointsFromFile,
LoadPointsFromMultiSweeps, NormalizePointsColor,
PointSegClassMapping)
from .test_time_aug import MultiScaleFlipAug3D
from .transforms_3d import (BackgroundPointsFilter, GlobalRotScaleTrans,
IndoorPatchPointSample, IndoorPointSample,
......@@ -19,5 +20,5 @@ __all__ = [
'NormalizePointsColor', 'LoadAnnotations3D', 'IndoorPointSample',
'PointSegClassMapping', 'MultiScaleFlipAug3D', 'LoadPointsFromMultiSweeps',
'BackgroundPointsFilter', 'VoxelBasedPointSampler',
'IndoorPatchPointSample'
'IndoorPatchPointSample', 'LoadImageFromFileMono3D'
]
......@@ -7,6 +7,7 @@ from mmdet3d.core.bbox import DepthInstance3DBoxes
from mmdet.datasets import DATASETS
from .custom_3d import Custom3DDataset
from .custom_3d_seg import Custom3DSegDataset
from .pipelines import Compose
@DATASETS.register_module()
......@@ -108,22 +109,40 @@ class ScanNetDataset(Custom3DDataset):
pts_semantic_mask_path=pts_semantic_mask_path)
return anns_results
def show(self, results, out_dir, show=True):
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='DefaultFormatBundle3D',
class_names=self.CLASSES,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
return Compose(pipeline)
def show(self, results, out_dir, show=True, pipeline=None):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
data_info = self.data_infos[i]
pts_path = data_info['pts_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
points = np.fromfile(
osp.join(self.data_root, pts_path),
dtype=np.float32).reshape(-1, 6)
points = self._extract_data(i, pipeline, 'points').numpy()
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
pred_bboxes = result['boxes_3d'].tensor.numpy()
show_result(points, gt_bboxes, pred_bboxes, out_dir, file_name,
......@@ -239,25 +258,53 @@ class ScanNetSegDataset(Custom3DSegDataset):
anns_results = dict(pts_semantic_mask_path=pts_semantic_mask_path)
return anns_results
def show(self, results, out_dir, show=True):
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(
type='LoadAnnotations3D',
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16,
24, 28, 33, 34, 36, 39)),
dict(
type='DefaultFormatBundle3D',
with_label=False,
class_names=self.CLASSES),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
return Compose(pipeline)
def show(self, results, out_dir, show=True, pipeline=None):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
data_info = self.data_infos[i]
pts_path = data_info['pts_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
points = np.fromfile(
osp.join(self.data_root, pts_path),
dtype=np.float32).reshape(-1, 6)
sem_mask_path = data_info['pts_semantic_mask_path']
gt_sem_mask = self.convert_to_label(
osp.join(self.data_root, sem_mask_path))
points, gt_sem_mask = self._extract_data(
i, pipeline, ['points', 'pts_semantic_mask'], load_annos=True)
points = points.numpy()
pred_sem_mask = result['semantic_mask'].numpy()
show_seg_result(points, gt_sem_mask,
pred_sem_mask, out_dir, file_name,
......
import mmcv
import numpy as np
from collections import OrderedDict
from os import path as osp
......@@ -8,6 +7,7 @@ from mmdet3d.core.bbox import DepthInstance3DBoxes
from mmdet.core import eval_map
from mmdet.datasets import DATASETS
from .custom_3d import Custom3DDataset
from .pipelines import Compose
@DATASETS.register_module()
......@@ -152,26 +152,45 @@ class SUNRGBDDataset(Custom3DDataset):
return anns_results
def show(self, results, out_dir, show=True):
def _build_default_pipeline(self):
"""Build the default pipeline for this dataset."""
pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2]),
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):
"""Results visualization.
Args:
results (list[dict]): List of bounding boxes results.
out_dir (str): Output directory of visualization result.
show (bool): Visualize the results online.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
"""
assert out_dir is not None, 'Expect out_dir, got none.'
pipeline = self._get_pipeline(pipeline)
for i, result in enumerate(results):
data_info = self.data_infos[i]
pts_path = data_info['pts_path']
file_name = osp.split(pts_path)[-1].split('.')[0]
if hasattr(self, 'pipeline'):
example = self.prepare_test_data(i)
else:
example = None
points = np.fromfile(
osp.join(self.data_root, pts_path),
dtype=np.float32).reshape(-1, 6)
points, img_metas, img, calib = self._extract_data(
i, pipeline, ['points', 'img_metas', 'img', 'calib'])
# scale colors to [0, 255]
points = points.numpy()
points[:, 3:] *= 255
gt_bboxes = self.get_ann_info(i)['gt_bboxes_3d'].tensor.numpy()
......@@ -180,9 +199,10 @@ class SUNRGBDDataset(Custom3DDataset):
file_name, show)
# multi-modality visualization
if self.modality['use_camera'] and example is not None and \
'calib' in data_info.keys():
img = mmcv.imread(example['img_metas']._data['filename'])
if self.modality['use_camera'] and 'calib' in data_info.keys():
img = img.numpy()
# need to transpose channel to first dim
img = img.transpose(1, 2, 0)
pred_bboxes = DepthInstance3DBoxes(
pred_bboxes, origin=(0.5, 0.5, 0))
gt_bboxes = DepthInstance3DBoxes(
......@@ -191,11 +211,11 @@ class SUNRGBDDataset(Custom3DDataset):
img,
gt_bboxes,
pred_bboxes,
example['calib'],
calib,
out_dir,
file_name,
depth_bbox=True,
img_metas=example['img_metas']._data,
img_metas=img_metas,
show=show)
def evaluate(self,
......@@ -205,12 +225,31 @@ class SUNRGBDDataset(Custom3DDataset):
iou_thr_2d=(0.5, ),
logger=None,
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluate.
Evaluation in indoor protocol.
Args:
results (list[dict]): List of results.
metric (str | list[str]): Metrics to be evaluated.
iou_thr (list[float]): AP IoU thresholds.
iou_thr_2d (list[float]): AP IoU thresholds for 2d evaluation.
show (bool): Whether to visualize.
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict: Evaluation results.
"""
# evaluate 3D detection performance
if isinstance(results[0], dict):
return super().evaluate(results, metric, iou_thr, logger, show,
out_dir)
out_dir, pipeline)
# evaluate 2D detection performance
else:
eval_results = OrderedDict()
......
# yapf: disable
from mmdet3d.datasets.pipelines import (Collect3D, DefaultFormatBundle3D,
LoadAnnotations3D,
LoadImageFromFileMono3D,
LoadMultiViewImageFromFiles,
LoadPointsFromFile,
LoadPointsFromMultiSweeps)
LoadPointsFromMultiSweeps,
MultiScaleFlipAug3D,
PointSegClassMapping)
# yapf: enable
from mmdet.datasets.builder import PIPELINES
from mmdet.datasets.pipelines import LoadImageFromFile
def is_loading_function(transform):
"""Judge whether a transform function is a loading function.
Args:
transform (dict | :obj:`Pipeline`): A transform config or a function.
Returns:
bool | None: Whether it is a loading function. None means can't judge.
When transform is `MultiScaleFlipAug3D`, we return None.
"""
# TODO: use more elegant way to distinguish loading modules
loading_functions = (LoadImageFromFile, LoadPointsFromFile,
LoadAnnotations3D, LoadMultiViewImageFromFiles,
LoadPointsFromMultiSweeps, DefaultFormatBundle3D,
Collect3D, LoadImageFromFileMono3D,
PointSegClassMapping)
if isinstance(transform, dict):
obj_cls = PIPELINES.get(transform['type'])
if obj_cls is None:
return False
if obj_cls in loading_functions:
return True
if obj_cls in (MultiScaleFlipAug3D):
return None
elif callable(transform):
if isinstance(transform, loading_functions):
return True
if isinstance(transform, MultiScaleFlipAug3D):
return None
return False
def get_loading_pipeline(pipeline):
"""Only keep loading image, points and annotations related configuration.
Args:
pipeline (list[dict]): Data pipeline configs.
pipeline (list[dict] | list[:obj:`Pipeline`]):
Data pipeline configs or list of pipeline functions.
Returns:
list[dict]: The new pipeline list with only keep
loading image, points and annotations related configuration.
list[dict] | list[:obj:`Pipeline`]): The new pipeline list with only
keep loading image, points and annotations related configuration.
Examples:
>>> pipelines = [
......@@ -51,16 +89,19 @@ def get_loading_pipeline(pipeline):
>>> assert expected_pipelines ==\
... get_loading_pipeline(pipelines)
"""
loading_pipeline_cfg = []
for cfg in pipeline:
obj_cls = PIPELINES.get(cfg['type'])
# TODO: use more elegant way to distinguish loading modules
if obj_cls is not None and obj_cls in (
LoadImageFromFile, LoadPointsFromFile, LoadAnnotations3D,
LoadMultiViewImageFromFiles, LoadPointsFromMultiSweeps,
DefaultFormatBundle3D, Collect3D):
loading_pipeline_cfg.append(cfg)
assert len(loading_pipeline_cfg) > 0, \
loading_pipeline = []
for transform in pipeline:
is_loading = is_loading_function(transform)
if is_loading is None: # MultiScaleFlipAug3D
# extract its inner pipeline
if isinstance(transform, dict):
inner_pipeline = transform.get('transforms', [])
else:
inner_pipeline = transform.transforms.transforms
loading_pipeline.extend(get_loading_pipeline(inner_pipeline))
elif is_loading:
loading_pipeline.append(transform)
assert len(loading_pipeline) > 0, \
'The data pipeline in your config file must include ' \
'loading step.'
return loading_pipeline_cfg
return loading_pipeline
......@@ -219,7 +219,8 @@ class WaymoDataset(KittiDataset):
pklfile_prefix=None,
submission_prefix=None,
show=False,
out_dir=None):
out_dir=None,
pipeline=None):
"""Evaluation in KITTI protocol.
Args:
......@@ -237,6 +238,8 @@ class WaymoDataset(KittiDataset):
Default: False.
out_dir (str): Path to save the visualization results.
Default: None.
pipeline (list[dict], optional): raw data loading for showing.
Default: None.
Returns:
dict[str: float]: results of each evaluation metric
......@@ -346,7 +349,7 @@ class WaymoDataset(KittiDataset):
tmp_dir.cleanup()
if show:
self.show(results, out_dir)
self.show(results, out_dir, pipeline=pipeline)
return ap_dict
def bbox2result_kitti(self,
......
......@@ -261,6 +261,30 @@ def test_show():
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# test show with pipeline
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4),
dict(
type='DefaultFormatBundle3D',
class_names=classes,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
kitti_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, '000000', '000000_points.obj')
gt_file_path = osp.join(temp_dir, '000000', '000000_gt.obj')
pred_file_path = osp.join(temp_dir, '000000', '000000_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# test multi-modality show
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
......@@ -283,6 +307,37 @@ def test_show():
mmcv.check_file_exist(img_gt_file)
tmp_dir.cleanup()
# test multi-modality show with pipeline
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=4,
use_dim=4),
dict(type='LoadImageFromFile'),
dict(
type='DefaultFormatBundle3D',
class_names=classes,
with_label=False),
dict(type='Collect3D', keys=['points', 'img'])
]
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
kitti_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, '000000', '000000_points.obj')
gt_file_path = osp.join(temp_dir, '000000', '000000_gt.obj')
pred_file_path = osp.join(temp_dir, '000000', '000000_pred.obj')
img_file_path = osp.join(temp_dir, '000000', '000000_img.png')
img_pred_path = osp.join(temp_dir, '000000', '000000_pred.png')
img_gt_file = osp.join(temp_dir, '000000', '000000_gt.png')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
mmcv.check_file_exist(img_file_path)
mmcv.check_file_exist(img_pred_path)
mmcv.check_file_exist(img_gt_file)
tmp_dir.cleanup()
def test_format_results():
from mmdet3d.core.bbox import LiDARInstance3DBoxes
......
import mmcv
import numpy as np
import tempfile
import torch
from mmdet3d.datasets import LyftDataset
......@@ -114,3 +115,54 @@ def test_evaluate():
ap_dict = lyft_dataset.evaluate(results, 'bbox')
car_precision = ap_dict['pts_bbox_Lyft/car_AP']
assert car_precision == 0.6
def test_show():
import mmcv
from os import path as osp
from mmdet3d.core.bbox import LiDARInstance3DBoxes
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
root_path = './tests/data/lyft'
ann_file = './tests/data/lyft/lyft_infos.pkl'
class_names = ('car', 'truck', 'bus', 'emergency_vehicle', 'other_vehicle',
'motorcycle', 'bicycle', 'pedestrian', 'animal')
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=dict(backend='disk')),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=dict(backend='disk')),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
kitti_dataset = LyftDataset(ann_file, None, root_path)
boxes_3d = LiDARInstance3DBoxes(
torch.tensor(
[[46.1218, -4.6496, -0.9275, 0.5316, 1.4442, 1.7450, 1.1749],
[33.3189, 0.1981, 0.3136, 0.5656, 1.2301, 1.7985, 1.5723],
[46.1366, -4.6404, -0.9510, 0.5162, 1.6501, 1.7540, 1.3778],
[33.2646, 0.2297, 0.3446, 0.5746, 1.3365, 1.7947, 1.5430],
[58.9079, 16.6272, -1.5829, 1.5656, 3.9313, 1.4899, 1.5505]]))
scores_3d = torch.tensor([0.1815, 0.1663, 0.5792, 0.2194, 0.2780])
labels_3d = torch.tensor([0, 0, 1, 1, 2])
result = dict(boxes_3d=boxes_3d, scores_3d=scores_3d, labels_3d=labels_3d)
results = [dict(pts_bbox=result)]
kitti_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
file_name = 'host-a017_lidar1_1236118886901125926'
pts_file_path = osp.join(temp_dir, file_name, f'{file_name}_points.obj')
gt_file_path = osp.join(temp_dir, file_name, f'{file_name}_gt.obj')
pred_file_path = osp.join(temp_dir, file_name, f'{file_name}_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
import numpy as np
import tempfile
import torch
from mmdet3d.datasets import NuScenesDataset
......@@ -59,3 +61,55 @@ def test_getitem():
assert data['img_metas'][0].data['flip'] is False
assert data['img_metas'][0].data['pcd_horizontal_flip'] is False
assert data['points'][0]._data.shape == (597, 4)
def test_show():
import mmcv
from os import path as osp
from mmdet3d.core.bbox import LiDARInstance3DBoxes
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
class_names = [
'car', 'truck', 'trailer', 'bus', 'construction_vehicle', 'bicycle',
'motorcycle', 'pedestrian', 'traffic_cone', 'barrier'
]
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=dict(backend='disk')),
dict(
type='LoadPointsFromMultiSweeps',
sweeps_num=10,
file_client_args=dict(backend='disk')),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
nus_dataset = NuScenesDataset('tests/data/nuscenes/nus_info.pkl', None,
'tests/data/nuscenes')
boxes_3d = LiDARInstance3DBoxes(
torch.tensor(
[[46.1218, -4.6496, -0.9275, 0.5316, 1.4442, 1.7450, 1.1749],
[33.3189, 0.1981, 0.3136, 0.5656, 1.2301, 1.7985, 1.5723],
[46.1366, -4.6404, -0.9510, 0.5162, 1.6501, 1.7540, 1.3778],
[33.2646, 0.2297, 0.3446, 0.5746, 1.3365, 1.7947, 1.5430],
[58.9079, 16.6272, -1.5829, 1.5656, 3.9313, 1.4899, 1.5505]]))
scores_3d = torch.tensor([0.1815, 0.1663, 0.5792, 0.2194, 0.2780])
labels_3d = torch.tensor([0, 0, 1, 1, 2])
result = dict(boxes_3d=boxes_3d, scores_3d=scores_3d, labels_3d=labels_3d)
results = [dict(pts_bbox=result)]
nus_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
file_name = 'n015-2018-08-02-17-16-37+0800__LIDAR_TOP__1533201470948018'
pts_file_path = osp.join(temp_dir, file_name, f'{file_name}_points.obj')
gt_file_path = osp.join(temp_dir, file_name, f'{file_name}_gt.obj')
pred_file_path = osp.join(temp_dir, file_name, f'{file_name}_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
......@@ -214,6 +214,37 @@ def test_show():
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# show function with pipeline
class_names = ('cabinet', 'bed', 'chair', 'sofa', 'table', 'door',
'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet',
'sink', 'bathtub', 'garbagebin')
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
scannet_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, 'scene0000_00',
'scene0000_00_points.obj')
gt_file_path = osp.join(temp_dir, 'scene0000_00', 'scene0000_00_gt.obj')
pred_file_path = osp.join(temp_dir, 'scene0000_00',
'scene0000_00_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
def test_seg_getitem():
np.random.seed(0)
......@@ -489,7 +520,33 @@ def test_seg_evaluate():
13, 2, 3, 1, 0, 13, 19, 1, 14, 5, 3, 1, 13, 1, 2, 3, 2, 1
]).long())
results.append(pred_sem_mask)
ret_dict = scannet_dataset.evaluate(results)
class_names = ('wall', 'floor', 'cabinet', 'bed', 'chair', 'sofa', 'table',
'door', 'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet',
'sink', 'bathtub', 'otherfurniture')
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(
type='LoadAnnotations3D',
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24,
28, 33, 34, 36, 39)),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
ret_dict = scannet_dataset.evaluate(results, pipeline=eval_pipeline)
assert abs(ret_dict['miou'] - 0.5308) < 0.01
assert abs(ret_dict['acc'] - 0.8219) < 0.01
assert abs(ret_dict['acc_cls'] - 0.7649) < 0.01
......@@ -525,6 +582,44 @@ def test_seg_show():
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# test show with pipeline
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
class_names = ('wall', 'floor', 'cabinet', 'bed', 'chair', 'sofa', 'table',
'door', 'window', 'bookshelf', 'picture', 'counter', 'desk',
'curtain', 'refrigerator', 'showercurtrain', 'toilet',
'sink', 'bathtub', 'otherfurniture')
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=False,
use_color=True,
load_dim=6,
use_dim=[0, 1, 2, 3, 4, 5]),
dict(
type='LoadAnnotations3D',
with_bbox_3d=False,
with_label_3d=False,
with_mask_3d=False,
with_seg_3d=True),
dict(
type='PointSegClassMapping',
valid_cat_ids=(1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 14, 16, 24,
28, 33, 34, 36, 39)),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(type='Collect3D', keys=['points', 'pts_semantic_mask'])
]
scannet_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, 'scene0000_00',
'scene0000_00_points.obj')
gt_file_path = osp.join(temp_dir, 'scene0000_00', 'scene0000_00_gt.obj')
pred_file_path = osp.join(temp_dir, 'scene0000_00',
'scene0000_00_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
def test_seg_format_results():
......@@ -557,4 +652,3 @@ def test_seg_format_results():
expected_txt_path = osp.join(tmp_dir.name, 'results', 'scene0000_00.txt')
assert np.all(result_files[0]['seg_mask'] == expected_label)
mmcv.check_file_exist(expected_txt_path)
tmp_dir.cleanup()
......@@ -210,7 +210,7 @@ def test_show():
from mmdet3d.core.bbox import DepthInstance3DBoxes
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
root_path, ann_file, _, pipelines, modality = \
root_path, ann_file, class_names, pipelines, modality = \
_generate_sunrgbd_dataset_config()
sunrgbd_dataset = SUNRGBDDataset(
root_path, ann_file, pipelines, modality=modality)
......@@ -235,14 +235,71 @@ def test_show():
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# test show with pipeline
eval_pipeline = [
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points'])
]
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
sunrgbd_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, '000001', '000001_points.obj')
gt_file_path = osp.join(temp_dir, '000001', '000001_gt.obj')
pred_file_path = osp.join(temp_dir, '000001', '000001_pred.obj')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
tmp_dir.cleanup()
# test multi-modality show
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
root_path, ann_file, _, multi_modality_pipelines, modality = \
root_path, ann_file, class_names, multi_modality_pipelines, modality = \
_generate_sunrgbd_multi_modality_dataset_config()
sunrgbd_dataset = SUNRGBDDataset(
root_path, ann_file, multi_modality_pipelines, modality=modality)
sunrgbd_dataset.show(results, temp_dir, show=False)
sunrgbd_dataset.show(results, temp_dir, False, multi_modality_pipelines)
pts_file_path = osp.join(temp_dir, '000001', '000001_points.obj')
gt_file_path = osp.join(temp_dir, '000001', '000001_gt.obj')
pred_file_path = osp.join(temp_dir, '000001', '000001_pred.obj')
img_file_path = osp.join(temp_dir, '000001', '000001_img.png')
img_pred_path = osp.join(temp_dir, '000001', '000001_pred.png')
img_gt_file = osp.join(temp_dir, '000001', '000001_gt.png')
mmcv.check_file_exist(pts_file_path)
mmcv.check_file_exist(gt_file_path)
mmcv.check_file_exist(pred_file_path)
mmcv.check_file_exist(img_file_path)
mmcv.check_file_exist(img_pred_path)
mmcv.check_file_exist(img_gt_file)
tmp_dir.cleanup()
# test multi-modality show with pipeline
eval_pipeline = [
dict(type='LoadImageFromFile'),
dict(
type='LoadPointsFromFile',
coord_type='DEPTH',
shift_height=True,
load_dim=6,
use_dim=[0, 1, 2]),
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points', 'img', 'calib'])
]
tmp_dir = tempfile.TemporaryDirectory()
temp_dir = tmp_dir.name
sunrgbd_dataset.show(results, temp_dir, show=False, pipeline=eval_pipeline)
pts_file_path = osp.join(temp_dir, '000001', '000001_points.obj')
gt_file_path = osp.join(temp_dir, '000001', '000001_gt.obj')
pred_file_path = osp.join(temp_dir, '000001', '000001_pred.obj')
......
......@@ -32,7 +32,12 @@ def main():
results = mmcv.load(args.result)
if getattr(dataset, 'show', None) is not None:
dataset.show(results, args.show_dir)
# data loading pipeline for showing
eval_pipeline = cfg.get('eval_pipeline', {})
if eval_pipeline:
dataset.show(results, args.show_dir, pipeline=eval_pipeline)
else:
dataset.show(results, args.show_dir) # use default pipeline
else:
raise NotImplementedError(
'Show is not implemented for dataset {}!'.format(
......
Markdown is supported
0% or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment