diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index d24b1ff8..49e0b958 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -147,8 +147,8 @@ def create_parameter_dict(*args): nodes.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_self", remappings=[ ("input", "pointcloud_raw_ex"), @@ -169,8 +169,8 @@ def create_parameter_dict(*args): nodes.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::CropBoxFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_mirror", remappings=[ ("input", "self_cropped/pointcloud_ex"), @@ -183,8 +183,8 @@ def create_parameter_dict(*args): nodes.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DistortionCorrectorComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::DistortionCorrectorComponent", name="distortion_corrector_node", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), @@ -206,8 +206,8 @@ def create_parameter_dict(*args): } # keep the output frame as the input frame nodes.append( ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::RingOutlierFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::RingOutlierFilterComponent", name="ring_outlier_filter", remappings=[ ("input", "rectified/pointcloud_ex"), diff --git a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py index 8122b07e..c29d74e3 100644 --- a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -27,8 +27,8 @@ def launch_setup(context, *args, **kwargs): # set concat filter as a component concat_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::PointCloudConcatenateDataSynchronizerComponent", name="concatenate_data", remappings=[ ("~/input/twist", "/sensing/vehicle_velocity_converter/twist_with_covariance"), diff --git a/sample_sensor_kit_launch/package.xml b/sample_sensor_kit_launch/package.xml index 054149b0..210c5a88 100644 --- a/sample_sensor_kit_launch/package.xml +++ b/sample_sensor_kit_launch/package.xml @@ -10,9 +10,9 @@ ament_cmake_auto + autoware_pointcloud_preprocessor common_sensor_launch gnss_poser - pointcloud_preprocessor tamagawa_imu_driver topic_tools ublox_gps