pointpillars_hv_secfpn_8xb6-160e_kitti-3d-3class.py 4.21 KB
Newer Older
zhangwenwei's avatar
zhangwenwei committed
1
_base_ = [
2
    '../_base_/models/pointpillars_hv_secfpn_kitti.py',
zhangwenwei's avatar
zhangwenwei committed
3
    '../_base_/datasets/kitti-3d-3class.py',
4
    '../_base_/schedules/cyclic-40e.py', '../_base_/default_runtime.py'
zhangwenwei's avatar
zhangwenwei committed
5
]
6

zhangwenwei's avatar
zhangwenwei committed
7
point_cloud_range = [0, -39.68, -3, 69.12, 39.68, 1]
8
9
10
# dataset settings
data_root = 'data/kitti/'
class_names = ['Pedestrian', 'Cyclist', 'Car']
11
metainfo = dict(classes=class_names)
12
backend_args = None
13

zhangwenwei's avatar
zhangwenwei committed
14
# PointPillars adopted a different sampling strategies among classes
15
16
17
18
19
20
db_sampler = dict(
    data_root=data_root,
    info_path=data_root + 'kitti_dbinfos_train.pkl',
    rate=1.0,
    prepare=dict(
        filter_by_difficulty=[-1],
21
        filter_by_min_points=dict(Car=5, Pedestrian=5, Cyclist=5)),
22
    classes=class_names,
23
24
    sample_groups=dict(Car=15, Pedestrian=15, Cyclist=15),
    points_loader=dict(
25
26
27
28
29
30
        type='LoadPointsFromFile',
        coord_type='LIDAR',
        load_dim=4,
        use_dim=4,
        backend_args=backend_args),
    backend_args=backend_args)
31

zhangwenwei's avatar
zhangwenwei committed
32
# PointPillars uses different augmentation hyper parameters
33
train_pipeline = [
34
35
36
37
38
39
    dict(
        type='LoadPointsFromFile',
        coord_type='LIDAR',
        load_dim=4,
        use_dim=4,
        backend_args=backend_args),
40
    dict(type='LoadAnnotations3D', with_bbox_3d=True, with_label_3d=True),
Xiangxu-0103's avatar
Xiangxu-0103 committed
41
    dict(type='ObjectSample', db_sampler=db_sampler, use_ground_plane=True),
wuyuefeng's avatar
wuyuefeng committed
42
    dict(type='RandomFlip3D', flip_ratio_bev_horizontal=0.5),
43
    dict(
zhangwenwei's avatar
zhangwenwei committed
44
45
46
        type='GlobalRotScaleTrans',
        rot_range=[-0.78539816, 0.78539816],
        scale_ratio_range=[0.95, 1.05]),
47
48
49
    dict(type='PointsRangeFilter', point_cloud_range=point_cloud_range),
    dict(type='ObjectRangeFilter', point_cloud_range=point_cloud_range),
    dict(type='PointShuffle'),
VVsssssk's avatar
VVsssssk committed
50
51
52
    dict(
        type='Pack3DDetInputs',
        keys=['points', 'gt_labels_3d', 'gt_bboxes_3d'])
53
54
]
test_pipeline = [
55
56
57
58
59
60
    dict(
        type='LoadPointsFromFile',
        coord_type='LIDAR',
        load_dim=4,
        use_dim=4,
        backend_args=backend_args),
61
    dict(
zhangwenwei's avatar
zhangwenwei committed
62
63
64
65
66
67
68
69
70
71
72
73
        type='MultiScaleFlipAug3D',
        img_scale=(1333, 800),
        pts_scale_ratio=1,
        flip=False,
        transforms=[
            dict(
                type='GlobalRotScaleTrans',
                rot_range=[0, 0],
                scale_ratio_range=[1., 1.],
                translation_std=[0, 0, 0]),
            dict(type='RandomFlip3D'),
            dict(
74
75
76
                type='PointsRangeFilter', point_cloud_range=point_cloud_range)
        ]),
    dict(type='Pack3DDetInputs', keys=['points'])
77
78
]

VVsssssk's avatar
VVsssssk committed
79
80
train_dataloader = dict(
    dataset=dict(dataset=dict(pipeline=train_pipeline, metainfo=metainfo)))
81
82
test_dataloader = dict(dataset=dict(pipeline=test_pipeline, metainfo=metainfo))
val_dataloader = dict(dataset=dict(pipeline=test_pipeline, metainfo=metainfo))
zhangwenwei's avatar
zhangwenwei committed
83
# In practice PointPillars also uses a different schedule
84
# optimizer
zhangwenwei's avatar
zhangwenwei committed
85
lr = 0.001
VVsssssk's avatar
VVsssssk committed
86
87
88
89
90
91
epoch_num = 80
optim_wrapper = dict(
    optimizer=dict(lr=lr), clip_grad=dict(max_norm=35, norm_type=2))
param_scheduler = [
    dict(
        type='CosineAnnealingLR',
92
        T_max=epoch_num * 0.4,
VVsssssk's avatar
VVsssssk committed
93
94
        eta_min=lr * 10,
        begin=0,
95
96
97
        end=epoch_num * 0.4,
        by_epoch=True,
        convert_to_iter_based=True),
VVsssssk's avatar
VVsssssk committed
98
99
    dict(
        type='CosineAnnealingLR',
100
        T_max=epoch_num * 0.6,
VVsssssk's avatar
VVsssssk committed
101
        eta_min=lr * 1e-4,
102
103
104
105
        begin=epoch_num * 0.4,
        end=epoch_num * 1,
        by_epoch=True,
        convert_to_iter_based=True),
VVsssssk's avatar
VVsssssk committed
106
    dict(
107
        type='CosineAnnealingMomentum',
108
        T_max=epoch_num * 0.4,
VVsssssk's avatar
VVsssssk committed
109
110
        eta_min=0.85 / 0.95,
        begin=0,
111
112
113
        end=epoch_num * 0.4,
        by_epoch=True,
        convert_to_iter_based=True),
VVsssssk's avatar
VVsssssk committed
114
    dict(
115
        type='CosineAnnealingMomentum',
116
        T_max=epoch_num * 0.6,
VVsssssk's avatar
VVsssssk committed
117
        eta_min=1,
118
119
120
        begin=epoch_num * 0.4,
        end=epoch_num * 1,
        convert_to_iter_based=True)
VVsssssk's avatar
VVsssssk committed
121
]
zhangwenwei's avatar
zhangwenwei committed
122
123
124
125
126
127
# max_norm=35 is slightly better than 10 for PointPillars in the earlier
# development of the codebase thus we keep the setting. But we does not
# specifically tune this parameter.
# PointPillars usually need longer schedule than second, we simply double
# the training schedule. Do remind that since we use RepeatDataset and
# repeat factor is 2, so we actually train 160 epochs.
128
129
train_cfg = dict(by_epoch=True, max_epochs=epoch_num, val_interval=2)
val_cfg = dict()
VVsssssk's avatar
VVsssssk committed
130
test_cfg = dict()