From a03c37d6d07e16f64a01a884f304a9ffb8cf35a3 Mon Sep 17 00:00:00 2001 From: Tomohito ANDO Date: Wed, 15 Jan 2025 14:25:03 +0900 Subject: [PATCH] fix(aip_x2_gen2_launch): add missing `autoware_` prefix (#370) * fix(aip_x2_gen2_launch): add missing prefix Signed-off-by: Tomohito Ando * ci(pre-commit): autofix * fix plugin Signed-off-by: Tomohito Ando * add missing autoware_ prefix Signed-off-by: Tomohito Ando --------- Signed-off-by: Tomohito Ando Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com> --- aip_x2_gen2_launch/launch/gnss.launch.xml | 2 +- aip_x2_gen2_launch/launch/imu.launch.xml | 4 ++-- .../launch/nebula_node_container.launch.py | 24 +++++++++---------- .../launch/pointcloud_preprocessor.launch.py | 4 ++-- aip_x2_gen2_launch/launch/radar.launch.xml | 14 +++++------ aip_x2_gen2_launch/launch/sensing.launch.xml | 2 +- aip_x2_gen2_launch/package.xml | 11 +++++---- 7 files changed, 32 insertions(+), 29 deletions(-) diff --git a/aip_x2_gen2_launch/launch/gnss.launch.xml b/aip_x2_gen2_launch/launch/gnss.launch.xml index 8ccd477c..7f9e5d3f 100644 --- a/aip_x2_gen2_launch/launch/gnss.launch.xml +++ b/aip_x2_gen2_launch/launch/gnss.launch.xml @@ -14,7 +14,7 @@ - + diff --git a/aip_x2_gen2_launch/launch/imu.launch.xml b/aip_x2_gen2_launch/launch/imu.launch.xml index a2c0c80d..fd07632c 100644 --- a/aip_x2_gen2_launch/launch/imu.launch.xml +++ b/aip_x2_gen2_launch/launch/imu.launch.xml @@ -23,13 +23,13 @@ - + - + diff --git a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py index ad58a838..6f17007b 100644 --- a/aip_x2_gen2_launch/launch/nebula_node_container.launch.py +++ b/aip_x2_gen2_launch/launch/nebula_node_container.launch.py @@ -75,7 +75,7 @@ def str2vector(string): sensor_make, sensor_extension = get_lidar_make(sensor_model) glog_component = ComposableNode( - package="glog_component", + package="autoware_glog_component", plugin="GlogComponent", name="glog_component", ) @@ -136,8 +136,8 @@ def str2vector(string): cropbox_parameters["max_z"] = vehicle_info["max_height_offset"] self_crop_component = 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"), @@ -148,8 +148,8 @@ def str2vector(string): ) undistort_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"), @@ -162,8 +162,8 @@ def str2vector(string): ) ring_outlier_filter_component = 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"), @@ -173,8 +173,8 @@ def str2vector(string): ) dual_return_filter_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::DualReturnOutlierFilterComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::DualReturnOutlierFilterComponent", name="dual_return_filter", remappings=[ ("input", "rectified/pointcloud_ex"), @@ -193,8 +193,8 @@ def str2vector(string): distance_range = str2vector(context.perform_substitution(LaunchConfiguration("distance_range"))) blockage_diag_component = ComposableNode( - package="pointcloud_preprocessor", - plugin="pointcloud_preprocessor::BlockageDiagComponent", + package="autoware_pointcloud_preprocessor", + plugin="autoware::pointcloud_preprocessor::BlockageDiagComponent", name="blockage_return_diag", remappings=[ ("input", "pointcloud_raw_ex"), @@ -216,7 +216,7 @@ def str2vector(string): container = ComposableNodeContainer( name="nebula_node_container", - namespace="pointcloud_preprocessor", + namespace="autoware_pointcloud_preprocessor", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[ diff --git a/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py index ef03f232..0775e3a2 100644 --- a/aip_x2_gen2_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_x2_gen2_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/aip_x2_gen2_launch/launch/radar.launch.xml b/aip_x2_gen2_launch/launch/radar.launch.xml index 5fc16689..d793d8de 100644 --- a/aip_x2_gen2_launch/launch/radar.launch.xml +++ b/aip_x2_gen2_launch/launch/radar.launch.xml @@ -32,7 +32,7 @@ - + @@ -62,7 +62,7 @@ - + @@ -92,7 +92,7 @@ - + @@ -122,7 +122,7 @@ - + @@ -152,7 +152,7 @@ - + @@ -182,7 +182,7 @@ - + @@ -194,7 +194,7 @@ - + diff --git a/aip_x2_gen2_launch/launch/sensing.launch.xml b/aip_x2_gen2_launch/launch/sensing.launch.xml index ec9adc0e..8000211f 100644 --- a/aip_x2_gen2_launch/launch/sensing.launch.xml +++ b/aip_x2_gen2_launch/launch/sensing.launch.xml @@ -30,7 +30,7 @@ - + diff --git a/aip_x2_gen2_launch/package.xml b/aip_x2_gen2_launch/package.xml index 2743c6a8..685c1424 100644 --- a/aip_x2_gen2_launch/package.xml +++ b/aip_x2_gen2_launch/package.xml @@ -10,17 +10,20 @@ ament_cmake_auto + autoware_glog_component + autoware_gnss_poser + autoware_imu_corrector + autoware_pointcloud_preprocessor + autoware_radar_tracks_msgs_converter + autoware_simple_object_merger + autoware_vehicle_velocity_converter common_sensor_launch dummy_diag_publisher - gnss_poser - imu_corrector - pointcloud_preprocessor septentrio_gnss_driver tamagawa_imu_driver topic_tools ublox_gps usb_cam - vehicle_velocity_converter ament_lint_auto autoware_lint_common