diff --git a/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py index a230ce0..26eaa1b 100644 --- a/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ b/awsim_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -29,8 +29,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/awsim_sensor_kit_launch/package.xml b/awsim_sensor_kit_launch/package.xml index 93f53f5..694fc77 100644 --- a/awsim_sensor_kit_launch/package.xml +++ b/awsim_sensor_kit_launch/package.xml @@ -9,9 +9,9 @@ ament_cmake_auto + autoware_pointcloud_preprocessor common_sensor_launch gnss_poser - pointcloud_preprocessor tamagawa_imu_driver topic_tools ublox_gps diff --git a/common_awsim_sensor_launch/launch/velodyne_node_container.launch.py b/common_awsim_sensor_launch/launch/velodyne_node_container.launch.py index 40291ab..87565eb 100644 --- a/common_awsim_sensor_launch/launch/velodyne_node_container.launch.py +++ b/common_awsim_sensor_launch/launch/velodyne_node_container.launch.py @@ -72,8 +72,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"), @@ -94,8 +94,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"), @@ -108,8 +108,8 @@ def create_parameter_dict(*args): 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"), @@ -130,8 +130,8 @@ def create_parameter_dict(*args): ) distortion_component = 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"),