Skip to content
This repository has been archived by the owner on Mar 27, 2023. It is now read-only.

feat(localization_launch): change argument structure in util.launch #270

Merged
merged 1 commit into from
Apr 7, 2022
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
28 changes: 9 additions & 19 deletions localization_launch/launch/util/util.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -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"),
Expand All @@ -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")}],
Expand All @@ -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")}],
Expand Down Expand Up @@ -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)])
13 changes: 8 additions & 5 deletions localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -2,10 +2,8 @@
<launch>

<!-- Topics -->
<arg name="input_sensor_points_topic" default="/sensing/lidar/top/rectified/pointcloud" description="input topic name for raw pointcloud"/>
<arg name="output_measurement_range_sensor_points_topic" default="measurement_range/pointcloud" description="output topic name for crop box filter"/>
<arg name="output_voxel_grid_downsample_sensor_points_topic" default="voxel_grid_downsample/pointcloud" description="output topic name for voxel grid downsample filter"/>
<arg name="output_downsample_sensor_points_topic" default="downsample/pointcloud" description="output topic name for downsample filter. this is final output"/>
<arg name="input/pointcloud" default="/sensing/lidar/top/rectified/pointcloud" description="input topic name"/>
<arg name="output/pointcloud" default="downsample/pointcloud" description="final output topic name"/>

<!-- container -->
<arg name="container" default="/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container" description="container name"/>
Expand All @@ -17,6 +15,11 @@
<include file="$(find-pkg-share pose_initializer)/launch/pose_initializer.launch.xml" />

<!-- util -->
<include file="$(find-pkg-share localization_launch)/launch/util/util.launch.py" />
<include file="$(find-pkg-share localization_launch)/launch/util/util.launch.py">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="output/pointcloud" value="$(var output/pointcloud)"/>
<arg name="container" value="$(var container)"/>
<arg name="use_intra_process" value="$(var use_intra_process)"/>
</include>

</launch>