Skip to content

Commit 934d97f

Browse files
committed
fix: refactor repo
Signed-off-by: Kaan Çolak <kaancolak95@gmail.com>
1 parent 0238da8 commit 934d97f

16 files changed

+505
-454
lines changed
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,3 @@
11
from .pillar_encoder_autoware import PillarFeatureNetAutoware
22

3-
__all__ = [ 'PillarFeatureNetAutoware']
3+
__all__ = ['PillarFeatureNetAutoware']

projects/AutowareCenterPoint/centerpoint/pillar_encoder_autoware.py

+34-30
Original file line numberDiff line numberDiff line change
@@ -5,8 +5,11 @@
55
from mmcv.ops import DynamicScatter
66
from torch import Tensor, nn
77

8+
from mmdet3d.models.voxel_encoders.utils import (PFNLayer,
9+
get_paddings_indicator)
810
from mmdet3d.registry import MODELS
9-
from mmdet3d.models.voxel_encoders.utils import PFNLayer, get_paddings_indicator
11+
12+
1013
@MODELS.register_module()
1114
class PillarFeatureNetAutoware(nn.Module):
1215
"""Pillar Feature Net.
@@ -35,20 +38,20 @@ class PillarFeatureNetAutoware(nn.Module):
3538
the original behavior. Defaults to True.
3639
"""
3740

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+
):
5255
super(PillarFeatureNetAutoware, self).__init__()
5356
assert len(feat_channels) > 0
5457
self.legacy = legacy
@@ -111,7 +114,7 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
111114
if self._with_cluster_center:
112115
points_mean = features[:, :, :3].sum(
113116
dim=1, keepdim=True) / num_points.type_as(features).view(
114-
-1, 1, 1)
117+
-1, 1, 1)
115118
f_cluster = features[:, :, :3] - points_mean
116119
features_ls.append(f_cluster)
117120

@@ -120,29 +123,30 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
120123
if self._with_voxel_center:
121124
center_feature_size = 3 if self.use_voxel_center_z else 2
122125
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])
124128
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)
127131
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)
130134
if self.use_voxel_center_z:
131135
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)
134138
else:
135139
f_center = features[:, :, :center_feature_size]
136140
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)
139143
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)
142146
if self.use_voxel_center_z:
143147
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)
146150
features_ls.append(f_center)
147151

148152
if self._with_distance:
@@ -162,4 +166,4 @@ def forward(self, features: Tensor, num_points: Tensor, coors: Tensor,
162166
for pfn in self.pfn_layers:
163167
features = pfn(features, num_points)
164168

165-
return features.squeeze(1)
169+
return features.squeeze(1)

0 commit comments

Comments
 (0)