-
Notifications
You must be signed in to change notification settings - Fork 267
/
bevdet-stbase-4d-stereo-512x1408-cbgs.py
323 lines (302 loc) · 9.68 KB
/
bevdet-stbase-4d-stereo-512x1408-cbgs.py
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
# Copyright (c) Phigent Robotics. All rights reserved.
# align_after_view_transfromation=False
# mAP: 0.4722
# mATE: 0.5103
# mASE: 0.2599
# mAOE: 0.3332
# mAVE: 0.3119
# mAAE: 0.1880
# NDS: 0.5758
# Per-class results:
# AP ATE ASE AOE AVE AAE Object Class
# 0.652 0.372 0.148 0.074 0.281 0.202 car
# 0.372 0.563 0.192 0.074 0.291 0.195 truck
# 0.513 0.566 0.187 0.053 0.589 0.254 bus
# 0.240 0.844 0.229 0.334 0.312 0.125 trailer
# 0.145 0.851 0.437 0.979 0.111 0.362 construction_vehicle
# 0.560 0.495 0.292 0.592 0.358 0.182 pedestrian
# 0.487 0.429 0.253 0.325 0.413 0.180 motorcycle
# 0.459 0.370 0.269 0.481 0.141 0.003 bicycle
# 0.663 0.302 0.312 1.000 1.000 1.000 traffic_cone
# 0.629 0.310 0.279 0.086 1.000 1.000 barrier
_base_ = ['../_base_/datasets/nus-3d.py', '../_base_/default_runtime.py']
# Global
# If point cloud range is changed, the models should also change their point
# cloud range accordingly
point_cloud_range = [-51.2, -51.2, -5.0, 51.2, 51.2, 3.0]
# For nuScenes we usually do 10-class detection
class_names = [
'car', 'truck', 'construction_vehicle', 'bus', 'trailer', 'barrier',
'motorcycle', 'bicycle', 'pedestrian', 'traffic_cone'
]
data_config = {
'cams': [
'CAM_FRONT_LEFT', 'CAM_FRONT', 'CAM_FRONT_RIGHT', 'CAM_BACK_LEFT',
'CAM_BACK', 'CAM_BACK_RIGHT'
],
'Ncams':
6,
'input_size': (512, 1408),
'src_size': (900, 1600),
# Augmentation
'resize': (-0.06, 0.11),
'rot': (-5.4, 5.4),
'flip': True,
'crop_h': (0.0, 0.0),
'resize_test': -0.00,
}
# Model
grid_config = {
'x': [-51.2, 51.2, 0.4],
'y': [-51.2, 51.2, 0.4],
'z': [-5, 3, 8],
'depth': [1.0, 60.0, 0.5],
}
voxel_size = [0.1, 0.1, 0.2]
numC_Trans = 80
multi_adj_frame_id_cfg = (1, 1+1, 1)
model = dict(
type='BEVStereo4D',
align_after_view_transfromation=False,
num_adj=len(range(*multi_adj_frame_id_cfg)),
img_backbone=dict(
type='SwinTransformer',
pretrained="https://github.com/SwinTransformer/storage/releases/download/v1.0.0/swin_base_patch4_window12_384_22k.pth",
pretrain_img_size=224,
patch_size=4,
window_size=12,
mlp_ratio=4,
embed_dims=128,
depths=[2, 2, 18, 2],
num_heads=[4, 8, 16, 32],
strides=(4, 2, 2, 2),
out_indices=(2, 3),
qkv_bias=True,
qk_scale=None,
patch_norm=True,
drop_rate=0.,
attn_drop_rate=0.,
drop_path_rate=0.1,
use_abs_pos_embed=False,
return_stereo_feat=True,
act_cfg=dict(type='GELU'),
norm_cfg=dict(type='LN', requires_grad=True),
pretrain_style='official',
output_missing_index_as_none=False),
img_neck=dict(
type='FPN_LSS',
in_channels=512+1024,
out_channels=512,
extra_upsample=None,
input_feature_index=(0,1),
scale_factor=2),
img_view_transformer=dict(
type='LSSViewTransformerBEVStereo',
grid_config=grid_config,
input_size=data_config['input_size'],
in_channels=512,
out_channels=numC_Trans,
sid=True,
depthnet_cfg=dict(use_dcn=False,
aspp_mid_channels=96,
stereo=True,
bias=5.),
downsample=16),
img_bev_encoder_backbone=dict(
type='CustomResNet',
with_cp=False,
numC_input=numC_Trans * (len(range(*multi_adj_frame_id_cfg))+1),
num_channels=[numC_Trans * 2, numC_Trans * 4, numC_Trans * 8]),
img_bev_encoder_neck=dict(
type='FPN_LSS',
in_channels=numC_Trans * 8 + numC_Trans * 2,
out_channels=256),
pre_process=dict(
type='CustomResNet',
with_cp=False,
numC_input=numC_Trans,
num_layer=[2,],
num_channels=[numC_Trans,],
stride=[1,],
backbone_output_ids=[0,]),
pts_bbox_head=dict(
type='CenterHead',
in_channels=256,
tasks=[
dict(num_class=1, class_names=['car']),
dict(num_class=2, class_names=['truck', 'construction_vehicle']),
dict(num_class=2, class_names=['bus', 'trailer']),
dict(num_class=1, class_names=['barrier']),
dict(num_class=2, class_names=['motorcycle', 'bicycle']),
dict(num_class=2, class_names=['pedestrian', 'traffic_cone']),
],
common_heads=dict(
reg=(2, 2), height=(1, 2), dim=(3, 2), rot=(2, 2), vel=(2, 2)),
share_conv_channel=64,
bbox_coder=dict(
type='CenterPointBBoxCoder',
pc_range=point_cloud_range[:2],
post_center_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_num=500,
score_threshold=0.1,
out_size_factor=4,
voxel_size=voxel_size[:2],
code_size=9),
separate_head=dict(
type='SeparateHead', init_bias=-2.19, final_kernel=3),
loss_cls=dict(type='GaussianFocalLoss', reduction='mean'),
loss_bbox=dict(type='L1Loss', reduction='mean', loss_weight=0.25),
norm_bbox=True),
# model training and testing settings
train_cfg=dict(
pts=dict(
point_cloud_range=point_cloud_range,
grid_size=[1024, 1024, 40],
voxel_size=voxel_size,
out_size_factor=4,
dense_reg=1,
gaussian_overlap=0.1,
max_objs=500,
min_radius=2,
code_weights=[1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0, 1.0])),
test_cfg=dict(
pts=dict(
pc_range=point_cloud_range[:2],
post_center_limit_range=[-61.2, -61.2, -10.0, 61.2, 61.2, 10.0],
max_per_img=500,
max_pool_nms=False,
min_radius=[4, 12, 10, 1, 0.85, 0.175],
score_threshold=0.1,
out_size_factor=4,
voxel_size=voxel_size[:2],
pre_max_size=1000,
post_max_size=83,
# Scale-NMS
nms_thr=0.125,
nms_type=['rotate', 'rotate', 'rotate', 'circle', 'rotate', 'rotate'],
nms_rescale_factor=[0.7, [0.4, 0.6], [0.3, 0.4], 0.9, [1.0, 1.0], [1.5, 2.5]],
)))
# Data
dataset_type = 'NuScenesDataset'
data_root = 'data/nuscenes/'
file_client_args = dict(backend='disk')
bda_aug_conf = dict(
rot_lim=(-22.5, 22.5),
scale_lim=(0.95, 1.05),
flip_dx_ratio=0.5,
flip_dy_ratio=0.5)
train_pipeline = [
dict(
type='PrepareImageInputs',
is_train=True,
data_config=data_config,
sequential=True),
dict(type='LoadAnnotations'),
dict(
type='BEVAug',
bda_aug_conf=bda_aug_conf,
classes=class_names),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(type='PointToMultiViewDepth', downsample=1, grid_config=grid_config),
dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
dict(type='ObjectNameFilter', classes=class_names),
dict(type='DefaultFormatBundle3D', class_names=class_names),
dict(
type='Collect3D', keys=['img_inputs', 'gt_bboxes_3d', 'gt_labels_3d',
'gt_depth'])
]
test_pipeline = [
dict(type='PrepareImageInputs', data_config=data_config, sequential=True),
dict(type='LoadAnnotations'),
dict(type='BEVAug',
bda_aug_conf=bda_aug_conf,
classes=class_names,
is_train=False),
dict(
type='LoadPointsFromFile',
coord_type='LIDAR',
load_dim=5,
use_dim=5,
file_client_args=file_client_args),
dict(
type='MultiScaleFlipAug3D',
img_scale=(1333, 800),
pts_scale_ratio=1,
flip=False,
transforms=[
dict(
type='DefaultFormatBundle3D',
class_names=class_names,
with_label=False),
dict(type='Collect3D', keys=['points', 'img_inputs'])
])
]
input_modality = dict(
use_lidar=False,
use_camera=True,
use_radar=False,
use_map=False,
use_external=False)
share_data_config = dict(
type=dataset_type,
classes=class_names,
modality=input_modality,
stereo=True,
img_info_prototype='bevdet4d',
multi_adj_frame_id_cfg=multi_adj_frame_id_cfg,
)
test_data_config = dict(
pipeline=test_pipeline,
ann_file=data_root + 'bevdetv3-nuscenes_infos_val.pkl')
data = dict(
samples_per_gpu=2, # with 32 GPU
workers_per_gpu=4,
train=dict(
type='CBGSDataset',
dataset=dict(
data_root=data_root,
ann_file=data_root + 'bevdetv3-nuscenes_infos_train.pkl',
pipeline=train_pipeline,
classes=class_names,
test_mode=False,
use_valid_flag=True,
# we use box_type_3d='LiDAR' in kitti and nuscenes dataset
# and box_type_3d='Depth' in sunrgbd and scannet dataset.
box_type_3d='LiDAR')),
val=test_data_config,
test=test_data_config)
for key in ['val', 'test']:
data[key].update(share_data_config)
data['train']['dataset'].update(share_data_config)
# Optimizer
optimizer = dict(type='AdamW', lr=2e-4, weight_decay=1e-2)
optimizer_config = dict(grad_clip=dict(max_norm=5, norm_type=2))
lr_config = dict(
policy='step',
warmup='linear',
warmup_iters=200,
warmup_ratio=0.001,
step=[20,])
runner = dict(type='EpochBasedRunner', max_epochs=20)
custom_hooks = [
dict(
type='MEGVIIEMAHook',
init_updates=10560,
priority='NORMAL',
),
dict(
type='SequentialControlHook',
temporal_start_epoch=2,
),
dict(
# we use syncbn to prevent loss divergency
type='SyncbnControlHook',
syncbn_start_epoch=2,
),
]
# fp16 = dict(loss_scale='dynamic')