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 @@
-
@@ -57,7 +56,6 @@
-
diff --git a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
index 8d9892b0..ff012c8a 100644
--- a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
@@ -19,7 +19,6 @@
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
-from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
@@ -50,30 +49,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 +67,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 @@
-
@@ -12,7 +11,6 @@
-
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 @@
-
@@ -189,7 +188,6 @@
-
diff --git a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
index 6aa031b0..6d435dee 100644
--- a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
@@ -20,7 +20,6 @@
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
-from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
@@ -56,31 +55,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 +74,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 @@
-
@@ -12,7 +11,6 @@
-
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 @@
-
@@ -101,7 +100,6 @@
-
diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
index e53dfb70..10542a54 100644
--- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
@@ -20,7 +20,6 @@
from launch.conditions import IfCondition
from launch.conditions import UnlessCondition
from launch.substitutions import LaunchConfiguration
-from launch_ros.actions import ComposableNodeContainer
from launch_ros.actions import LoadComposableNodes
from launch_ros.descriptions import ComposableNode
@@ -57,30 +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"),
- 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", "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 @@
-
@@ -13,7 +12,6 @@
-