From 6a9ea0f93ed3280e830cca15aa51e1fe4395e59a Mon Sep 17 00:00:00 2001 From: h-ohta Date: Thu, 7 Apr 2022 11:02:12 +0900 Subject: [PATCH] feat(localization_launch): change argument structure in util.launch --- .../launch/util/util.launch.py | 28 ++++++------------- .../launch/util/util.launch.xml | 13 +++++---- 2 files changed, 17 insertions(+), 24 deletions(-) diff --git a/localization_launch/launch/util/util.launch.py b/localization_launch/launch/util/util.launch.py index abcd824b7..83d99b2a0 100644 --- a/localization_launch/launch/util/util.launch.py +++ b/localization_launch/launch/util/util.launch.py @@ -34,8 +34,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::CropBoxFilterComponent", name="crop_box_filter_measurement_range", remappings=[ - ("input", LaunchConfiguration("input_sensor_points_topic")), - ("output", LaunchConfiguration("output_measurement_range_sensor_points_topic")), + ("input", LaunchConfiguration("input/pointcloud")), + ("output", "measurement_range/pointcloud"), ], parameters=[ load_composable_node_param("crop_box_filter_measurement_range_param_path"), @@ -47,8 +47,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent", name="voxel_grid_downsample_filter", remappings=[ - ("input", LaunchConfiguration("output_measurement_range_sensor_points_topic")), - ("output", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), + ("input", "measurement_range/pointcloud"), + ("output", "voxel_grid_downsample/pointcloud"), ], parameters=[load_composable_node_param("voxel_grid_downsample_filter_param_path")], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -58,8 +58,8 @@ def load_composable_node_param(param_path): plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent", name="random_downsample_filter", remappings=[ - ("input", LaunchConfiguration("output_voxel_grid_downsample_sensor_points_topic")), - ("output", LaunchConfiguration("output_downsample_sensor_points_topic")), + ("input", "voxel_grid_downsample/pointcloud"), + ("output", LaunchConfiguration("output/pointcloud")), ], parameters=[load_composable_node_param("random_downsample_filter_param_path")], extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], @@ -112,24 +112,14 @@ def add_launch_arg(name: str, default_value=None, description=None): "container name", ) add_launch_arg( - "input_sensor_points_topic", + "input/pointcloud", "/sensing/lidar/top/rectified/pointcloud", "input topic name for raw pointcloud", ) add_launch_arg( - "output_measurement_range_sensor_points_topic", - "measurement_range/pointcloud", - "output topic name for crop box filter", - ) - add_launch_arg( - "output_voxel_grid_downsample_sensor_points_topic", - "voxel_grid_downsample/pointcloud", - "output topic name for voxel grid downsample filter", - ) - add_launch_arg( - "output_downsample_sensor_points_topic", + "output/pointcloud", "downsample/pointcloud", - "output topic name for downsample filter. this is final output", + "final output topic name", ) return launch.LaunchDescription(launch_arguments + [OpaqueFunction(function=launch_setup)]) diff --git a/localization_launch/launch/util/util.launch.xml b/localization_launch/launch/util/util.launch.xml index 6d2cc2954..4973513b8 100644 --- a/localization_launch/launch/util/util.launch.xml +++ b/localization_launch/launch/util/util.launch.xml @@ -2,10 +2,8 @@ - - - - + + @@ -17,6 +15,11 @@ - + + + + + +