Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

refactor(tier4_localization_launch): use util.launch.xml instead of util.launch.py #6287

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
Original file line number Diff line number Diff line change
Expand Up @@ -108,7 +108,7 @@
<!-- pointcloud_downsampling -->
<let name="override_input_pointcloud" value="$(var input_pointcloud)"/>
<let name="override_input_pointcloud" value="$(var input_pointcloud)/relay" if="$(var multi_localizer_mode)"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.py" if="$(var use_ndt_pose)">
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.xml" if="$(var use_ndt_pose)">
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
<arg name="input_pointcloud" value="$(var override_input_pointcloud)"/>
</include>
Expand Down
136 changes: 0 additions & 136 deletions launch/tier4_localization_launch/launch/util/util.launch.py

This file was deleted.

33 changes: 33 additions & 0 deletions launch/tier4_localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
@@ -0,0 +1,33 @@
<launch>
<!-- topic -->
<arg name="output/pointcloud" default="downsample/pointcloud" description="final output topic name"/>

<!-- container -->
<arg name="lidar_container_name" default="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container" description="container name of main lidar used for localization"/>

<!-- whether use intra-process -->
<arg name="use_intra_process" default="true" description="use ROS 2 component container communication"/>

<load_composable_node target="$(var lidar_container_name)">
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter_measurement_range">
<param from="$(var crop_box_filter_measurement_range_param_path)"/>
<remap from="input" to="$(var input_pointcloud)"/>
<remap from="output" to="measurement_range/pointcloud"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>

<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" name="voxel_grid_downsample_filter">
<param from="$(var voxel_grid_downsample_filter_param_path)"/>
<remap from="input" to="measurement_range/pointcloud"/>
<remap from="output" to="voxel_grid_downsample/pointcloud"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>

<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent" name="random_downsample_filter">
<param from="$(var random_downsample_filter_param_path)"/>
<remap from="input" to="voxel_grid_downsample/pointcloud"/>
<remap from="output" to="$(var output/pointcloud)"/>
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
</composable_node>
</load_composable_node>
</launch>
Loading