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
OpenPCDet
Commits
45ffca47
Commit
45ffca47
authored
Jul 02, 2020
by
Shaoshuai Shi
Browse files
support NuScenes dataset with training
parent
883fc156
Changes
5
Hide whitespace changes
Inline
Side-by-side
Showing
5 changed files
with
716 additions
and
1 deletion
+716
-1
pcdet/datasets/__init__.py
pcdet/datasets/__init__.py
+3
-1
pcdet/datasets/nuscenes/nuscenes_dataset.py
pcdet/datasets/nuscenes/nuscenes_dataset.py
+212
-0
pcdet/datasets/nuscenes/nuscenes_utils.py
pcdet/datasets/nuscenes/nuscenes_utils.py
+261
-0
tools/cfgs/dataset_configs/nuscenes_dataset.yaml
tools/cfgs/dataset_configs/nuscenes_dataset.yaml
+69
-0
tools/cfgs/nuscenes_models/second.yaml
tools/cfgs/nuscenes_models/second.yaml
+171
-0
No files found.
pcdet/datasets/__init__.py
View file @
45ffca47
...
@@ -2,14 +2,17 @@ import torch
...
@@ -2,14 +2,17 @@ import torch
from
torch.utils.data
import
DataLoader
from
torch.utils.data
import
DataLoader
from
.dataset
import
DatasetTemplate
from
.dataset
import
DatasetTemplate
from
.kitti.kitti_dataset
import
KittiDataset
from
.kitti.kitti_dataset
import
KittiDataset
from
.nuscenes.nuscenes_dataset
import
NuScenesDataset
from
torch.utils.data
import
DistributedSampler
as
_DistributedSampler
from
torch.utils.data
import
DistributedSampler
as
_DistributedSampler
from
pcdet.utils
import
common_utils
from
pcdet.utils
import
common_utils
__all__
=
{
__all__
=
{
'DatasetTemplate'
:
DatasetTemplate
,
'DatasetTemplate'
:
DatasetTemplate
,
'KittiDataset'
:
KittiDataset
,
'KittiDataset'
:
KittiDataset
,
'NuScenesDataset'
:
NuScenesDataset
}
}
class
DistributedSampler
(
_DistributedSampler
):
class
DistributedSampler
(
_DistributedSampler
):
def
__init__
(
self
,
dataset
,
num_replicas
=
None
,
rank
=
None
,
shuffle
=
True
):
def
__init__
(
self
,
dataset
,
num_replicas
=
None
,
rank
=
None
,
shuffle
=
True
):
...
@@ -33,7 +36,6 @@ class DistributedSampler(_DistributedSampler):
...
@@ -33,7 +36,6 @@ class DistributedSampler(_DistributedSampler):
return
iter
(
indices
)
return
iter
(
indices
)
def
build_dataloader
(
dataset_cfg
,
class_names
,
batch_size
,
dist
,
root_path
=
None
,
workers
=
4
,
def
build_dataloader
(
dataset_cfg
,
class_names
,
batch_size
,
dist
,
root_path
=
None
,
workers
=
4
,
logger
=
None
,
training
=
True
):
logger
=
None
,
training
=
True
):
...
...
pcdet/datasets/nuscenes/nuscenes_dataset.py
0 → 100644
View file @
45ffca47
import
pickle
import
copy
import
numpy
as
np
from
tqdm
import
tqdm
from
...utils
import
common_utils
from
..dataset
import
DatasetTemplate
from
...ops.roiaware_pool3d
import
roiaware_pool3d_utils
class
NuScenesDataset
(
DatasetTemplate
):
def
__init__
(
self
,
dataset_cfg
,
class_names
,
training
=
True
,
root_path
=
None
,
logger
=
None
):
root_path
=
(
root_path
if
root_path
is
not
None
else
Path
(
dataset_cfg
.
DATA_PATH
))
/
dataset_cfg
.
VERSION
super
().
__init__
(
dataset_cfg
=
dataset_cfg
,
class_names
=
class_names
,
training
=
training
,
root_path
=
root_path
,
logger
=
logger
)
self
.
infos
=
[]
self
.
include_nuscenes_data
(
self
.
mode
)
def
include_nuscenes_data
(
self
,
mode
):
self
.
logger
.
info
(
'Loading NuScenes dataset'
)
nuscenes_infos
=
[]
for
info_path
in
self
.
dataset_cfg
.
INFO_PATH
[
mode
]:
info_path
=
self
.
root_path
/
info_path
if
not
info_path
.
exists
():
continue
with
open
(
info_path
,
'rb'
)
as
f
:
infos
=
pickle
.
load
(
f
)
nuscenes_infos
.
extend
(
infos
)
self
.
infos
.
extend
(
nuscenes_infos
)
self
.
logger
.
info
(
'Total samples for NuScenes dataset: %d'
%
(
len
(
nuscenes_infos
)))
def
get_sweep
(
self
,
sweep_info
):
def
remove_ego_points
(
points
,
center_radius
=
1.0
):
mask
=
~
((
np
.
abs
(
points
[:,
0
])
<
center_radius
)
&
(
np
.
abs
(
points
[:,
1
])
<
center_radius
))
return
points
[
mask
]
lidar_path
=
self
.
root_path
/
sweep_info
[
'lidar_path'
]
points_sweep
=
np
.
fromfile
(
lidar_path
,
dtype
=
np
.
float32
,
count
=-
1
).
reshape
([
-
1
,
5
])[:,
:
4
]
points_sweep
=
remove_ego_points
(
points_sweep
).
T
if
sweep_info
[
'transform_matrix'
]
is
not
None
:
num_points
=
points_sweep
.
shape
[
1
]
points_sweep
[:
3
,
:]
=
sweep_info
[
'transform_matrix'
].
dot
(
np
.
vstack
((
points_sweep
[:
3
,
:],
np
.
ones
(
num_points
))))[:
3
,
:]
cur_times
=
sweep_info
[
'time_lag'
]
*
np
.
ones
((
1
,
points_sweep
.
shape
[
1
]))
return
points_sweep
.
T
,
cur_times
.
T
def
get_lidar_with_sweeps
(
self
,
index
,
max_sweeps
=
1
):
info
=
self
.
infos
[
index
]
lidar_path
=
self
.
root_path
/
info
[
'lidar_path'
]
points
=
np
.
fromfile
(
lidar_path
,
dtype
=
np
.
float32
,
count
=-
1
).
reshape
([
-
1
,
5
])[:,
:
4
]
sweep_points_list
=
[
points
]
sweep_times_list
=
[
np
.
zeros
((
points
.
shape
[
0
],
1
))]
for
k
in
np
.
random
.
choice
(
len
(
info
[
'sweeps'
]),
max_sweeps
-
1
,
replace
=
False
):
points_sweep
,
times_sweep
=
self
.
get_sweep
(
info
[
'sweeps'
][
k
])
sweep_points_list
.
append
(
points_sweep
)
sweep_times_list
.
append
(
times_sweep
)
points
=
np
.
concatenate
(
sweep_points_list
,
axis
=
0
)
times
=
np
.
concatenate
(
sweep_times_list
,
axis
=
0
).
astype
(
points
.
dtype
)
points
=
np
.
concatenate
((
points
,
times
),
axis
=
1
)
return
points
def
__len__
(
self
):
return
len
(
self
.
infos
)
def
__getitem__
(
self
,
index
):
info
=
copy
.
deepcopy
(
self
.
infos
[
index
])
points
=
self
.
get_lidar_with_sweeps
(
index
,
max_sweeps
=
self
.
dataset_cfg
.
MAX_SWEEPS
)
input_dict
=
{
'points'
:
points
,
'frame_id'
:
Path
(
info
[
'lidar_path'
]).
stem
,
}
if
'gt_boxes'
in
info
:
input_dict
.
update
({
'gt_names'
:
info
[
'gt_names'
],
'gt_boxes'
:
info
[
'gt_boxes'
]
})
data_dict
=
self
.
prepare_data
(
data_dict
=
input_dict
)
if
not
self
.
dataset_cfg
.
PRED_VELOCITY
and
'gt_boxes'
in
data_dict
:
data_dict
[
'gt_boxes'
]
=
data_dict
[
'gt_boxes'
][:,
[
0
,
1
,
2
,
3
,
4
,
5
,
6
,
-
1
]]
return
data_dict
def
create_groundtruth_database
(
self
,
used_classes
=
None
,
max_sweeps
=
10
):
import
torch
database_save_path
=
self
.
root_path
/
f
'gt_database_
{
max_sweeps
}
sweeps_withvelo'
db_info_save_path
=
self
.
root_path
/
f
'nuscenes_dbinfos_
{
max_sweeps
}
sweeps_withvelo.pkl'
database_save_path
.
mkdir
(
parents
=
True
,
exist_ok
=
True
)
all_db_infos
=
{}
for
idx
in
tqdm
(
range
(
len
(
self
.
infos
))):
sample_idx
=
idx
info
=
self
.
infos
[
idx
]
points
=
self
.
get_lidar_with_sweeps
(
idx
,
max_sweeps
=
max_sweeps
)
gt_boxes
=
info
[
'gt_boxes'
]
gt_names
=
info
[
'gt_names'
]
point_indices
=
roiaware_pool3d_utils
.
points_in_boxes_cpu
(
torch
.
from_numpy
(
points
[:,
0
:
3
]),
torch
.
from_numpy
(
gt_boxes
[:,
0
:
7
])
).
numpy
()
# (nboxes, npoints)
for
i
in
range
(
gt_boxes
.
shape
[
0
]):
filename
=
'%s_%s_%d.bin'
%
(
sample_idx
,
gt_names
[
i
],
i
)
filepath
=
database_save_path
/
filename
gt_points
=
points
[
point_indices
[
i
]
>
0
]
gt_points
[:,
:
3
]
-=
gt_boxes
[
i
,
:
3
]
with
open
(
filepath
,
'w'
)
as
f
:
gt_points
.
tofile
(
f
)
if
(
used_classes
is
None
)
or
gt_names
[
i
]
in
used_classes
:
db_path
=
str
(
filepath
.
relative_to
(
self
.
root_path
))
# gt_database/xxxxx.bin
db_info
=
{
'name'
:
gt_names
[
i
],
'path'
:
db_path
,
'image_idx'
:
sample_idx
,
'gt_idx'
:
i
,
'box3d_lidar'
:
gt_boxes
[
i
],
'num_points_in_gt'
:
gt_points
.
shape
[
0
]}
if
gt_names
[
i
]
in
all_db_infos
:
all_db_infos
[
gt_names
[
i
]].
append
(
db_info
)
else
:
all_db_infos
[
gt_names
[
i
]]
=
[
db_info
]
for
k
,
v
in
all_db_infos
.
items
():
print
(
'Database %s: %d'
%
(
k
,
len
(
v
)))
with
open
(
db_info_save_path
,
'wb'
)
as
f
:
pickle
.
dump
(
all_db_infos
,
f
)
def
create_nuscenes_info
(
version
,
data_path
,
save_path
,
max_sweeps
=
10
):
from
nuscenes.nuscenes
import
NuScenes
from
nuscenes.utils
import
splits
from
.
import
nuscenes_utils
data_path
=
data_path
/
version
save_path
=
save_path
/
version
assert
version
in
[
'v1.0-trainval'
,
'v1.0-test'
,
'v1.0-mini'
]
if
version
==
'v1.0-trainval'
:
train_scenes
=
splits
.
train
val_scenes
=
splits
.
val
elif
version
==
'v1.0-test'
:
train_scenes
=
splits
.
test
val_scenes
=
[]
elif
version
==
'v1.0-mini'
:
train_scenes
=
splits
.
mini_train
val_scenes
=
splits
.
mini_val
else
:
raise
NotImplementedError
nusc
=
NuScenes
(
version
=
version
,
dataroot
=
data_path
,
verbose
=
True
)
available_scenes
=
nuscenes_utils
.
get_available_scenes
(
nusc
)
available_scene_names
=
[
s
[
'name'
]
for
s
in
available_scenes
]
train_scenes
=
list
(
filter
(
lambda
x
:
x
in
available_scene_names
,
train_scenes
))
val_scenes
=
list
(
filter
(
lambda
x
:
x
in
available_scene_names
,
val_scenes
))
train_scenes
=
set
([
available_scenes
[
available_scene_names
.
index
(
s
)][
'token'
]
for
s
in
train_scenes
])
val_scenes
=
set
([
available_scenes
[
available_scene_names
.
index
(
s
)][
'token'
]
for
s
in
val_scenes
])
print
(
'%s: train scene(%d), val scene(%d)'
%
(
version
,
len
(
train_scenes
),
len
(
val_scenes
)))
train_nusc_infos
,
val_nusc_infos
=
nuscenes_utils
.
fill_trainval_infos
(
data_path
=
data_path
,
nusc
=
nusc
,
train_scenes
=
train_scenes
,
val_scenes
=
val_scenes
,
test
=
'test'
in
version
,
max_sweeps
=
max_sweeps
)
if
version
==
'v1.0-test'
:
print
(
'test sample: %d'
%
len
(
train_nusc_infos
))
with
open
(
save_path
/
f
'nuscenes_infos_
{
max_sweeps
}
sweeps_test.pkl'
,
'wb'
)
as
f
:
pickle
.
dump
(
train_nusc_infos
,
f
)
else
:
print
(
'train sample: %d, val sample: %d'
%
(
len
(
train_nusc_infos
),
len
(
val_nusc_infos
)))
with
open
(
save_path
/
f
'nuscenes_infos_
{
max_sweeps
}
sweeps_train.pkl'
,
'wb'
)
as
f
:
pickle
.
dump
(
train_nusc_infos
,
f
)
with
open
(
save_path
/
f
'nuscenes_infos_
{
max_sweeps
}
sweeps_val.pkl'
,
'wb'
)
as
f
:
pickle
.
dump
(
val_nusc_infos
,
f
)
if
__name__
==
'__main__'
:
import
yaml
import
argparse
from
pathlib
import
Path
from
easydict
import
EasyDict
parser
=
argparse
.
ArgumentParser
(
description
=
'arg parser'
)
parser
.
add_argument
(
'--cfg_file'
,
type
=
str
,
default
=
None
,
help
=
'specify the config of dataset'
)
parser
.
add_argument
(
'--func'
,
type
=
str
,
default
=
'create_nuscenes_infos'
,
help
=
''
)
args
=
parser
.
parse_args
()
if
args
.
func
==
'create_nuscenes_infos'
:
dataset_cfg
=
EasyDict
(
yaml
.
load
(
open
(
args
.
cfg_file
)))
ROOT_DIR
=
(
Path
(
__file__
).
resolve
().
parent
/
'../../../'
).
resolve
()
create_nuscenes_info
(
version
=
dataset_cfg
.
VERSION
,
data_path
=
ROOT_DIR
/
'data'
/
'nuscenes'
,
save_path
=
ROOT_DIR
/
'data'
/
'nuscenes'
,
max_sweeps
=
dataset_cfg
.
MAX_SWEEPS
,
)
nuscenes_dataset
=
NuScenesDataset
(
dataset_cfg
=
dataset_cfg
,
class_names
=
None
,
root_path
=
ROOT_DIR
/
'data'
/
'nuscenes'
,
logger
=
common_utils
.
create_logger
()
)
nuscenes_dataset
.
create_groundtruth_database
(
max_sweeps
=
dataset_cfg
.
MAX_SWEEPS
)
pcdet/datasets/nuscenes/nuscenes_utils.py
0 → 100644
View file @
45ffca47
"""
The NuScenes data pre-processing is borrowed from
https://github.com/traveller59/second.pytorch and https://github.com/poodarchu/Det3D
"""
from
pathlib
import
Path
import
tqdm
import
numpy
as
np
from
functools
import
reduce
from
nuscenes.utils.geometry_utils
import
transform_matrix
from
pyquaternion
import
Quaternion
map_name_from_general_to_detection
=
{
'human.pedestrian.adult'
:
'pedestrian'
,
'human.pedestrian.child'
:
'pedestrian'
,
'human.pedestrian.wheelchair'
:
'ignore'
,
'human.pedestrian.stroller'
:
'ignore'
,
'human.pedestrian.personal_mobility'
:
'ignore'
,
'human.pedestrian.police_officer'
:
'pedestrian'
,
'human.pedestrian.construction_worker'
:
'pedestrian'
,
'animal'
:
'ignore'
,
'vehicle.car'
:
'car'
,
'vehicle.motorcycle'
:
'motorcycle'
,
'vehicle.bicycle'
:
'bicycle'
,
'vehicle.bus.bendy'
:
'bus'
,
'vehicle.bus.rigid'
:
'bus'
,
'vehicle.truck'
:
'truck'
,
'vehicle.construction'
:
'construction_vehicle'
,
'vehicle.emergency.ambulance'
:
'ignore'
,
'vehicle.emergency.police'
:
'ignore'
,
'vehicle.trailer'
:
'trailer'
,
'movable_object.barrier'
:
'barrier'
,
'movable_object.trafficcone'
:
'traffic_cone'
,
'movable_object.pushable_pullable'
:
'ignore'
,
'movable_object.debris'
:
'ignore'
,
'static_object.bicycle_rack'
:
'ignore'
,
}
def
get_available_scenes
(
nusc
):
available_scenes
=
[]
print
(
'total scene num:'
,
len
(
nusc
.
scene
))
for
scene
in
nusc
.
scene
:
scene_token
=
scene
[
'token'
]
scene_rec
=
nusc
.
get
(
'scene'
,
scene_token
)
sample_rec
=
nusc
.
get
(
'sample'
,
scene_rec
[
'first_sample_token'
])
sd_rec
=
nusc
.
get
(
'sample_data'
,
sample_rec
[
'data'
][
'LIDAR_TOP'
])
has_more_frames
=
True
scene_not_exist
=
False
while
has_more_frames
:
lidar_path
,
boxes
,
_
=
nusc
.
get_sample_data
(
sd_rec
[
'token'
])
if
not
Path
(
lidar_path
).
exists
():
scene_not_exist
=
True
break
else
:
break
# if not sd_rec['next'] == '':
# sd_rec = nusc.get('sample_data', sd_rec['next'])
# else:
# has_more_frames = False
if
scene_not_exist
:
continue
available_scenes
.
append
(
scene
)
print
(
'exist scene num:'
,
len
(
available_scenes
))
return
available_scenes
def
get_sample_data
(
nusc
,
sample_data_token
,
selected_anntokens
=
None
):
"""
Returns the data path as well as all annotations related to that sample_data.
Note that the boxes are transformed into the current sensor's coordinate frame.
Args:
nusc:
sample_data_token: Sample_data token.
selected_anntokens: If provided only return the selected annotation.
Returns:
"""
# Retrieve sensor & pose records
sd_record
=
nusc
.
get
(
'sample_data'
,
sample_data_token
)
cs_record
=
nusc
.
get
(
'calibrated_sensor'
,
sd_record
[
'calibrated_sensor_token'
])
sensor_record
=
nusc
.
get
(
'sensor'
,
cs_record
[
'sensor_token'
])
pose_record
=
nusc
.
get
(
'ego_pose'
,
sd_record
[
'ego_pose_token'
])
data_path
=
nusc
.
get_sample_data_path
(
sample_data_token
)
if
sensor_record
[
'modality'
]
==
'camera'
:
cam_intrinsic
=
np
.
array
(
cs_record
[
'camera_intrinsic'
])
imsize
=
(
sd_record
[
'width'
],
sd_record
[
'height'
])
else
:
cam_intrinsic
=
None
imsize
=
None
# Retrieve all sample annotations and map to sensor coordinate system.
if
selected_anntokens
is
not
None
:
boxes
=
list
(
map
(
nusc
.
get_box
,
selected_anntokens
))
else
:
boxes
=
nusc
.
get_boxes
(
sample_data_token
)
# Make list of Box objects including coord system transforms.
box_list
=
[]
for
box
in
boxes
:
# Move box to ego vehicle coord system
box
.
translate
(
-
np
.
array
(
pose_record
[
'translation'
]))
box
.
rotate
(
Quaternion
(
pose_record
[
'rotation'
]).
inverse
)
# Move box to sensor coord system
box
.
translate
(
-
np
.
array
(
cs_record
[
'translation'
]))
box
.
rotate
(
Quaternion
(
cs_record
[
'rotation'
]).
inverse
)
box_list
.
append
(
box
)
return
data_path
,
box_list
,
cam_intrinsic
def
quaternion_yaw
(
q
:
Quaternion
)
->
float
:
"""
Calculate the yaw angle from a quaternion.
Note that this only works for a quaternion that represents a box in lidar or global coordinate frame.
It does not work for a box in the camera frame.
:param q: Quaternion of interest.
:return: Yaw angle in radians.
"""
# Project into xy plane.
v
=
np
.
dot
(
q
.
rotation_matrix
,
np
.
array
([
1
,
0
,
0
]))
# Measure yaw using arctan.
yaw
=
np
.
arctan2
(
v
[
1
],
v
[
0
])
return
yaw
def
fill_trainval_infos
(
data_path
,
nusc
,
train_scenes
,
val_scenes
,
test
=
False
,
max_sweeps
=
10
):
train_nusc_infos
=
[]
val_nusc_infos
=
[]
progress_bar
=
tqdm
.
tqdm
(
total
=
len
(
nusc
.
sample
),
desc
=
'create_info'
,
dynamic_ncols
=
True
)
ref_chan
=
'LIDAR_TOP'
# The radar channel from which we track back n sweeps to aggregate the point cloud.
chan
=
'LIDAR_TOP'
# The reference channel of the current sample_rec that the point clouds are mapped to.
for
index
,
sample
in
enumerate
(
nusc
.
sample
):
progress_bar
.
update
()
ref_sd_token
=
sample
[
'data'
][
ref_chan
]
ref_sd_rec
=
nusc
.
get
(
'sample_data'
,
ref_sd_token
)
ref_cs_rec
=
nusc
.
get
(
'calibrated_sensor'
,
ref_sd_rec
[
'calibrated_sensor_token'
])
ref_pose_rec
=
nusc
.
get
(
'ego_pose'
,
ref_sd_rec
[
'ego_pose_token'
])
ref_time
=
1e-6
*
ref_sd_rec
[
'timestamp'
]
ref_lidar_path
,
ref_boxes
,
_
=
get_sample_data
(
nusc
,
ref_sd_token
)
ref_cam_front_token
=
sample
[
'data'
][
'CAM_FRONT'
]
ref_cam_path
,
_
,
ref_cam_intrinsic
=
nusc
.
get_sample_data
(
ref_cam_front_token
)
# Homogeneous transform from ego car frame to reference frame
ref_from_car
=
transform_matrix
(
ref_cs_rec
[
'translation'
],
Quaternion
(
ref_cs_rec
[
'rotation'
]),
inverse
=
True
)
# Homogeneous transformation matrix from global to _current_ ego car frame
car_from_global
=
transform_matrix
(
ref_pose_rec
[
'translation'
],
Quaternion
(
ref_pose_rec
[
'rotation'
]),
inverse
=
True
,
)
info
=
{
'lidar_path'
:
Path
(
ref_lidar_path
).
relative_to
(
data_path
).
__str__
(),
'cam_front_path'
:
Path
(
ref_cam_path
).
relative_to
(
data_path
).
__str__
(),
'cam_intrinsic'
:
ref_cam_intrinsic
,
'token'
:
sample
[
'token'
],
'sweeps'
:
[],
'ref_from_car'
:
ref_from_car
,
'car_from_global'
:
car_from_global
,
'timestamp'
:
ref_time
,
}
sample_data_token
=
sample
[
'data'
][
chan
]
curr_sd_rec
=
nusc
.
get
(
'sample_data'
,
sample_data_token
)
sweeps
=
[]
while
len
(
sweeps
)
<
max_sweeps
-
1
:
if
curr_sd_rec
[
'prev'
]
==
''
:
if
len
(
sweeps
)
==
0
:
sweep
=
{
'lidar_path'
:
ref_lidar_path
,
'sample_data_token'
:
curr_sd_rec
[
'token'
],
'transform_matrix'
:
None
,
'time_lag'
:
curr_sd_rec
[
'timestamp'
]
*
0
,
}
sweeps
.
append
(
sweep
)
else
:
sweeps
.
append
(
sweeps
[
-
1
])
else
:
curr_sd_rec
=
nusc
.
get
(
'sample_data'
,
curr_sd_rec
[
'prev'
])
# Get past pose
current_pose_rec
=
nusc
.
get
(
'ego_pose'
,
curr_sd_rec
[
'ego_pose_token'
])
global_from_car
=
transform_matrix
(
current_pose_rec
[
'translation'
],
Quaternion
(
current_pose_rec
[
'rotation'
]),
inverse
=
False
,
)
# Homogeneous transformation matrix from sensor coordinate frame to ego car frame.
current_cs_rec
=
nusc
.
get
(
'calibrated_sensor'
,
curr_sd_rec
[
'calibrated_sensor_token'
]
)
car_from_current
=
transform_matrix
(
current_cs_rec
[
'translation'
],
Quaternion
(
current_cs_rec
[
'rotation'
]),
inverse
=
False
,
)
tm
=
reduce
(
np
.
dot
,
[
ref_from_car
,
car_from_global
,
global_from_car
,
car_from_current
])
lidar_path
=
nusc
.
get_sample_data_path
(
curr_sd_rec
[
'token'
])
time_lag
=
ref_time
-
1e-6
*
curr_sd_rec
[
'timestamp'
]
sweep
=
{
'lidar_path'
:
Path
(
lidar_path
).
relative_to
(
data_path
).
__str__
(),
'sample_data_token'
:
curr_sd_rec
[
'token'
],
'transform_matrix'
:
tm
,
'global_from_car'
:
global_from_car
,
'car_from_current'
:
car_from_current
,
'time_lag'
:
time_lag
,
}
sweeps
.
append
(
sweep
)
info
[
'sweeps'
]
=
sweeps
assert
len
(
info
[
'sweeps'
])
==
max_sweeps
-
1
,
\
f
"sweep
{
curr_sd_rec
[
'token'
]
}
only has
{
len
(
info
[
'sweeps'
])
}
sweeps, "
\
f
"you should duplicate to sweep num
{
max_sweeps
-
1
}
"
if
not
test
:
annotations
=
[
nusc
.
get
(
'sample_annotation'
,
token
)
for
token
in
sample
[
'anns'
]]
# the filtering gives 0.5~1 map improvement
mask
=
np
.
array
([(
anno
[
'num_lidar_pts'
]
+
anno
[
'num_radar_pts'
])
>
0
for
anno
in
annotations
],
dtype
=
bool
).
reshape
(
-
1
)
locs
=
np
.
array
([
b
.
center
for
b
in
ref_boxes
]).
reshape
(
-
1
,
3
)
dims
=
np
.
array
([
b
.
wlh
for
b
in
ref_boxes
]).
reshape
(
-
1
,
3
)[:,
[
1
,
0
,
2
]]
# wlh == > dxdydz (lwh)
velocity
=
np
.
array
([
b
.
velocity
for
b
in
ref_boxes
]).
reshape
(
-
1
,
3
)
rots
=
np
.
array
([
quaternion_yaw
(
b
.
orientation
)
for
b
in
ref_boxes
]).
reshape
(
-
1
,
1
)
names
=
np
.
array
([
b
.
name
for
b
in
ref_boxes
])
tokens
=
np
.
array
([
b
.
token
for
b
in
ref_boxes
])
gt_boxes
=
np
.
concatenate
([
locs
,
dims
,
rots
,
velocity
[:,
:
2
]],
axis
=
1
)
assert
len
(
annotations
)
==
len
(
gt_boxes
)
==
len
(
velocity
)
info
[
'gt_boxes'
]
=
gt_boxes
[
mask
,
:]
info
[
'gt_boxes_velocity'
]
=
velocity
[
mask
,
:]
info
[
'gt_names'
]
=
np
.
array
([
map_name_from_general_to_detection
[
name
]
for
name
in
names
])[
mask
]
info
[
'gt_boxes_token'
]
=
tokens
[
mask
]
if
sample
[
'scene_token'
]
in
train_scenes
:
train_nusc_infos
.
append
(
info
)
else
:
val_nusc_infos
.
append
(
info
)
progress_bar
.
close
()
return
train_nusc_infos
,
val_nusc_infos
tools/cfgs/dataset_configs/nuscenes_dataset.yaml
0 → 100644
View file @
45ffca47
DATASET
:
'
NuScenesDataset'
DATA_PATH
:
'
../data/nuscenes'
VERSION
:
'
v1.0-mini'
MAX_SWEEPS
:
10
PRED_VELOCITY
:
False
INFO_PATH
:
{
'
train'
:
[
nuscenes_infos_10sweeps_train.pkl
],
'
test'
:
[
nuscenes_infos_10sweeps_train.pkl
],
}
POINT_CLOUD_RANGE
:
[
-51.2
,
-51.2
,
-5.0
,
51.2
,
51.2
,
3.0
]
DATA_AUGMENTOR
:
-
NAME
:
gt_sampling
DB_INFO_PATH
:
-
nuscenes_dbinfos_10sweeps_withvelo.pkl
PREPARE
:
{
filter_by_min_points
:
[
'
car:5'
,
'
truck:5'
,
'
construction_vehicle:5'
,
'
bus:5'
,
'
trailer:5'
,
'
barrier:5'
,
'
motorcycle:5'
,
'
bicycle:5'
,
'
pedestrian:5'
,
'
traffic_cone:5'
],
}
SAMPLE_GROUPS
:
[
'
car:2'
,
'
truck:3'
,
'
construction_vehicle:7'
,
'
bus:4'
,
'
trailer:6'
,
'
barrier:2'
,
'
motorcycle:6'
,
'
bicycle:6'
,
'
pedestrian:2'
,
'
traffic_cone:2'
]
NUM_POINT_FEATURES
:
5
DATABASE_WITH_FAKELIDAR
:
False
REMOVE_EXTRA_WIDTH
:
[
0.0
,
0.0
,
0.0
]
LIMIT_WHOLE_SCENE
:
True
-
NAME
:
random_world_flip
ALONG_AXIS_LIST
:
[
'
x'
,
'
y'
]
-
NAME
:
random_world_rotation
WORLD_ROT_ANGLE
:
[
-0.3925
,
0.3925
]
-
NAME
:
random_world_scaling
WORLD_SCALE_RANGE
:
[
0.95
,
1.05
]
POINT_FEATURE_ENCODING
:
{
encoding_type
:
absolute_coordinates_encoding
,
used_feature_list
:
[
'
x'
,
'
y'
,
'
z'
,
'
intensity'
,
'
timestamp'
],
src_feature_list
:
[
'
x'
,
'
y'
,
'
z'
,
'
intensity'
,
'
timestamp'
],
}
DATA_PROCESSOR
:
-
NAME
:
mask_points_and_boxes_outside_range
REMOVE_OUTSIDE_BOXES
:
True
-
NAME
:
shuffle_points
SHUFFLE_ENABLED
:
{
'
train'
:
True
,
'
test'
:
True
}
-
NAME
:
transform_points_to_voxels
VOXEL_SIZE
:
[
0.1
,
0.1
,
0.2
]
MAX_POINTS_PER_VOXEL
:
10
MAX_NUMBER_OF_VOXELS
:
{
'
train'
:
60000
,
'
test'
:
60000
}
tools/cfgs/nuscenes_models/second.yaml
0 → 100644
View file @
45ffca47
CLASS_NAMES
:
[
'
car'
,
'
truck'
,
'
construction_vehicle'
,
'
bus'
,
'
trailer'
,
'
barrier'
,
'
motorcycle'
,
'
bicycle'
,
'
pedestrian'
,
'
traffic_cone'
]
DATA_CONFIG
:
_BASE_CONFIG_
:
cfgs/dataset_configs/nuscenes_dataset.yaml
MODEL
:
NAME
:
SECONDNet
VFE
:
NAME
:
MeanVFE
BACKBONE_3D
:
NAME
:
VoxelBackBone8x
MAP_TO_BEV
:
NAME
:
HeightCompression
NUM_BEV_FEATURES
:
256
BACKBONE_2D
:
NAME
:
BaseBEVBackbone
LAYER_NUMS
:
[
5
,
5
]
LAYER_STRIDES
:
[
1
,
2
]
NUM_FILTERS
:
[
128
,
256
]
UPSAMPLE_STRIDES
:
[
1
,
2
]
NUM_UPSAMPLE_FILTERS
:
[
256
,
256
]
DENSE_HEAD
:
NAME
:
AnchorHeadSingle
CLASS_AGNOSTIC
:
False
USE_DIRECTION_CLASSIFIER
:
True
DIR_OFFSET
:
0.78539
DIR_LIMIT_OFFSET
:
0.0
NUM_DIR_BINS
:
2
ANCHOR_GENERATOR_CONFIG
:
[
{
'
anchor_sizes'
:
[[
4.63
,
1.97
,
1.74
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-0.95
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
car
},
{
'
anchor_sizes'
:
[[
6.93
,
2.51
,
2.84
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-0.6
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
truck
},
{
'
anchor_sizes'
:
[[
6.37
,
2.85
,
3.19
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-0.225
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
construction_vehicle
},
{
'
anchor_sizes'
:
[[
10.5
,
2.94
,
3.47
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-0.085
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
bus
},
{
'
anchor_sizes'
:
[[
12.29
,
2.90
,
3.87
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
0.115
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
trailer
},
{
'
anchor_sizes'
:
[[
0.50
,
2.53
,
0.98
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-1.33
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
barrier
},
{
'
anchor_sizes'
:
[[
2.11
,
0.77
,
1.47
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-1.085
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
motorcycle
},
{
'
anchor_sizes'
:
[[
1.70
,
0.60
,
1.28
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-1.18
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
bicycle
},
{
'
anchor_sizes'
:
[[
0.73
,
0.67
,
1.77
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-0.935
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
pedestrian
},
{
'
anchor_sizes'
:
[[
0.41
,
0.41
,
1.07
]],
'
anchor_rotations'
:
[
0
,
1.57
],
'
anchor_bottom_heights'
:
[
-1.285
],
'
align_center'
:
False
,
'
feature_map_stride'
:
8
,
'
class_name'
:
traffic_cone
},
]
TARGET_ASSIGNER_CONFIG
:
NAME
:
AxisAlignedTargetAssigner
POS_FRACTION
:
-1.0
SAMPLE_SIZE
:
512
MATCHED_THRESHOLDS
:
[
0.6
,
0.55
,
0.5
,
0.55
,
0.5
,
0.55
,
0.5
,
0.5
,
0.6
,
0.6
]
UNMATCHED_THRESHOLDS
:
[
0.45
,
0.4
,
0.35
,
0.4
,
0.35
,
0.4
,
0.3
,
0.35
,
0.4
,
0.4
]
NORM_BY_NUM_EXAMPLES
:
False
MATCH_HEIGHT
:
False
BOX_CODER
:
ResidualCoder
LOSS_CONFIG
:
LOSS_WEIGHTS
:
{
'
cls_weight'
:
1.0
,
'
loc_weight'
:
2.0
,
'
dir_weight'
:
0.2
,
'
code_weights'
:
[
1.0
,
1.0
,
1.0
,
1.0
,
1.0
,
1.0
,
1.0
]
}
POST_PROCESSING
:
RECALL_THRESH_LIST
:
[
0.3
,
0.5
,
0.7
]
SCORE_THRESH
:
0.1
OUTPUT_RAW_SCORE
:
False
EVAL_METRIC
:
kitti
NMS_CONFIG
:
MULTI_CLASSES_NMS
:
False
NMS_TYPE
:
nms_gpu
NMS_THRESH
:
0.01
NMS_PRE_MAXSIZE
:
4096
NMS_POST_MAXSIZE
:
500
OPTIMIZATION
:
OPTIMIZER
:
adam_onecycle
LR
:
0.003
WEIGHT_DECAY
:
0.01
MOMENTUM
:
0.9
MOMS
:
[
0.95
,
0.85
]
PCT_START
:
0.4
DIV_FACTOR
:
10
DECAY_STEP_LIST
:
[
35
,
45
]
LR_DECAY
:
0.1
LR_CLIP
:
0.0000001
LR_WARMUP
:
False
WARMUP_EPOCH
:
1
GRAD_NORM_CLIP
:
10
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