Skip to content

Commit caedccd

Browse files
committed
refactor(tier4_localization_launch): use util.launch.xml instead of util.launch.py
Signed-off-by: Yamato Ando <yamato.ando@tier4.jp>
1 parent e41946b commit caedccd

File tree

3 files changed

+41
-138
lines changed

3 files changed

+41
-138
lines changed

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

+2-2
Original file line numberDiff line numberDiff line change
@@ -23,7 +23,7 @@
2323
<group if="$(var gnss_enabled)">
2424
<include file="$(find-pkg-share automatic_pose_initializer)/launch/automatic_pose_initializer.launch.xml"/>
2525
</group>
26-
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.py">
26+
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.xml">
2727
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
2828
</include>
2929
</group>
@@ -144,7 +144,7 @@
144144
<group if="$(var gnss_enabled)">
145145
<include file="$(find-pkg-share automatic_pose_initializer)/launch/automatic_pose_initializer.launch.xml"/>
146146
</group>
147-
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.py">
147+
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.xml">
148148
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
149149
</include>
150150
</group>

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

0 commit comments

Comments
 (0)