Skip to content

Commit

Permalink
feat!: replace use_pointcloud_container
Browse files Browse the repository at this point in the history
Signed-off-by: kminoda <[email protected]>
  • Loading branch information
kminoda committed Jan 16, 2024
1 parent 5ccd754 commit f7b8ca0
Show file tree
Hide file tree
Showing 3 changed files with 12 additions and 15 deletions.
10 changes: 3 additions & 7 deletions sample_sensor_kit_launch/launch/lidar.launch.xml
Original file line number Diff line number Diff line change
Expand Up @@ -4,7 +4,7 @@
<arg name="use_concat_filter" default="true"/>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>
<arg name="vehicle_mirror_param_file"/>
<arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="include_concat_node_in_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>

<group>
Expand All @@ -21,7 +21,6 @@
<arg name="scan_phase" value="300.0"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand All @@ -39,7 +38,6 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand All @@ -57,7 +55,6 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand All @@ -75,7 +72,6 @@
<arg name="cloud_max_angle" value="60"/>
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
Expand All @@ -84,8 +80,8 @@
<arg name="base_frame" value="base_link"/>
<arg name="use_intra_process" value="true"/>
<arg name="use_multithread" value="true"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="container_name" value="$(var pointcloud_container_name)"/>
<arg name="include_concat_node_in_pointcloud_container" value="$(var include_concat_node_in_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>
</group>
</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -51,19 +51,19 @@ def launch_setup(context, *args, **kwargs):

# set container to run all required components in the same process
container = ComposableNodeContainer(
name=LaunchConfiguration("container_name"),
name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[],
condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
condition=UnlessCondition(LaunchConfiguration("include_concat_node_in_pointcloud_container")),
output="screen",
)

target_container = (
container
if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("container_name")
if UnlessCondition(LaunchConfiguration("include_concat_node_in_pointcloud_container")).evaluate(context)
else LaunchConfiguration("pointcloud_container_name")
)

# load concat or passthrough filter
Expand All @@ -85,8 +85,9 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("base_frame", "base_link")
add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "False")
add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("container_name", "pointcloud_preprocessor_container")
add_launch_arg("include_concat_node_in_pointcloud_container", "False")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")

set_container_executable = SetLaunchConfiguration(
"container_executable",
Expand Down
4 changes: 2 additions & 2 deletions sample_sensor_kit_launch/launch/sensing.launch.xml
Original file line number Diff line number Diff line change
@@ -1,7 +1,7 @@
<launch>
<arg name="launch_driver" default="true" description="do launch driver"/>
<arg name="vehicle_mirror_param_file" description="path to the file of vehicle mirror position yaml"/>
<arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="include_concat_node_in_pointcloud_container" default="false" description="launch pointcloud container"/>
<arg name="pointcloud_container_name" default="pointcloud_container"/>
<arg name="vehicle_id" default="$(env VEHICLE_ID default)"/>

Expand All @@ -10,7 +10,7 @@
<include file="$(find-pkg-share sample_sensor_kit_launch)/launch/lidar.launch.xml">
<arg name="launch_driver" value="$(var launch_driver)"/>
<arg name="vehicle_mirror_param_file" value="$(var vehicle_mirror_param_file)"/>
<arg name="use_pointcloud_container" value="$(var use_pointcloud_container)"/>
<arg name="include_concat_node_in_pointcloud_container" value="$(var include_concat_node_in_pointcloud_container)"/>
<arg name="pointcloud_container_name" value="$(var pointcloud_container_name)"/>
</include>

Expand Down

0 comments on commit f7b8ca0

Please sign in to comment.