Skip to content
This repository was archived by the owner on Mar 28, 2025. It is now read-only.

Commit 7714bb3

Browse files
committed
refactor!: pointcloud_preprocessor prefix package and namespace with autoware
Signed-off-by: Amadeusz Szymko <[email protected]>
1 parent 59843a4 commit 7714bb3

File tree

3 files changed

+11
-11
lines changed

3 files changed

+11
-11
lines changed

common_sensor_launch/launch/nebula_node_container.launch.py

+8-8
Original file line numberDiff line numberDiff line change
@@ -147,8 +147,8 @@ def create_parameter_dict(*args):
147147

148148
nodes.append(
149149
ComposableNode(
150-
package="pointcloud_preprocessor",
151-
plugin="pointcloud_preprocessor::CropBoxFilterComponent",
150+
package="autoware_pointcloud_preprocessor",
151+
plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent",
152152
name="crop_box_filter_self",
153153
remappings=[
154154
("input", "pointcloud_raw_ex"),
@@ -169,8 +169,8 @@ def create_parameter_dict(*args):
169169

170170
nodes.append(
171171
ComposableNode(
172-
package="pointcloud_preprocessor",
173-
plugin="pointcloud_preprocessor::CropBoxFilterComponent",
172+
package="autoware_pointcloud_preprocessor",
173+
plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent",
174174
name="crop_box_filter_mirror",
175175
remappings=[
176176
("input", "self_cropped/pointcloud_ex"),
@@ -183,8 +183,8 @@ def create_parameter_dict(*args):
183183

184184
nodes.append(
185185
ComposableNode(
186-
package="pointcloud_preprocessor",
187-
plugin="pointcloud_preprocessor::DistortionCorrectorComponent",
186+
package="autoware_pointcloud_preprocessor",
187+
plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent",
188188
name="distortion_corrector_node",
189189
remappings=[
190190
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),
@@ -206,8 +206,8 @@ def create_parameter_dict(*args):
206206
} # keep the output frame as the input frame
207207
nodes.append(
208208
ComposableNode(
209-
package="pointcloud_preprocessor",
210-
plugin="pointcloud_preprocessor::RingOutlierFilterComponent",
209+
package="autoware_pointcloud_preprocessor",
210+
plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent",
211211
name="ring_outlier_filter",
212212
remappings=[
213213
("input", "rectified/pointcloud_ex"),

sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py

+2-2
Original file line numberDiff line numberDiff line change
@@ -27,8 +27,8 @@
2727
def launch_setup(context, *args, **kwargs):
2828
# set concat filter as a component
2929
concat_component = ComposableNode(
30-
package="pointcloud_preprocessor",
31-
plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
30+
package="autoware_pointcloud_preprocessor",
31+
plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent",
3232
name="concatenate_data",
3333
remappings=[
3434
("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"),

sample_sensor_kit_launch/package.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212

1313
<exec_depend>common_sensor_launch</exec_depend>
1414
<exec_depend>gnss_poser</exec_depend>
15-
<exec_depend>pointcloud_preprocessor</exec_depend>
15+
<exec_depend>autoware_pointcloud_preprocessor</exec_depend>
1616
<exec_depend>tamagawa_imu_driver</exec_depend>
1717
<exec_depend>topic_tools</exec_depend>
1818
<exec_depend>ublox_gps</exec_depend>

0 commit comments

Comments
 (0)