diff --git a/aip_x1_launch/launch/lidar.launch.xml b/aip_x1_launch/launch/lidar.launch.xml
index 8ced85b6..283b3af0 100644
--- a/aip_x1_launch/launch/lidar.launch.xml
+++ b/aip_x1_launch/launch/lidar.launch.xml
@@ -4,7 +4,7 @@
-
+
@@ -57,7 +57,7 @@
-
+
diff --git a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
index 2cb69ae7..8d9892b0 100644
--- a/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x1_launch/launch/pointcloud_preprocessor.launch.py
@@ -57,17 +57,13 @@ def launch_setup(context, *args, **kwargs):
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[],
- condition=UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
- ),
+ condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)
target_container = (
container
- if UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
- ).evaluate(context)
+ if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("pointcloud_container_name")
)
@@ -89,7 +85,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("include_concat_node_in_pointcloud_container", "False")
+ add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")
diff --git a/aip_x1_launch/launch/sensing.launch.xml b/aip_x1_launch/launch/sensing.launch.xml
index 345eba9e..df8b83b4 100644
--- a/aip_x1_launch/launch/sensing.launch.xml
+++ b/aip_x1_launch/launch/sensing.launch.xml
@@ -2,7 +2,7 @@
-
+
@@ -12,7 +12,7 @@
-
+
diff --git a/aip_x2_launch/launch/lidar.launch.xml b/aip_x2_launch/launch/lidar.launch.xml
index bb874172..5c93fc41 100644
--- a/aip_x2_launch/launch/lidar.launch.xml
+++ b/aip_x2_launch/launch/lidar.launch.xml
@@ -4,7 +4,7 @@
-
+
@@ -189,7 +189,7 @@
-
+
diff --git a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
index 46045756..6aa031b0 100644
--- a/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_x2_launch/launch/pointcloud_preprocessor.launch.py
@@ -63,17 +63,13 @@ def launch_setup(context, *args, **kwargs):
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=[],
- condition=UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
- ),
+ condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)
target_container = (
container
- if UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
- ).evaluate(context)
+ if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
else LaunchConfiguration("pointcloud_container_name")
)
@@ -96,7 +92,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("include_concat_node_in_pointcloud_container", "False")
+ add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")
diff --git a/aip_x2_launch/launch/sensing.launch.xml b/aip_x2_launch/launch/sensing.launch.xml
index e5bd6c41..d64ebe50 100644
--- a/aip_x2_launch/launch/sensing.launch.xml
+++ b/aip_x2_launch/launch/sensing.launch.xml
@@ -2,7 +2,7 @@
-
+
@@ -12,7 +12,7 @@
-
+
diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml
index 41717e34..1b5c075b 100644
--- a/aip_xx1_launch/launch/lidar.launch.xml
+++ b/aip_xx1_launch/launch/lidar.launch.xml
@@ -5,7 +5,7 @@
-
+
@@ -101,7 +101,7 @@
-
+
diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
index fe27fdf7..d039caa3 100644
--- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
+++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py
@@ -64,7 +64,7 @@ def launch_setup(context, *args, **kwargs):
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
condition=UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
+ LaunchConfiguration("use_pointcloud_container")
),
output="screen",
)
@@ -72,7 +72,7 @@ def launch_setup(context, *args, **kwargs):
target_container = (
container
if UnlessCondition(
- LaunchConfiguration("include_concat_node_in_pointcloud_container")
+ LaunchConfiguration("use_pointcloud_container")
).evaluate(context)
else LaunchConfiguration("pointcloud_container_name")
)
@@ -96,7 +96,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("include_concat_node_in_pointcloud_container", "False")
+ add_launch_arg("use_pointcloud_container", "False")
add_launch_arg("pointcloud_container_name", "pointcloud_container")
add_launch_arg("individual_container_name", "concatenate_container")
diff --git a/aip_xx1_launch/launch/sensing.launch.xml b/aip_xx1_launch/launch/sensing.launch.xml
index 279a8bc6..ba6b935c 100644
--- a/aip_xx1_launch/launch/sensing.launch.xml
+++ b/aip_xx1_launch/launch/sensing.launch.xml
@@ -3,7 +3,7 @@
-
+
@@ -13,7 +13,7 @@
-
+