From 09cf8130ecc8832e5e3dfa466e5237d5bdd7bf31 Mon Sep 17 00:00:00 2001 From: kminoda <koji.minoda@tier4.jp> Date: Fri, 19 Jan 2024 11:05:17 +0900 Subject: [PATCH] feat: remove use_pointcloud_container Signed-off-by: kminoda <koji.minoda@tier4.jp> --- aip_x1_launch/launch/lidar.launch.xml | 2 -- .../launch/pointcloud_preprocessor.launch.py | 23 ++----------------- aip_x1_launch/launch/sensing.launch.xml | 2 -- aip_x2_launch/launch/lidar.launch.xml | 2 -- .../launch/pointcloud_preprocessor.launch.py | 23 ++----------------- aip_x2_launch/launch/sensing.launch.xml | 2 -- aip_xx1_launch/launch/lidar.launch.xml | 2 -- .../launch/pointcloud_preprocessor.launch.py | 22 ++---------------- aip_xx1_launch/launch/sensing.launch.xml | 2 -- 9 files changed, 6 insertions(+), 74 deletions(-) diff --git a/aip_x1_launch/launch/lidar.launch.xml b/aip_x1_launch/launch/lidar.launch.xml index a6ceb956..56066df5 100644 --- a/aip_x1_launch/launch/lidar.launch.xml +++ b/aip_x1_launch/launch/lidar.launch.xml @@ -4,7 +4,6 @@ <arg name="use_concat_filter" default="true" /> <arg name="use_radius_search" default="false" /> <arg name="vehicle_mirror_param_file" /> - <arg name="use_pointcloud_container" default="false" description="launch pointcloud container"/> <arg name="pointcloud_container_name" default="pointcloud_container"/> <!-- x1 additional setting --> @@ -57,7 +56,6 @@ <arg name="base_frame" value="base_link" /> <arg name="use_intra_process" value="true" /> <arg name="use_multithread" value="false" /> - <arg name="use_pointcloud_container" value="$(var use_pointcloud_container)" /> <arg name="container_name" value="$(var pointcloud_container_name)"/> </include> diff --git a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py index 8d9892b0..d71e5b97 100644 --- a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py @@ -50,30 +50,13 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("individual_container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[], - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - # load concat or passthrough filter concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], - target_container=target_container, + target_container=LaunchConfiguration("pointcloud_container_name"), ) - return [container, concat_loader] + return [concat_loader] def generate_launch_description(): @@ -85,9 +68,7 @@ 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("pointcloud_container_name", "pointcloud_container") - add_launch_arg("individual_container_name", "concatenate_container") set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/aip_x1_launch/launch/sensing.launch.xml b/aip_x1_launch/launch/sensing.launch.xml index a0fbd4b2..1c294fdf 100644 --- a/aip_x1_launch/launch/sensing.launch.xml +++ b/aip_x1_launch/launch/sensing.launch.xml @@ -2,7 +2,6 @@ <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="pointcloud_container_name" default="pointcloud_container"/> <arg name ="vehicle_id" default="$(env VEHICLE_ID default)" /> @@ -12,7 +11,6 @@ <include file="$(find-pkg-share aip_x1_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="pointcloud_container_name" value="$(var pointcloud_container_name)"/> </include> diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml index c7e21aa1..a1c8f5f6 100644 --- a/aip_x2_launch/launch/lidar.launch.xml +++ b/aip_x2_launch/launch/lidar.launch.xml @@ -4,7 +4,6 @@ <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="pointcloud_container_name" default="pointcloud_container"/> <arg name="dual_return_filter_param_file" default="$(find-pkg-share aip_x2_launch)/config/dual_return_filter.param.yaml"/> @@ -189,7 +188,6 @@ <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="pointcloud_container_name" value="$(var pointcloud_container_name)"/> </include> diff --git a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py index 6aa031b0..a03ae7eb 100644 --- a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py @@ -56,31 +56,14 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("individual_container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - composable_node_descriptions=[], - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - # load concat or passthrough filter concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], - target_container=target_container, + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_concat_filter")), ) - return [container, concat_loader] + return [concat_loader] def generate_launch_description(): @@ -92,9 +75,7 @@ def add_launch_arg(name: str, default_value=None): add_launch_arg("base_frame", "base_link") add_launch_arg("use_multithread", "True") add_launch_arg("use_intra_process", "True") - add_launch_arg("use_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", diff --git a/aip_x2_launch/launch/sensing.launch.xml b/aip_x2_launch/launch/sensing.launch.xml index 51614263..274f6334 100644 --- a/aip_x2_launch/launch/sensing.launch.xml +++ b/aip_x2_launch/launch/sensing.launch.xml @@ -2,7 +2,6 @@ <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="pointcloud_container_name" default="pointcloud_container"/> <arg name ="vehicle_id" default="$(env VEHICLE_ID default)" /> @@ -12,7 +11,6 @@ <include file="$(find-pkg-share aip_x2_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="pointcloud_container_name" value="$(var pointcloud_container_name)"/> </include> diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 0adfe218..417d4972 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -5,7 +5,6 @@ <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="pointcloud_container_name" default="pointcloud_container"/> <group> @@ -101,7 +100,6 @@ <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="pointcloud_container_name" value="$(var pointcloud_container_name)"/> </include> diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index e53dfb70..adfa47a0 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -57,30 +57,14 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - # set container to run all required components in the same process - container = ComposableNodeContainer( - name=LaunchConfiguration("individual_container_name"), - namespace="", - package="rclcpp_components", - executable=LaunchConfiguration("container_executable"), - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), - output="screen", - ) - - target_container = ( - container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("pointcloud_container_name") - ) - # load concat or passthrough filter concat_loader = LoadComposableNodes( composable_node_descriptions=[concat_component], - target_container=target_container, + target_container=LaunchConfiguration("pointcloud_container_name"), condition=IfCondition(LaunchConfiguration("use_concat_filter")), ) - return [container, concat_loader] + return [concat_loader] def generate_launch_description(): @@ -92,9 +76,7 @@ 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("pointcloud_container_name", "pointcloud_container") - add_launch_arg("individual_container_name", "concatenate_container") set_container_executable = SetLaunchConfiguration( "container_executable", diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml index ba6b935c..2128f30a 100644 --- a/aip_xx1_launch/launch/sensing.launch.xml +++ b/aip_xx1_launch/launch/sensing.launch.xml @@ -3,7 +3,6 @@ <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="perception_mode" default="camera_lidar_fusion" description="select perception mode. camera_lidar_fusion, lidar, camera"/> - <arg name="use_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)" /> @@ -13,7 +12,6 @@ <include file="$(find-pkg-share aip_xx1_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="pointcloud_container_name" value="$(var pointcloud_container_name)"/> </include>