Skip to content

Commit

Permalink
feat(tier4_localization_launch): change the default input pointcloud …
Browse files Browse the repository at this point in the history
…of localization into the concatenated pointcloud (#6528)

refactor lacun argument lidar_container_name to localization_pointcloud_container_name

Signed-off-by: TaikiYamada4 <[email protected]>
  • Loading branch information
TaikiYamada4 authored Mar 4, 2024
1 parent 065068b commit 1b45a7e
Show file tree
Hide file tree
Showing 3 changed files with 6 additions and 6 deletions.
Original file line number Diff line number Diff line change
Expand Up @@ -17,15 +17,15 @@
<arg name="eagleye_param_path"/>
<arg name="ar_tag_based_localizer_param_path"/>

<arg name="input_pointcloud" default="/sensing/lidar/top/pointcloud"/>
<arg name="lidar_container_name" default="/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container"/>
<arg name="input_pointcloud" default="/sensing/lidar/concatenated/pointcloud"/>
<arg name="localization_pointcloud_container_name" default="/pointcloud_container"/>

<!-- localization module -->
<group>
<push-ros-namespace namespace="localization"/>
<!-- pose_twist_estimator module -->
<include file="$(find-pkg-share tier4_localization_launch)/launch/pose_twist_estimator/pose_twist_estimator.launch.xml">
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
<arg name="localization_pointcloud_container_name" value="$(var localization_pointcloud_container_name)"/>
</include>

<!-- pose_twist_fusion_filter module -->
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -109,7 +109,7 @@
<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.xml" if="$(var use_ndt_pose)">
<arg name="lidar_container_name" value="$(var lidar_container_name)"/>
<arg name="localization_pointcloud_container_name" value="$(var localization_pointcloud_container_name)"/>
<arg name="input_pointcloud" value="$(var override_input_pointcloud)"/>
</include>
</group>
Expand Down
4 changes: 2 additions & 2 deletions launch/tier4_localization_launch/launch/util/util.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -3,12 +3,12 @@
<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"/>
<arg name="localization_pointcloud_container_name" default="/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)">
<load_composable_node target="$(var localization_pointcloud_container_name)">
<composable_node pkg="pointcloud_preprocessor" plugin="pointcloud_preprocessor::CropBoxFilterComponent" name="crop_box_filter_measurement_range">
<param from="$(var ndt_scan_matcher/pointcloud_preprocessor/crop_box_filter_measurement_range_param_path)"/>
<remap from="input" to="$(var input_pointcloud)"/>
Expand Down

0 comments on commit 1b45a7e

Please sign in to comment.