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

feat(tier4_localization_launch): pass pc container to localization #2114

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
@@ -1,7 +1,8 @@
<?xml version="1.0"?>
<launch>
<arg name="input/pointcloud" default="/sensing/lidar/top/outlier_filtered/pointcloud" description="The topic will be used in the localization util module"/>
<arg name="container" default="/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container"/>
<arg name="use_pointcloud_container" default="true" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<arg name="tier4_localization_launch_param_path" default="$(find-pkg-share tier4_localization_launch)/config" description="tier4_localization_launch parameter path"/>

Expand All @@ -13,7 +14,8 @@
<push-ros-namespace namespace="util"/>
<include file="$(find-pkg-share tier4_localization_launch)/launch/util/util.launch.xml">
<arg name="input/pointcloud" value="$(var input/pointcloud)"/>
<arg name="container" value="$(var container)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="tier4_localization_launch_param_path" value="$(var tier4_localization_launch_param_path)"/>
</include>
</group>
Expand Down
17 changes: 13 additions & 4 deletions launch/tier4_localization_launch/launch/util/util.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -16,6 +16,7 @@
from launch.actions import DeclareLaunchArgument
from launch.actions import OpaqueFunction
from launch.conditions import LaunchConfigurationNotEquals
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
Expand Down Expand Up @@ -71,10 +72,16 @@ def load_composable_node_param(param_path):
random_downsample_component,
]

target_container = (
"/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container"
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("pointcloud_container_name")
)

load_composable_nodes = LoadComposableNodes(
condition=LaunchConfigurationNotEquals("container", ""),
condition=LaunchConfigurationNotEquals(target_container, ""),
composable_node_descriptions=composable_nodes,
target_container=LaunchConfiguration("container"),
target_container=target_container,
)

return [load_composable_nodes]
Expand Down Expand Up @@ -117,11 +124,13 @@ def add_launch_arg(name: str, default_value=None, description=None):
"path to the parameter file of random_downsample_filter",
)
add_launch_arg("use_intra_process", "true", "use ROS2 component container communication")
add_launch_arg("use_pointcloud_container", "True", "use pointcloud container")
add_launch_arg(
"container",
"/sensing/lidar/top/pointcloud_preprocessor/velodyne_node_container",
"pointcloud_container_name",
"/pointcloud_container",
"container name",
)

add_launch_arg(
"output/pointcloud",
"downsample/pointcloud",
Expand Down
Original file line number Diff line number Diff line change
Expand Up @@ -6,7 +6,8 @@
<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"/>
<arg name="use_pointcloud_container" default="True" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="/pointcloud_container" description="container name"/>

<!-- option -->
<arg name="use_intra_process" default="true" description="use ROS2 component container communication"/>
Expand All @@ -31,7 +32,8 @@
<arg name="tier4_localization_launch_param_path" value="$(var tier4_localization_launch_param_path)"/>
<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_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
<arg name="use_intra_process" value="$(var use_intra_process)"/>
</include>
</group>
Expand Down