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
49121b64
Commit
49121b64
authored
May 12, 2020
by
yinchimaoliang
Browse files
Merge branch 'master_temp' into scannet_dataset
parents
f8f05baf
868c5fab
Changes
48
Hide whitespace changes
Inline
Side-by-side
Showing
20 changed files
with
1030 additions
and
19 deletions
+1030
-19
configs/kitti/dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
...igs/kitti/dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
+2
-1
configs/kitti/dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py
.../kitti/dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py
+2
-1
configs/kitti/dv_second_secfpn_6x8_80e_kitti-3d-car.py
configs/kitti/dv_second_secfpn_6x8_80e_kitti-3d-car.py
+2
-1
configs/kitti/hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
...igs/kitti/hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
+2
-1
configs/kitti/hv_second_secfpn_6x8_80e_kitti-3d-car.py
configs/kitti/hv_second_secfpn_6x8_80e_kitti-3d-car.py
+2
-1
docs/INSTALL.md
docs/INSTALL.md
+5
-1
mmdet3d/core/bbox/__init__.py
mmdet3d/core/bbox/__init__.py
+3
-1
mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py
mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py
+22
-6
mmdet3d/core/bbox/samplers/__init__.py
mmdet3d/core/bbox/samplers/__init__.py
+2
-1
mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py
mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py
+154
-0
mmdet3d/core/bbox/structures/__init__.py
mmdet3d/core/bbox/structures/__init__.py
+5
-0
mmdet3d/core/bbox/structures/base_box3d.py
mmdet3d/core/bbox/structures/base_box3d.py
+277
-0
mmdet3d/core/bbox/structures/box_3d_mode.py
mmdet3d/core/bbox/structures/box_3d_mode.py
+150
-0
mmdet3d/core/bbox/structures/cam_box3d.py
mmdet3d/core/bbox/structures/cam_box3d.py
+160
-0
mmdet3d/core/bbox/structures/lidar_box3d.py
mmdet3d/core/bbox/structures/lidar_box3d.py
+155
-0
mmdet3d/core/bbox/structures/utils.py
mmdet3d/core/bbox/structures/utils.py
+61
-0
mmdet3d/datasets/__init__.py
mmdet3d/datasets/__init__.py
+10
-4
mmdet3d/datasets/kitti_dataset.py
mmdet3d/datasets/kitti_dataset.py
+2
-0
mmdet3d/datasets/pipelines/__init__.py
mmdet3d/datasets/pipelines/__init__.py
+9
-1
mmdet3d/datasets/pipelines/data_augment_utils.py
mmdet3d/datasets/pipelines/data_augment_utils.py
+5
-0
No files found.
configs/kitti/dv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
View file @
49121b64
...
...
@@ -93,7 +93,8 @@ class_names = ['Car']
img_norm_cfg
=
dict
(
mean
=
[
123.675
,
116.28
,
103.53
],
std
=
[
58.395
,
57.12
,
57.375
],
to_rgb
=
True
)
input_modality
=
dict
(
use_lidar
=
True
,
use_lidar
=
False
,
use_lidar_reduced
=
True
,
use_depth
=
False
,
use_lidar_intensity
=
True
,
use_camera
=
False
,
...
...
configs/kitti/dv_second_secfpn_2x8_cosine_80e_kitti-3d-3class.py
View file @
49121b64
...
...
@@ -113,7 +113,8 @@ class_names = ['Pedestrian', 'Cyclist', 'Car']
img_norm_cfg
=
dict
(
mean
=
[
123.675
,
116.28
,
103.53
],
std
=
[
58.395
,
57.12
,
57.375
],
to_rgb
=
True
)
input_modality
=
dict
(
use_lidar
=
True
,
use_lidar
=
False
,
use_lidar_reduced
=
True
,
use_depth
=
False
,
use_lidar_intensity
=
True
,
use_camera
=
True
,
...
...
configs/kitti/dv_second_secfpn_6x8_80e_kitti-3d-car.py
View file @
49121b64
...
...
@@ -91,7 +91,8 @@ class_names = ['Car']
img_norm_cfg
=
dict
(
mean
=
[
123.675
,
116.28
,
103.53
],
std
=
[
58.395
,
57.12
,
57.375
],
to_rgb
=
True
)
input_modality
=
dict
(
use_lidar
=
True
,
use_lidar
=
False
,
use_lidar_reduced
=
True
,
use_depth
=
False
,
use_lidar_intensity
=
True
,
use_camera
=
True
,
...
...
configs/kitti/hv_pointpillars_secfpn_6x8_160e_kitti-3d-car.py
View file @
49121b64
...
...
@@ -90,7 +90,8 @@ class_names = ['Car']
img_norm_cfg
=
dict
(
mean
=
[
123.675
,
116.28
,
103.53
],
std
=
[
58.395
,
57.12
,
57.375
],
to_rgb
=
True
)
input_modality
=
dict
(
use_lidar
=
True
,
use_lidar
=
False
,
use_lidar_reduced
=
True
,
use_depth
=
False
,
use_lidar_intensity
=
True
,
use_camera
=
False
,
...
...
configs/kitti/hv_second_secfpn_6x8_80e_kitti-3d-car.py
View file @
49121b64
...
...
@@ -89,7 +89,8 @@ class_names = ['Car']
img_norm_cfg
=
dict
(
mean
=
[
123.675
,
116.28
,
103.53
],
std
=
[
58.395
,
57.12
,
57.375
],
to_rgb
=
True
)
input_modality
=
dict
(
use_lidar
=
True
,
use_lidar
=
False
,
use_lidar_reduced
=
True
,
use_depth
=
False
,
use_lidar_intensity
=
True
,
use_camera
=
False
,
...
...
docs/INSTALL.md
View file @
49121b64
...
...
@@ -110,7 +110,11 @@ mmdetection
│ ├── VOCdevkit
│ │ ├── VOC2007
│ │ ├── VOC2012
│ ├── ScanNet
│ │ ├── meta_data
│ │ ├── scannet_train_instance_data
│ ├── SUNRGBD
│ │ ├── sunrgbd_trainval
```
The cityscapes annotations have to be converted into the coco format using
`tools/convert_datasets/cityscapes.py`
:
```
shell
...
...
mmdet3d/core/bbox/__init__.py
View file @
49121b64
...
...
@@ -7,6 +7,7 @@ from .iou_calculators import (BboxOverlaps3D, BboxOverlapsNearest3D,
from
.samplers
import
(
BaseSampler
,
CombinedSampler
,
InstanceBalancedPosSampler
,
IoUBalancedNegSampler
,
PseudoSampler
,
RandomSampler
,
SamplingResult
)
from
.structures
import
Box3DMode
,
CameraInstance3DBoxes
,
LiDARInstance3DBoxes
from
.transforms
import
boxes3d_to_bev_torch_lidar
from
.assign_sampling
import
(
# isort:skip, avoid recursive imports
...
...
@@ -20,5 +21,6 @@ __all__ = [
'build_assigner'
,
'build_sampler'
,
'assign_and_sample'
,
'box_torch_ops'
,
'build_bbox_coder'
,
'DeltaXYZWLHRBBoxCoder'
,
'boxes3d_to_bev_torch_lidar'
,
'BboxOverlapsNearest3D'
,
'BboxOverlaps3D'
,
'bbox_overlaps_nearest_3d'
,
'bbox_overlaps_3d'
'bbox_overlaps_3d'
,
'Box3DMode'
,
'LiDARInstance3DBoxes'
,
'CameraInstance3DBoxes'
]
mmdet3d/core/bbox/iou_calculators/iou3d_calculator.py
View file @
49121b64
import
torch
from
mmdet3d.ops.iou3d
import
boxes_iou3d_gpu
from
mmdet3d.ops.iou3d
import
boxes_iou3d_gpu
_camera
,
boxes_iou3d_gpu_lidar
from
mmdet.core.bbox
import
bbox_overlaps
from
mmdet.core.bbox.iou_calculators.builder
import
IOU_CALCULATORS
from
..
import
box_torch_ops
...
...
@@ -22,10 +22,18 @@ class BboxOverlapsNearest3D(object):
@
IOU_CALCULATORS
.
register_module
()
class
BboxOverlaps3D
(
object
):
"""3D IoU Calculator
"""
"""3D IoU Calculator
def
__call__
(
self
,
bboxes1
,
bboxes2
,
mode
=
'iou'
,
is_aligned
=
False
):
return
bbox_overlaps_3d
(
bboxes1
,
bboxes2
,
mode
,
is_aligned
)
Args:
coordinate (str): 'camera' or 'lidar' coordinate system
"""
def
__init__
(
self
,
coordinate
):
assert
coordinate
in
[
'camera'
,
'lidar'
]
self
.
coordinate
=
coordinate
def
__call__
(
self
,
bboxes1
,
bboxes2
,
mode
=
'iou'
):
return
bbox_overlaps_3d
(
bboxes1
,
bboxes2
,
mode
,
self
.
coordinate
)
def
__repr__
(
self
):
repr_str
=
self
.
__class__
.
__name__
...
...
@@ -62,7 +70,7 @@ def bbox_overlaps_nearest_3d(bboxes1, bboxes2, mode='iou', is_aligned=False):
return
ret
def
bbox_overlaps_3d
(
bboxes1
,
bboxes2
,
mode
=
'iou'
):
def
bbox_overlaps_3d
(
bboxes1
,
bboxes2
,
mode
=
'iou'
,
coordinate
=
'camera'
):
"""Calculate 3D IoU using cuda implementation
Args:
...
...
@@ -70,6 +78,7 @@ def bbox_overlaps_3d(bboxes1, bboxes2, mode='iou'):
bboxes2: Tensor, shape (M, 7) [x, y, z, h, w, l, ry]
mode: mode (str): "iou" (intersection over union) or
iof (intersection over foreground).
coordinate (str): 'camera' or 'lidar' coordinate system
Return:
iou: (M, N) not support aligned mode currently
...
...
@@ -77,4 +86,11 @@ def bbox_overlaps_3d(bboxes1, bboxes2, mode='iou'):
# TODO: check the input dimension meanings,
# this is inconsistent with that in bbox_overlaps_nearest_3d
assert
bboxes1
.
size
(
-
1
)
==
bboxes2
.
size
(
-
1
)
==
7
return
boxes_iou3d_gpu
(
bboxes1
,
bboxes2
,
mode
)
assert
coordinate
in
[
'camera'
,
'lidar'
]
if
coordinate
==
'camera'
:
return
boxes_iou3d_gpu_camera
(
bboxes1
,
bboxes2
,
mode
)
elif
coordinate
==
'lidar'
:
return
boxes_iou3d_gpu_lidar
(
bboxes1
,
bboxes2
,
mode
)
else
:
raise
NotImplementedError
mmdet3d/core/bbox/samplers/__init__.py
View file @
49121b64
...
...
@@ -3,9 +3,10 @@ from mmdet.core.bbox.samplers import (BaseSampler, CombinedSampler,
IoUBalancedNegSampler
,
OHEMSampler
,
PseudoSampler
,
RandomSampler
,
SamplingResult
)
from
.iou_neg_piecewise_sampler
import
IoUNegPiecewiseSampler
__all__
=
[
'BaseSampler'
,
'PseudoSampler'
,
'RandomSampler'
,
'InstanceBalancedPosSampler'
,
'IoUBalancedNegSampler'
,
'CombinedSampler'
,
'OHEMSampler'
,
'SamplingResult'
'OHEMSampler'
,
'SamplingResult'
,
'IoUNegPiecewiseSampler'
]
mmdet3d/core/bbox/samplers/iou_neg_piecewise_sampler.py
0 → 100644
View file @
49121b64
import
torch
from
mmdet.core.bbox.builder
import
BBOX_SAMPLERS
from
.
import
RandomSampler
,
SamplingResult
@
BBOX_SAMPLERS
.
register_module
class
IoUNegPiecewiseSampler
(
RandomSampler
):
"""IoU Piece-wise Sampling
Sampling negtive proposals according to a list of IoU thresholds.
The negtive proposals are divided into several pieces according
to `neg_iou_piece_thrs`. And the ratio of each piece is indicated
by `neg_piece_fractions`.
Args:
num (int): number of proposals.
pos_fraction (float): the fraction of positive proposals.
neg_piece_fractions (list): a list contains fractions that indicates
the ratio of each piece of total negtive samplers.
neg_iou_piece_thrs (list): a list contains IoU thresholds that
indicate the upper bound of this piece.
neg_pos_ub (float): the total ratio to limit the upper bound
number of negtive samples
add_gt_as_proposals (bool): whether to add gt as proposals.
"""
def
__init__
(
self
,
num
,
pos_fraction
=
None
,
neg_piece_fractions
=
None
,
neg_iou_piece_thrs
=
None
,
neg_pos_ub
=-
1
,
add_gt_as_proposals
=
False
,
return_iou
=
False
):
super
(
IoUNegPiecewiseSampler
,
self
).
__init__
(
num
,
pos_fraction
,
neg_pos_ub
,
add_gt_as_proposals
)
assert
isinstance
(
neg_piece_fractions
,
list
)
assert
len
(
neg_piece_fractions
)
==
len
(
neg_iou_piece_thrs
)
self
.
neg_piece_fractions
=
neg_piece_fractions
self
.
neg_iou_thr
=
neg_iou_piece_thrs
self
.
return_iou
=
return_iou
self
.
neg_piece_num
=
len
(
self
.
neg_piece_fractions
)
def
_sample_pos
(
self
,
assign_result
,
num_expected
,
**
kwargs
):
"""Randomly sample some positive samples."""
pos_inds
=
torch
.
nonzero
(
assign_result
.
gt_inds
>
0
,
as_tuple
=
False
)
if
pos_inds
.
numel
()
!=
0
:
pos_inds
=
pos_inds
.
squeeze
(
1
)
if
pos_inds
.
numel
()
<=
num_expected
:
return
pos_inds
else
:
return
self
.
random_choice
(
pos_inds
,
num_expected
)
def
_sample_neg
(
self
,
assign_result
,
num_expected
,
**
kwargs
):
neg_inds
=
torch
.
nonzero
(
assign_result
.
gt_inds
==
0
)
if
neg_inds
.
numel
()
!=
0
:
neg_inds
=
neg_inds
.
squeeze
(
1
)
if
len
(
neg_inds
)
<=
num_expected
:
return
neg_inds
else
:
neg_inds_choice
=
neg_inds
.
new_zeros
([
0
])
extend_num
=
0
max_overlaps
=
assign_result
.
max_overlaps
[
neg_inds
]
for
piece_inds
in
range
(
self
.
neg_piece_num
):
if
piece_inds
==
self
.
neg_piece_num
-
1
:
# for the last piece
piece_expected_num
=
num_expected
-
len
(
neg_inds_choice
)
min_iou_thr
=
0
else
:
# if the numbers of negative samplers in previous
# pieces are less than the expected number, extend
# the same number in the current piece.
piece_expected_num
=
int
(
num_expected
*
self
.
neg_piece_fractions
[
piece_inds
])
+
extend_num
min_iou_thr
=
self
.
neg_iou_thr
[
piece_inds
+
1
]
max_iou_thr
=
self
.
neg_iou_thr
[
piece_inds
]
piece_neg_inds
=
torch
.
nonzero
(
(
max_overlaps
>=
min_iou_thr
)
&
(
max_overlaps
<
max_iou_thr
)).
view
(
-
1
)
if
len
(
piece_neg_inds
)
<
piece_expected_num
:
neg_inds_choice
=
torch
.
cat
(
[
neg_inds_choice
,
neg_inds
[
piece_neg_inds
]],
dim
=
0
)
extend_num
+=
piece_expected_num
-
len
(
piece_neg_inds
)
else
:
piece_choice
=
self
.
random_choice
(
piece_neg_inds
,
piece_expected_num
)
neg_inds_choice
=
torch
.
cat
(
[
neg_inds_choice
,
neg_inds
[
piece_choice
]],
dim
=
0
)
extend_num
=
0
return
neg_inds_choice
def
sample
(
self
,
assign_result
,
bboxes
,
gt_bboxes
,
gt_labels
=
None
,
**
kwargs
):
"""Sample positive and negative bboxes.
This is a simple implementation of bbox sampling given candidates,
assigning results and ground truth bboxes.
Args:
assign_result (:obj:`AssignResult`): Bbox assigning results.
bboxes (Tensor): Boxes to be sampled from.
gt_bboxes (Tensor): Ground truth bboxes.
gt_labels (Tensor, optional): Class labels of ground truth bboxes.
Returns:
:obj:`SamplingResult`: Sampling result.
"""
if
len
(
bboxes
.
shape
)
<
2
:
bboxes
=
bboxes
[
None
,
:]
gt_flags
=
bboxes
.
new_zeros
((
bboxes
.
shape
[
0
],
),
dtype
=
torch
.
bool
)
if
self
.
add_gt_as_proposals
and
len
(
gt_bboxes
)
>
0
:
if
gt_labels
is
None
:
raise
ValueError
(
'gt_labels must be given when add_gt_as_proposals is True'
)
bboxes
=
torch
.
cat
([
gt_bboxes
,
bboxes
],
dim
=
0
)
assign_result
.
add_gt_
(
gt_labels
)
gt_ones
=
bboxes
.
new_ones
(
gt_bboxes
.
shape
[
0
],
dtype
=
torch
.
bool
)
gt_flags
=
torch
.
cat
([
gt_ones
,
gt_flags
])
num_expected_pos
=
int
(
self
.
num
*
self
.
pos_fraction
)
pos_inds
=
self
.
pos_sampler
.
_sample_pos
(
assign_result
,
num_expected_pos
,
bboxes
=
bboxes
,
**
kwargs
)
# We found that sampled indices have duplicated items occasionally.
# (may be a bug of PyTorch)
pos_inds
=
pos_inds
.
unique
()
num_sampled_pos
=
pos_inds
.
numel
()
num_expected_neg
=
self
.
num
-
num_sampled_pos
if
self
.
neg_pos_ub
>=
0
:
_pos
=
max
(
1
,
num_sampled_pos
)
neg_upper_bound
=
int
(
self
.
neg_pos_ub
*
_pos
)
if
num_expected_neg
>
neg_upper_bound
:
num_expected_neg
=
neg_upper_bound
neg_inds
=
self
.
neg_sampler
.
_sample_neg
(
assign_result
,
num_expected_neg
,
bboxes
=
bboxes
,
**
kwargs
)
neg_inds
=
neg_inds
.
unique
()
sampling_result
=
SamplingResult
(
pos_inds
,
neg_inds
,
bboxes
,
gt_bboxes
,
assign_result
,
gt_flags
)
if
self
.
return_iou
:
# PartA2 needs iou score to regression.
sampling_result
.
iou
=
assign_result
.
max_overlaps
[
torch
.
cat
(
[
pos_inds
,
neg_inds
])]
sampling_result
.
iou
.
detach_
()
return
sampling_result
mmdet3d/core/bbox/structures/__init__.py
0 → 100644
View file @
49121b64
from
.box_3d_mode
import
Box3DMode
from
.cam_box3d
import
CameraInstance3DBoxes
from
.lidar_box3d
import
LiDARInstance3DBoxes
__all__
=
[
'Box3DMode'
,
'LiDARInstance3DBoxes'
,
'CameraInstance3DBoxes'
]
mmdet3d/core/bbox/structures/base_box3d.py
0 → 100644
View file @
49121b64
from
abc
import
abstractmethod
import
numpy
as
np
import
torch
from
.utils
import
limit_period
class
BaseInstance3DBoxes
(
object
):
"""Base class for 3D Boxes
Args:
tensor (torch.Tensor | np.ndarray): a Nxbox_dim matrix.
box_dim (int): number of the dimension of a box
Each row is (x, y, z, x_size, y_size, z_size, yaw).
"""
def
__init__
(
self
,
tensor
,
box_dim
=
7
):
if
isinstance
(
tensor
,
torch
.
Tensor
):
device
=
tensor
.
device
else
:
device
=
torch
.
device
(
'cpu'
)
tensor
=
torch
.
as_tensor
(
tensor
,
dtype
=
torch
.
float32
,
device
=
device
)
if
tensor
.
numel
()
==
0
:
# Use reshape, so we don't end up creating a new tensor that
# does not depend on the inputs (and consequently confuses jit)
tensor
=
tensor
.
reshape
((
0
,
box_dim
)).
to
(
dtype
=
torch
.
float32
,
device
=
device
)
assert
tensor
.
dim
()
==
2
and
tensor
.
size
(
-
1
)
==
box_dim
,
tensor
.
size
()
self
.
box_dim
=
box_dim
self
.
tensor
=
tensor
@
property
def
volume
(
self
):
"""Computes the volume of all the boxes.
Returns:
torch.Tensor: a vector with volume of each box.
"""
return
self
.
tensor
[:,
3
]
*
self
.
tensor
[:,
4
]
*
self
.
tensor
[:,
5
]
@
property
def
dims
(
self
):
"""Calculate the length in each dimension of all the boxes.
Convert the boxes to the form of (x_size, y_size, z_size)
Returns:
torch.Tensor: corners of each box with size (N, 8, 3)
"""
return
self
.
tensor
[:,
3
:
6
]
@
property
def
center
(
self
):
"""Calculate the center of all the boxes.
Note:
In the MMDetection.3D's convention, the bottom center is
usually taken as the default center.
The relative position of the centers in different kinds of
boxes are different, e.g., the relative center of a boxes is
[0.5, 1.0, 0.5] in camera and [0.5, 0.5, 0] in lidar.
It is recommended to use `bottom_center` or `gravity_center`
for more clear usage.
Returns:
torch.Tensor: a tensor with center of each box.
"""
return
self
.
bottom_center
@
property
def
bottom_center
(
self
):
"""Calculate the bottom center of all the boxes.
Returns:
torch.Tensor: a tensor with center of each box.
"""
return
self
.
tensor
[:,
:
3
]
@
property
def
gravity_center
(
self
):
"""Calculate the gravity center of all the boxes.
Returns:
torch.Tensor: a tensor with center of each box.
"""
pass
@
property
def
corners
(
self
):
"""Calculate the coordinates of corners of all the boxes.
Returns:
torch.Tensor: a tensor with 8 corners of each box.
"""
pass
@
abstractmethod
def
rotate
(
self
,
angles
,
axis
=
0
):
"""Calculate whether the points is in any of the boxes
Args:
angles (float): rotation angles
axis (int): the axis to rotate the boxes
"""
pass
@
abstractmethod
def
flip
(
self
):
"""Flip the boxes in horizontal direction
"""
pass
def
translate
(
self
,
trans_vector
):
"""Calculate whether the points is in any of the boxes
Args:
trans_vector (torch.Tensor): translation vector of size 1x3
"""
if
not
isinstance
(
trans_vector
,
torch
.
Tensor
):
trans_vector
=
self
.
tensor
.
new_tensor
(
trans_vector
)
self
.
tensor
[:,
:
3
]
+=
trans_vector
def
in_range_3d
(
self
,
box_range
):
"""Check whether the boxes are in the given range
Args:
box_range (list | torch.Tensor): the range of box
(x_min, y_min, z_min, x_max, y_max, z_max)
Note:
In the original implementation of SECOND, checking whether
a box in the range checks whether the points are in a convex
polygon, we try to reduce the burdun for simpler cases.
TODO: check whether this will effect the performance
Returns:
a binary vector, indicating whether each box is inside
the reference range.
"""
in_range_flags
=
((
self
.
tensor
[:,
0
]
>
box_range
[
0
])
&
(
self
.
tensor
[:,
1
]
>
box_range
[
1
])
&
(
self
.
tensor
[:,
2
]
>
box_range
[
2
])
&
(
self
.
tensor
[:,
0
]
<
box_range
[
3
])
&
(
self
.
tensor
[:,
1
]
<
box_range
[
4
])
&
(
self
.
tensor
[:,
2
]
<
box_range
[
5
]))
return
in_range_flags
@
abstractmethod
def
in_range_bev
(
self
,
box_range
):
"""Check whether the boxes are in the given range
Args:
box_range (list | torch.Tensor): the range of box
(x_min, y_min, x_max, y_max)
Returns:
a binary vector, indicating whether each box is inside
the reference range.
"""
pass
def
scale
(
self
,
scale_factor
):
"""Scale the box with horizontal and vertical scaling factors
Args:
scale_factors (float):
scale factors to scale the boxes.
"""
self
.
tensor
[:,
:
6
]
*=
scale_factor
self
.
tensor
[:,
7
:]
*=
scale_factor
def
limit_yaw
(
self
,
offset
=
0.5
,
period
=
np
.
pi
):
"""Limit the yaw to a given period and offset
Args:
offset (float): the offset of the yaw
period (float): the expected period
"""
self
.
tensor
[:,
6
]
=
limit_period
(
self
.
tensor
[:,
6
],
offset
,
period
)
def
nonempty
(
self
,
threshold
:
float
=
0.0
):
"""Find boxes that are non-empty.
A box is considered empty,
if either of its side is no larger than threshold.
Args:
threshold (float): the threshold of minimal sizes
Returns:
Tensor:
a binary vector which represents whether each box is empty
(False) or non-empty (True).
"""
box
=
self
.
tensor
size_x
=
box
[...,
3
]
size_y
=
box
[...,
4
]
size_z
=
box
[...,
5
]
keep
=
((
size_x
>
threshold
)
&
(
size_y
>
threshold
)
&
(
size_z
>
threshold
))
return
keep
def
__getitem__
(
self
,
item
):
"""
Note:
The following usage are allowed:
1. `new_boxes = boxes[3]`:
return a `Boxes` that contains only one box.
2. `new_boxes = boxes[2:10]`:
return a slice of boxes.
3. `new_boxes = boxes[vector]`:
where vector is a torch.BoolTensor with `length = len(boxes)`.
Nonzero elements in the vector will be selected.
Note that the returned Boxes might share storage with this Boxes,
subject to Pytorch's indexing semantics.
Returns:
Boxes: Create a new :class:`Boxes` by indexing.
"""
original_type
=
type
(
self
)
if
isinstance
(
item
,
int
):
return
original_type
(
self
.
tensor
[
item
].
view
(
1
,
-
1
))
b
=
self
.
tensor
[
item
]
assert
b
.
dim
()
==
2
,
\
f
'Indexing on Boxes with
{
item
}
failed to return a matrix!'
return
original_type
(
b
)
def
__len__
(
self
):
return
self
.
tensor
.
shape
[
0
]
def
__repr__
(
self
):
return
self
.
__class__
.
__name__
+
'(
\n
'
+
str
(
self
.
tensor
)
+
')'
@
classmethod
def
cat
(
cls
,
boxes_list
):
"""Concatenates a list of Boxes into a single Boxes
Arguments:
boxes_list (list[Boxes])
Returns:
Boxes: the concatenated Boxes
"""
assert
isinstance
(
boxes_list
,
(
list
,
tuple
))
if
len
(
boxes_list
)
==
0
:
return
cls
(
torch
.
empty
(
0
))
assert
all
(
isinstance
(
box
,
cls
)
for
box
in
boxes_list
)
# use torch.cat (v.s. layers.cat)
# so the returned boxes never share storage with input
cat_boxes
=
cls
(
torch
.
cat
([
b
.
tensor
for
b
in
boxes_list
],
dim
=
0
))
return
cat_boxes
def
to
(
self
,
device
):
original_type
=
type
(
self
)
return
original_type
(
self
.
tensor
.
to
(
device
))
def
clone
(
self
):
"""Clone the Boxes.
Returns:
Boxes
"""
original_type
=
type
(
self
)
return
original_type
(
self
.
tensor
.
clone
())
@
property
def
device
(
self
):
return
self
.
tensor
.
device
def
__iter__
(
self
):
"""
Yield a box as a Tensor of shape (4,) at a time.
"""
yield
from
self
.
tensor
mmdet3d/core/bbox/structures/box_3d_mode.py
0 → 100644
View file @
49121b64
from
enum
import
IntEnum
,
unique
import
numpy
as
np
import
torch
from
.base_box3d
import
BaseInstance3DBoxes
from
.cam_box3d
import
CameraInstance3DBoxes
from
.lidar_box3d
import
LiDARInstance3DBoxes
@
unique
class
Box3DMode
(
IntEnum
):
r
"""Enum of different ways to represent a box.
Coordinates in LiDAR:
.. code-block:: none
up z
^ x front
| /
| /
left y <------ 0
The relative coordinate of bottom center in a LiDAR box is [0.5, 0.5, 0],
and the yaw is around the z axis, thus the rotation axis=2.
Coordinates in camera:
.. code-block:: none
z front
/
/
0 ------> x right
|
|
v
down y
The relative coordinate of bottom center in a CAM box is [0.5, 1.0, 0.5],
and the yaw is around the y axis, thus the rotation axis=1.
Coordinates in Depth mode:
.. code-block:: none
up z
^ y front
| /
| /
0 ------> x right
The relative coordinate of bottom center in a DEPTH box is [0.5, 0.5, 0],
and the yaw is around the z axis, thus the rotation axis=2.
"""
LIDAR
=
0
CAM
=
1
DEPTH
=
2
@
staticmethod
def
convert
(
box
,
src
,
dst
,
rt_mat
=
None
):
"""Convert boxes from `src` mode to `dst` mode.
Args:
box (tuple | list | np.ndarray | torch.Tensor):
can be a k-tuple, k-list or an Nxk array/tensor, where k = 7
src (BoxMode): the src Box mode
dst (BoxMode): the target Box mode
rt_mat (np.ndarray | torch.Tensor): The rotation and translation
matrix between different coordinates. Defaults to None.
The conversion from `src` coordinates to `dst` coordinates
usually comes along the change of sensors, e.g., from camera
to LiDAR. This requires a transformation matrix.
Returns:
(tuple | list | np.ndarray | torch.Tensor):
The converted box of the same type.
"""
if
src
==
dst
:
return
box
is_numpy
=
isinstance
(
box
,
np
.
ndarray
)
is_Instance3DBoxes
=
isinstance
(
box
,
BaseInstance3DBoxes
)
single_box
=
isinstance
(
box
,
(
list
,
tuple
))
if
single_box
:
assert
len
(
box
)
>=
7
,
(
'BoxMode.convert takes either a k-tuple/list or '
'an Nxk array/tensor, where k >= 7'
)
arr
=
torch
.
tensor
(
box
)[
None
,
:]
else
:
# avoid modifying the input box
if
is_numpy
:
arr
=
torch
.
from_numpy
(
np
.
asarray
(
box
)).
clone
()
elif
is_Instance3DBoxes
:
arr
=
box
.
tensor
.
clone
()
else
:
arr
=
box
.
clone
()
# convert box from `src` mode to `dst` mode.
x_size
,
y_size
,
z_size
=
arr
[...,
3
:
4
],
arr
[...,
4
:
5
],
arr
[...,
5
:
6
]
if
src
==
Box3DMode
.
LIDAR
and
dst
==
Box3DMode
.
CAM
:
if
rt_mat
is
None
:
rt_mat
=
arr
.
new_tensor
([[
0
,
-
1
,
0
],
[
0
,
0
,
-
1
],
[
1
,
0
,
0
]])
xyz_size
=
torch
.
cat
([
y_size
,
z_size
,
x_size
],
dim
=-
1
)
elif
src
==
Box3DMode
.
CAM
and
dst
==
Box3DMode
.
LIDAR
:
if
rt_mat
is
None
:
rt_mat
=
arr
.
new_tensor
([[
0
,
0
,
1
],
[
-
1
,
0
,
0
],
[
0
,
-
1
,
0
]])
xyz_size
=
torch
.
cat
([
z_size
,
x_size
,
y_size
],
dim
=-
1
)
elif
src
==
Box3DMode
.
DEPTH
and
dst
==
Box3DMode
.
CAM
:
if
rt_mat
is
None
:
rt_mat
=
arr
.
new_tensor
([[
1
,
0
,
0
],
[
0
,
0
,
1
],
[
0
,
-
1
,
0
]])
xyz_size
=
torch
.
cat
([
x_size
,
z_size
,
y_size
],
dim
=-
1
)
elif
src
==
Box3DMode
.
CAM
and
dst
==
Box3DMode
.
DEPTH
:
if
rt_mat
is
None
:
rt_mat
=
arr
.
new_tensor
([[
1
,
0
,
0
],
[
0
,
0
,
-
1
],
[
0
,
1
,
0
]])
xyz_size
=
torch
.
cat
([
x_size
,
z_size
,
y_size
],
dim
=-
1
)
else
:
raise
NotImplementedError
(
f
'Conversion from Box3DMode
{
src
}
to
{
dst
}
'
'is not supported yet'
)
if
not
isinstance
(
rt_mat
,
torch
.
Tensor
):
rt_mat
=
arr
.
new_tensor
(
rt_mat
)
if
rt_mat
.
size
(
1
)
==
4
:
extended_xyz
=
torch
.
cat
(
[
arr
[:,
:
3
],
arr
.
new_ones
(
arr
.
size
(
0
),
1
)],
dim
=-
1
)
xyz
=
extended_xyz
@
rt_mat
.
t
()
else
:
xyz
=
arr
[:,
:
3
]
@
rt_mat
.
t
()
remains
=
arr
[...,
6
:]
arr
=
torch
.
cat
([
xyz
[:,
:
3
],
xyz_size
,
remains
],
dim
=-
1
)
# convert arr to the original type
original_type
=
type
(
box
)
if
single_box
:
return
original_type
(
arr
.
flatten
().
tolist
())
if
is_numpy
:
return
arr
.
numpy
()
elif
is_Instance3DBoxes
:
if
dst
==
Box3DMode
.
CAM
:
target_type
=
CameraInstance3DBoxes
elif
dst
==
Box3DMode
.
LIDAR
:
target_type
=
LiDARInstance3DBoxes
else
:
raise
NotImplementedError
(
f
'Conversion to
{
dst
}
through
{
original_type
}
'
' is not supported yet'
)
return
target_type
(
arr
,
box_dim
=
arr
.
size
(
-
1
))
else
:
return
arr
mmdet3d/core/bbox/structures/cam_box3d.py
0 → 100644
View file @
49121b64
import
numpy
as
np
import
torch
from
.base_box3d
import
BaseInstance3DBoxes
from
.utils
import
limit_period
,
rotation_3d_in_axis
class
CameraInstance3DBoxes
(
BaseInstance3DBoxes
):
"""3D boxes of instances in CAM coordinates
Coordinates in camera:
.. code-block:: none
z front
/
/
0 ------> x right
|
|
v
down y
The relative coordinate of bottom center in a CAM box is [0.5, 1.0, 0.5],
and the yaw is around the y axis, thus the rotation axis=1.
Attributes:
tensor (torch.Tensor): float matrix of N x box_dim.
box_dim (int): integer indicates the dimension of a box
Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).
"""
@
property
def
gravity_center
(
self
):
"""Calculate the gravity center of all the boxes.
Returns:
torch.Tensor: a tensor with center of each box.
"""
bottom_center
=
self
.
bottom_center
gravity_center
=
torch
.
zeros_like
(
bottom_center
)
gravity_center
[:,
[
0
,
2
]]
=
bottom_center
[:,
[
0
,
2
]]
gravity_center
[:,
1
]
=
bottom_center
[:,
1
]
-
self
.
tensor
[:,
4
]
*
0.5
return
gravity_center
@
property
def
corners
(
self
):
"""Calculate the coordinates of corners of all the boxes.
Convert the boxes to in clockwise order, in the form of
(x0y0z0, x0y0z1, x0y1z1, x0y1z0, x1y0z0, x1y0z1, x1y1z0, x1y1z1)
.. code-block:: none
front z
/
/
(x0, y0, z1) + ----------- + (x1, y0, z1)
/| / |
/ | / |
(x0, y0, z0) + ----------- + + (x1, y1, z0)
| / . | /
| / oriign | /
(x0, y1, z0) + ----------- + -------> x right
| (x1, y1, z0)
|
v
down y
Returns:
torch.Tensor: corners of each box with size (N, 8, 3)
"""
dims
=
self
.
dims
corners_norm
=
torch
.
from_numpy
(
np
.
stack
(
np
.
unravel_index
(
np
.
arange
(
8
),
[
2
]
*
3
),
axis
=
1
)).
to
(
device
=
dims
.
device
,
dtype
=
dims
.
dtype
)
corners_norm
=
corners_norm
[[
0
,
1
,
3
,
2
,
4
,
5
,
7
,
6
]]
# use relative origin [0.5, 1, 0.5]
corners_norm
=
corners_norm
-
dims
.
new_tensor
([
0.5
,
1
,
0.5
])
corners
=
dims
.
view
([
-
1
,
1
,
3
])
*
corners_norm
.
reshape
([
1
,
8
,
3
])
# rotate around y axis
corners
=
rotation_3d_in_axis
(
corners
,
self
.
tensor
[:,
6
],
axis
=
1
)
corners
+=
self
.
tensor
[:,
:
3
].
view
(
-
1
,
1
,
3
)
return
corners
@
property
def
nearset_bev
(
self
):
"""Calculate the 2D bounding boxes in BEV without rotation
Returns:
torch.Tensor: a tensor of 2D BEV box of each box.
"""
# Obtain BEV boxes with rotation in XZWHR format
bev_rotated_boxes
=
self
.
tensor
[:,
[
0
,
2
,
3
,
5
,
6
]]
# convert the rotation to a valid range
rotations
=
bev_rotated_boxes
[:,
-
1
]
normed_rotations
=
torch
.
abs
(
limit_period
(
rotations
,
0.5
,
np
.
pi
))
# find the center of boxes
conditions
=
(
normed_rotations
>
np
.
pi
/
4
)[...,
None
]
bboxes_xywh
=
torch
.
where
(
conditions
,
bev_rotated_boxes
[:,
[
0
,
1
,
3
,
2
]],
bev_rotated_boxes
[:,
:
4
])
centers
=
bboxes_xywh
[:,
:
2
]
dims
=
bboxes_xywh
[:,
2
:]
bev_boxes
=
torch
.
cat
([
centers
-
dims
/
2
,
centers
+
dims
/
2
],
dim
=-
1
)
return
bev_boxes
def
rotate
(
self
,
angle
):
"""Calculate whether the points is in any of the boxes
Args:
angles (float | torch.Tensor): rotation angle
Returns:
None if `return_rot_mat=False`,
torch.Tensor if `return_rot_mat=True`
"""
if
not
isinstance
(
angle
,
torch
.
Tensor
):
angle
=
self
.
tensor
.
new_tensor
(
angle
)
rot_sin
=
torch
.
sin
(
angle
)
rot_cos
=
torch
.
cos
(
angle
)
rot_mat_T
=
self
.
tensor
.
new_tensor
([[
rot_cos
,
0
,
-
rot_sin
],
[
0
,
1
,
0
],
[
rot_sin
,
0
,
rot_cos
]])
self
.
tensor
[:,
:
3
]
=
self
.
tensor
[:,
:
3
]
@
rot_mat_T
self
.
tensor
[:,
6
]
+=
angle
def
flip
(
self
):
"""Flip the boxes in horizontal direction
In CAM coordinates, it flips the x axis.
"""
self
.
tensor
[:,
0
::
7
]
=
-
self
.
tensor
[:,
0
::
7
]
self
.
tensor
[:,
6
]
=
-
self
.
tensor
[:,
6
]
+
np
.
pi
def
in_range_bev
(
self
,
box_range
):
"""Check whether the boxes are in the given range
Args:
box_range (list | torch.Tensor): the range of box
(x_min, z_min, x_max, z_max)
Note:
In the original implementation of SECOND, checking whether
a box in the range checks whether the points are in a convex
polygon, we try to reduce the burdun for simpler cases.
TODO: check whether this will effect the performance
Returns:
a binary vector, indicating whether each box is inside
the reference range.
"""
in_range_flags
=
((
self
.
tensor
[:,
0
]
>
box_range
[
0
])
&
(
self
.
tensor
[:,
2
]
>
box_range
[
1
])
&
(
self
.
tensor
[:,
0
]
<
box_range
[
2
])
&
(
self
.
tensor
[:,
2
]
<
box_range
[
3
]))
return
in_range_flags
mmdet3d/core/bbox/structures/lidar_box3d.py
0 → 100644
View file @
49121b64
import
numpy
as
np
import
torch
from
.base_box3d
import
BaseInstance3DBoxes
from
.utils
import
limit_period
,
rotation_3d_in_axis
class
LiDARInstance3DBoxes
(
BaseInstance3DBoxes
):
"""3D boxes of instances in LIDAR coordinates
Coordinates in LiDAR:
.. code-block:: none
up z x front
^ ^
| /
| /
left y <------ 0
The relative coordinate of bottom center in a LiDAR box is [0.5, 0.5, 0],
and the yaw is around the z axis, thus the rotation axis=2.
Attributes:
tensor (torch.Tensor): float matrix of N x box_dim.
box_dim (int): integer indicates the dimension of a box
Each row is (x, y, z, x_size, y_size, z_size, yaw, ...).
"""
@
property
def
gravity_center
(
self
):
"""Calculate the gravity center of all the boxes.
Returns:
torch.Tensor: a tensor with center of each box.
"""
bottom_center
=
self
.
bottom_center
gravity_center
=
torch
.
zeros_like
(
bottom_center
)
gravity_center
[:,
:
2
]
=
bottom_center
[:,
:
2
]
gravity_center
[:,
2
]
=
bottom_center
[:,
2
]
+
self
.
tensor
[:,
5
]
*
0.5
return
gravity_center
@
property
def
corners
(
self
):
"""Calculate the coordinates of corners of all the boxes.
Convert the boxes to corners in clockwise order, in form of
(x0y0z0, x0y0z1, x0y1z1, x0y1z0, x1y0z0, x1y0z1, x1y1z0, x1y1z1)
.. code-block:: none
up z
front x ^
/ |
/ |
(x1, y0, z1) + ----------- + (x1, y1, z1)
/| / |
/ | / |
(x0, y0, z1) + ----------- + + (x1, y1, z0)
| / . | /
| / oriign | /
left y<-------- + ----------- + (x0, y1, z0)
(x0, y0, z0)
Returns:
torch.Tensor: corners of each box with size (N, 8, 3)
"""
dims
=
self
.
dims
corners_norm
=
torch
.
from_numpy
(
np
.
stack
(
np
.
unravel_index
(
np
.
arange
(
8
),
[
2
]
*
3
),
axis
=
1
)).
to
(
device
=
dims
.
device
,
dtype
=
dims
.
dtype
)
corners_norm
=
corners_norm
[[
0
,
1
,
3
,
2
,
4
,
5
,
7
,
6
]]
# use relative origin [0.5, 0.5, 0]
corners_norm
=
corners_norm
-
dims
.
new_tensor
([
0.5
,
0.5
,
0
])
corners
=
dims
.
view
([
-
1
,
1
,
3
])
*
corners_norm
.
reshape
([
1
,
8
,
3
])
# rotate around z axis
corners
=
rotation_3d_in_axis
(
corners
,
self
.
tensor
[:,
6
],
axis
=
2
)
corners
+=
self
.
tensor
[:,
:
3
].
view
(
-
1
,
1
,
3
)
return
corners
@
property
def
nearset_bev
(
self
):
"""Calculate the 2D bounding boxes in BEV without rotation
Returns:
torch.Tensor: a tensor of 2D BEV box of each box.
"""
# Obtain BEV boxes with rotation in XYWHR format
bev_rotated_boxes
=
self
.
tensor
[:,
[
0
,
1
,
3
,
4
,
6
]]
# convert the rotation to a valid range
rotations
=
bev_rotated_boxes
[:,
-
1
]
normed_rotations
=
torch
.
abs
(
limit_period
(
rotations
,
0.5
,
np
.
pi
))
# find the center of boxes
conditions
=
(
normed_rotations
>
np
.
pi
/
4
)[...,
None
]
bboxes_xywh
=
torch
.
where
(
conditions
,
bev_rotated_boxes
[:,
[
0
,
1
,
3
,
2
]],
bev_rotated_boxes
[:,
:
4
])
centers
=
bboxes_xywh
[:,
:
2
]
dims
=
bboxes_xywh
[:,
2
:]
bev_boxes
=
torch
.
cat
([
centers
-
dims
/
2
,
centers
+
dims
/
2
],
dim
=-
1
)
return
bev_boxes
def
rotate
(
self
,
angle
):
"""Calculate whether the points is in any of the boxes
Args:
angles (float | torch.Tensor): rotation angle
Returns:
None if `return_rot_mat=False`,
torch.Tensor if `return_rot_mat=True`
"""
if
not
isinstance
(
angle
,
torch
.
Tensor
):
angle
=
self
.
tensor
.
new_tensor
(
angle
)
rot_sin
=
torch
.
sin
(
angle
)
rot_cos
=
torch
.
cos
(
angle
)
rot_mat_T
=
self
.
tensor
.
new_tensor
([[
rot_cos
,
-
rot_sin
,
0
],
[
rot_sin
,
rot_cos
,
0
],
[
0
,
0
,
1
]])
self
.
tensor
[:,
:
3
]
=
self
.
tensor
[:,
:
3
]
@
rot_mat_T
self
.
tensor
[:,
6
]
+=
angle
def
flip
(
self
):
"""Flip the boxes in horizontal direction
In LIDAR coordinates, it flips the y axis.
"""
self
.
tensor
[:,
1
::
7
]
=
-
self
.
tensor
[:,
1
::
7
]
self
.
tensor
[:,
6
]
=
-
self
.
tensor
[:,
6
]
+
np
.
pi
def
in_range_bev
(
self
,
box_range
):
"""Check whether the boxes are in the given range
Args:
box_range (list | torch.Tensor): the range of box
(x_min, y_min, x_max, y_max)
Note:
In the original implementation of SECOND, checking whether
a box in the range checks whether the points are in a convex
polygon, we try to reduce the burdun for simpler cases.
TODO: check whether this will effect the performance
Returns:
a binary vector, indicating whether each box is inside
the reference range.
"""
in_range_flags
=
((
self
.
tensor
[:,
0
]
>
box_range
[
0
])
&
(
self
.
tensor
[:,
1
]
>
box_range
[
1
])
&
(
self
.
tensor
[:,
0
]
<
box_range
[
2
])
&
(
self
.
tensor
[:,
1
]
<
box_range
[
3
]))
return
in_range_flags
mmdet3d/core/bbox/structures/utils.py
0 → 100644
View file @
49121b64
import
numpy
as
np
import
torch
def
limit_period
(
val
,
offset
=
0.5
,
period
=
np
.
pi
):
"""Limit the value into a period for periodic function.
Args:
val (torch.Tensor): The value to be converted
offset (float, optional): Offset to set the value range.
Defaults to 0.5.
period ([type], optional): Period of the value. Defaults to np.pi.
Returns:
torch.Tensor: value in the range of
[-offset * period, (1-offset) * period]
"""
return
val
-
torch
.
floor
(
val
/
period
+
offset
)
*
period
def
rotation_3d_in_axis
(
points
,
angles
,
axis
=
0
):
"""Rotate points by angles according to axis
Args:
points (torch.Tensor): Points of shape (N, M, 3).
angles (torch.Tensor): Vector of angles in shape (N,)
axis (int, optional): The axis to be rotated. Defaults to 0.
Raises:
ValueError: when the axis is not in range [0, 1, 2], it will
raise value error.
Returns:
torch.Tensor: rotated points in shape (N, M, 3)
"""
rot_sin
=
torch
.
sin
(
angles
)
rot_cos
=
torch
.
cos
(
angles
)
ones
=
torch
.
ones_like
(
rot_cos
)
zeros
=
torch
.
zeros_like
(
rot_cos
)
if
axis
==
1
:
rot_mat_T
=
torch
.
stack
([
torch
.
stack
([
rot_cos
,
zeros
,
-
rot_sin
]),
torch
.
stack
([
zeros
,
ones
,
zeros
]),
torch
.
stack
([
rot_sin
,
zeros
,
rot_cos
])
])
elif
axis
==
2
or
axis
==
-
1
:
rot_mat_T
=
torch
.
stack
([
torch
.
stack
([
rot_cos
,
-
rot_sin
,
zeros
]),
torch
.
stack
([
rot_sin
,
rot_cos
,
zeros
]),
torch
.
stack
([
zeros
,
zeros
,
ones
])
])
elif
axis
==
0
:
rot_mat_T
=
torch
.
stack
([
torch
.
stack
([
zeros
,
rot_cos
,
-
rot_sin
]),
torch
.
stack
([
zeros
,
rot_sin
,
rot_cos
]),
torch
.
stack
([
ones
,
zeros
,
zeros
])
])
else
:
raise
ValueError
(
f
'axis should in range [0, 1, 2], got
{
axis
}
'
)
return
torch
.
einsum
(
'aij,jka->aik'
,
(
points
,
rot_mat_T
))
mmdet3d/datasets/__init__.py
View file @
49121b64
...
...
@@ -5,14 +5,20 @@ from .kitti2d_dataset import Kitti2DDataset
from
.kitti_dataset
import
KittiDataset
from
.loader
import
DistributedGroupSampler
,
GroupSampler
,
build_dataloader
from
.nuscenes_dataset
import
NuScenesDataset
from
.pipelines
import
(
GlobalRotScale
,
ObjectNoise
,
ObjectRangeFilter
,
ObjectSample
,
PointShuffle
,
PointsRangeFilter
,
RandomFlip3D
)
from
.pipelines
import
(
GlobalRotScale
,
IndoorFlipData
,
IndoorGlobalRotScale
,
IndoorLoadAnnotations3D
,
IndoorLoadPointsFromFile
,
IndoorPointSample
,
IndoorPointsColorJitter
,
IndoorPointsColorNormalize
,
ObjectNoise
,
ObjectRangeFilter
,
ObjectSample
,
PointShuffle
,
PointsRangeFilter
,
RandomFlip3D
)
__all__
=
[
'KittiDataset'
,
'GroupSampler'
,
'DistributedGroupSampler'
,
'build_dataloader'
,
'RepeatFactorDataset'
,
'DATASETS'
,
'build_dataset'
,
'CocoDataset'
,
'Kitti2DDataset'
,
'NuScenesDataset'
,
'ObjectSample'
,
'RandomFlip3D'
,
'ObjectNoise'
,
'GlobalRotScale'
,
'PointShuffle'
,
'ObjectRangeFilter'
,
'PointsRangeFilter'
,
'Collect3D'
'ObjectRangeFilter'
,
'PointsRangeFilter'
,
'Collect3D'
,
'IndoorLoadPointsFromFile'
,
'IndoorPointsColorNormalize'
,
'IndoorPointSample'
,
'IndoorLoadAnnotations3D'
,
'IndoorPointsColorJitter'
,
'IndoorGlobalRotScale'
,
'IndoorFlipData'
]
mmdet3d/datasets/kitti_dataset.py
View file @
49121b64
...
...
@@ -184,6 +184,8 @@ class KittiDataset(torch_data.Dataset):
if
self
.
modality
[
'use_depth'
]
and
self
.
modality
[
'use_lidar'
]:
points
=
self
.
get_lidar_depth_reduced
(
sample_idx
)
elif
self
.
modality
[
'use_lidar'
]:
points
=
self
.
get_lidar
(
sample_idx
)
elif
self
.
modality
[
'use_lidar_reduced'
]:
points
=
self
.
get_lidar_reduced
(
sample_idx
)
elif
self
.
modality
[
'use_depth'
]:
points
=
self
.
get_pure_depth_reduced
(
sample_idx
)
...
...
mmdet3d/datasets/pipelines/__init__.py
View file @
49121b64
from
mmdet.datasets.pipelines
import
Compose
from
.dbsampler
import
DataBaseSampler
,
MMDataBaseSampler
from
.formating
import
DefaultFormatBundle
,
DefaultFormatBundle3D
from
.indoor_augment
import
(
IndoorFlipData
,
IndoorGlobalRotScale
,
IndoorPointsColorJitter
)
from
.indoor_loading
import
(
IndoorLoadAnnotations3D
,
IndoorLoadPointsFromFile
,
IndoorPointsColorNormalize
)
from
.indoor_sample
import
IndoorPointSample
from
.loading
import
LoadMultiViewImageFromFiles
,
LoadPointsFromFile
from
.train_aug
import
(
GlobalRotScale
,
ObjectNoise
,
ObjectRangeFilter
,
ObjectSample
,
PointShuffle
,
PointsRangeFilter
,
...
...
@@ -11,5 +16,8 @@ __all__ = [
'PointShuffle'
,
'ObjectRangeFilter'
,
'PointsRangeFilter'
,
'Collect3D'
,
'Compose'
,
'LoadMultiViewImageFromFiles'
,
'LoadPointsFromFile'
,
'DefaultFormatBundle'
,
'DefaultFormatBundle3D'
,
'DataBaseSampler'
,
'MMDataBaseSampler'
'IndoorGlobalRotScale'
,
'IndoorPointsColorJitter'
,
'IndoorFlipData'
,
'MMDataBaseSampler'
,
'IndoorLoadPointsFromFile'
,
'IndoorPointsColorNormalize'
,
'IndoorLoadAnnotations3D'
,
'IndoorPointSample'
]
mmdet3d/datasets/pipelines/data_augment_utils.py
View file @
49121b64
import
warnings
import
numba
import
numpy
as
np
from
numba.errors
import
NumbaPerformanceWarning
from
mmdet3d.core.bbox
import
box_np_ops
warnings
.
filterwarnings
(
"ignore"
,
category
=
NumbaPerformanceWarning
)
@
numba
.
njit
def
_rotation_box2d_jit_
(
corners
,
angle
,
rot_mat_T
):
...
...
Prev
1
2
3
Next
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