Skip to content

Commit b396413

Browse files
refactor(tier4_localization_launch): use util.launch.xml instead of util.launch.py (#6287)
* refactor(tier4_localization_launch): use util.launch.xml instead of util.launch.py Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> * style(pre-commit): autofix --------- Signed-off-by: Yamato Ando <yamato.ando@tier4.jp> Co-authored-by: pre-commit-ci[bot] <66853113+pre-commit-ci[bot]@users.noreply.github.com>
1 parent c897b3d commit b396413

File tree

3 files changed

+34
-137
lines changed

3 files changed

+34
-137
lines changed

launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml

+1-1
Original file line numberDiff line numberDiff line change
@@ -108,7 +108,7 @@
108108
<!-- pointcloud_downsampling -->
109109
<let name="override_input_pointcloud" value="$(var input_pointcloud)"/>
110110
<let name="override_input_pointcloud" value="$(var input_pointcloud)/relay" if="$(var multi_localizer_mode)"/>
111-
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.py" if="$(var use_ndt_pose)">
111+
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.xml" if="$(var use_ndt_pose)">
112112
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
113113
<arg name="input_pointcloud" value="$(var override_input_pointcloud)"/>
114114
</include>

launch/tier4_localization_launch/launch/util/util.launch.py

-136
This file was deleted.
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,33 @@
1+
<launch>
2+
<!-- topic -->
3+
<arg name="output/pointcloud" default="downsample/pointcloud" description="final output topic name"/>
4+
5+
<!-- container -->
6+
<arg name="lidar_container_name" default="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container" description="container name of main lidar used for localization"/>
7+
8+
<!-- whether use intra-process -->
9+
<arg name="use_intra_process" default="true" description="use ROS 2 component container communication"/>
10+
11+
<load_composable_node target="$(var lidar_container_name)">
12+
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter_measurement_range">
13+
<param from="$(var crop_box_filter_measurement_range_param_path)"/>
14+
<remap from="input" to="$(var input_pointcloud)"/>
15+
<remap from="output" to="measurement_range/pointcloud"/>
16+
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
17+
</composable_node>
18+
19+
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::VoxelGridDownsampleFilterComponent" name="voxel_grid_downsample_filter">
20+
<param from="$(var voxel_grid_downsample_filter_param_path)"/>
21+
<remap from="input" to="measurement_range/pointcloud"/>
22+
<remap from="output" to="voxel_grid_downsample/pointcloud"/>
23+
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
24+
</composable_node>
25+
26+
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::RandomDownsampleFilterComponent" name="random_downsample_filter">
27+
<param from="$(var random_downsample_filter_param_path)"/>
28+
<remap from="input" to="voxel_grid_downsample/pointcloud"/>
29+
<remap from="output" to="$(var output/pointcloud)"/>
30+
<extra_arg name="use_intra_process_comms" value="$(var use_intra_process)"/>
31+
</composable_node>
32+
</load_composable_node>
33+
</launch>

0 commit comments

Comments
 (0)