5
5
from mmcv .ops import DynamicScatter
6
6
from torch import Tensor , nn
7
7
8
+ from mmdet3d .models .voxel_encoders .utils import (PFNLayer ,
9
+ get_paddings_indicator )
8
10
from mmdet3d .registry import MODELS
9
- from mmdet3d .models .voxel_encoders .utils import PFNLayer , get_paddings_indicator
11
+
12
+
10
13
@MODELS .register_module ()
11
14
class PillarFeatureNetAutoware (nn .Module ):
12
15
"""Pillar Feature Net.
@@ -35,20 +38,20 @@ class PillarFeatureNetAutoware(nn.Module):
35
38
the original behavior. Defaults to True.
36
39
"""
37
40
38
- def __init__ (self ,
39
- in_channels : Optional [ int ] = 4 ,
40
- feat_channels : Optional [tuple ] = ( 64 ,) ,
41
- with_distance : Optional [bool ] = False ,
42
- with_cluster_center : Optional [bool ] = True ,
43
- with_voxel_center : Optional [bool ] = True ,
44
- voxel_size : Optional [Tuple [ float ]] = ( 0.2 , 0.2 , 4 ) ,
45
- point_cloud_range : Optional [Tuple [float ]] = (0 , - 40 , - 3 , 70.4 ,
46
- 40 , 1 ),
47
- norm_cfg : Optional [dict ] = dict (
48
- type = 'BN1d' , eps = 1e-3 , momentum = 0.01 ) ,
49
- mode : Optional [str ] = 'max' ,
50
- legacy : Optional [bool ] = True ,
51
- use_voxel_center_z : Optional [ bool ] = True , ):
41
+ def __init__ (
42
+ self ,
43
+ in_channels : Optional [int ] = 4 ,
44
+ feat_channels : Optional [tuple ] = ( 64 , ) ,
45
+ with_distance : Optional [bool ] = False ,
46
+ with_cluster_center : Optional [bool ] = True ,
47
+ with_voxel_center : Optional [bool ] = True ,
48
+ voxel_size : Optional [Tuple [float ]] = (0.2 , 0.2 , 4 ) ,
49
+ point_cloud_range : Optional [ Tuple [ float ]] = ( 0 , - 40 , - 3 , 70.4 , 40 , 1 ),
50
+ norm_cfg : Optional [dict ] = dict (type = 'BN1d' , eps = 1e-3 , momentum = 0.01 ),
51
+ mode : Optional [ str ] = 'max' ,
52
+ legacy : Optional [bool ] = True ,
53
+ use_voxel_center_z : Optional [bool ] = True ,
54
+ ):
52
55
super (PillarFeatureNetAutoware , self ).__init__ ()
53
56
assert len (feat_channels ) > 0
54
57
self .legacy = legacy
@@ -111,7 +114,7 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
111
114
if self ._with_cluster_center :
112
115
points_mean = features [:, :, :3 ].sum (
113
116
dim = 1 , keepdim = True ) / num_points .type_as (features ).view (
114
- - 1 , 1 , 1 )
117
+ - 1 , 1 , 1 )
115
118
f_cluster = features [:, :, :3 ] - points_mean
116
119
features_ls .append (f_cluster )
117
120
@@ -120,29 +123,30 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
120
123
if self ._with_voxel_center :
121
124
center_feature_size = 3 if self .use_voxel_center_z else 2
122
125
if not self .legacy :
123
- f_center = torch .zeros_like (features [:, :, :center_feature_size ])
126
+ f_center = torch .zeros_like (
127
+ features [:, :, :center_feature_size ])
124
128
f_center [:, :, 0 ] = features [:, :, 0 ] - (
125
- coors [:, 3 ].to (dtype ).unsqueeze (1 ) * self .vx +
126
- self .x_offset )
129
+ coors [:, 3 ].to (dtype ).unsqueeze (1 ) * self .vx +
130
+ self .x_offset )
127
131
f_center [:, :, 1 ] = features [:, :, 1 ] - (
128
- coors [:, 2 ].to (dtype ).unsqueeze (1 ) * self .vy +
129
- self .y_offset )
132
+ coors [:, 2 ].to (dtype ).unsqueeze (1 ) * self .vy +
133
+ self .y_offset )
130
134
if self .use_voxel_center_z :
131
135
f_center [:, :, 2 ] = features [:, :, 2 ] - (
132
- coors [:, 1 ].to (dtype ).unsqueeze (1 ) * self .vz +
133
- self .z_offset )
136
+ coors [:, 1 ].to (dtype ).unsqueeze (1 ) * self .vz +
137
+ self .z_offset )
134
138
else :
135
139
f_center = features [:, :, :center_feature_size ]
136
140
f_center [:, :, 0 ] = f_center [:, :, 0 ] - (
137
- coors [:, 3 ].type_as (features ).unsqueeze (1 ) * self .vx +
138
- self .x_offset )
141
+ coors [:, 3 ].type_as (features ).unsqueeze (1 ) * self .vx +
142
+ self .x_offset )
139
143
f_center [:, :, 1 ] = f_center [:, :, 1 ] - (
140
- coors [:, 2 ].type_as (features ).unsqueeze (1 ) * self .vy +
141
- self .y_offset )
144
+ coors [:, 2 ].type_as (features ).unsqueeze (1 ) * self .vy +
145
+ self .y_offset )
142
146
if self .use_voxel_center_z :
143
147
f_center [:, :, 2 ] = f_center [:, :, 2 ] - (
144
- coors [:, 1 ].type_as (features ).unsqueeze (1 ) * self .vz +
145
- self .z_offset )
148
+ coors [:, 1 ].type_as (features ).unsqueeze (1 ) * self .vz +
149
+ self .z_offset )
146
150
features_ls .append (f_center )
147
151
148
152
if self ._with_distance :
@@ -162,4 +166,4 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
162
166
for pfn in self .pfn_layers :
163
167
features = pfn (features , num_points )
164
168
165
- return features .squeeze (1 )
169
+ return features .squeeze (1 )
0 commit comments