diff --git a/launch/tier4_localization_launch/launch/localization.launch.xml b/launch/tier4_localization_launch/launch/localization.launch.xml
index 3fba4bd773e68..f4d6679291849 100644
--- a/launch/tier4_localization_launch/launch/localization.launch.xml
+++ b/launch/tier4_localization_launch/launch/localization.launch.xml
@@ -15,14 +15,15 @@
-
-
+
-
+
+
+
diff --git a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
index 7733b4e3117a1..02c6da20e17da 100644
--- a/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
+++ b/launch/tier4_localization_launch/launch/pose_twist_estimator/pose_twist_estimator.launch.xml
@@ -23,7 +23,9 @@
-
+
+
+
@@ -142,7 +144,9 @@
-
+
+
+
diff --git a/launch/tier4_localization_launch/launch/util/util.launch.py b/launch/tier4_localization_launch/launch/util/util.launch.py
index 1a34429f438ed..22a45fe7b8530 100644
--- a/launch/tier4_localization_launch/launch/util/util.launch.py
+++ b/launch/tier4_localization_launch/launch/util/util.launch.py
@@ -15,8 +15,6 @@
import launch
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
@@ -71,16 +69,9 @@ 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(target_container, ""),
composable_node_descriptions=composable_nodes,
- target_container=target_container,
+ target_container=LaunchConfiguration("lidar_container_name"),
)
return [load_composable_nodes]
@@ -115,11 +106,10 @@ 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 ROS 2 component container communication")
- add_launch_arg("use_pointcloud_container", "True", "use pointcloud container")
add_launch_arg(
- "pointcloud_container_name",
- "/pointcloud_container",
- "container name",
+ "lidar_container_name",
+ "/sensing/lidar/top/pointcloud_preprocessor/pointcloud_container",
+ "container name of main lidar used for localization",
)
add_launch_arg(
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml
index d269144067e0e..4cb648852a03c 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_fusion_based_detection.launch.xml
@@ -6,7 +6,7 @@
-
+
@@ -62,7 +62,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml
index 4838187ef8fbe..ba86bc1e334ff 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/camera_lidar_radar_fusion_based_detection.launch.xml
@@ -6,7 +6,7 @@
-
+
@@ -91,7 +91,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
index 68d5ea944e6cb..885fa80ed7004 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/detection.launch.xml
@@ -8,7 +8,7 @@
-
+
@@ -59,7 +59,7 @@
-
+
@@ -96,7 +96,7 @@
-
+
@@ -111,7 +111,7 @@
-
+
@@ -126,7 +126,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml
index 2c8b7d6581c53..04c4264b70e5f 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_based_detection.launch.xml
@@ -6,7 +6,7 @@
-
+
@@ -25,7 +25,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml
index ed37f6270c913..adedc2312677f 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/lidar_radar_based_detection.launch.xml
@@ -5,7 +5,7 @@
-
+
@@ -23,7 +23,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py
index 93d395ca3e466..1dcb9cfc90daf 100644
--- a/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py
+++ b/launch/tier4_perception_launch/launch/object_recognition/detection/pointcloud_map_filter.launch.py
@@ -141,7 +141,7 @@ def launch_setup(context, *args, **kwargs):
components = []
components.extend(pipeline.create_pipeline())
individual_container = ComposableNodeContainer(
- name=LaunchConfiguration("container_name"),
+ name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
@@ -151,7 +151,7 @@ def launch_setup(context, *args, **kwargs):
)
pointcloud_container_loader = LoadComposableNodes(
composable_node_descriptions=components,
- target_container=LaunchConfiguration("container_name"),
+ target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)
return [individual_container, pointcloud_container_loader]
@@ -168,7 +168,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "True")
add_launch_arg("use_pointcloud_container", "False")
- add_launch_arg("container_name", "pointcloud_map_filter_pipeline_container")
+ add_launch_arg("pointcloud_container_name", "pointcloud_container")
+ add_launch_arg("individual_container_name", "pointcloud_map_filter_container")
add_launch_arg("use_pointcloud_map", "true")
set_container_executable = SetLaunchConfiguration(
"container_executable",
diff --git a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py
index fecdd29bcb7e9..b54172acd4afc 100644
--- a/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py
+++ b/launch/tier4_perception_launch/launch/obstacle_segmentation/ground_segmentation/ground_segmentation.launch.py
@@ -511,7 +511,7 @@ def launch_setup(context, *args, **kwargs):
)
)
individual_container = ComposableNodeContainer(
- name=LaunchConfiguration("container_name"),
+ name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
@@ -521,7 +521,7 @@ def launch_setup(context, *args, **kwargs):
)
pointcloud_container_loader = LoadComposableNodes(
composable_node_descriptions=components,
- target_container=LaunchConfiguration("container_name"),
+ target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)
return [individual_container, pointcloud_container_loader]
@@ -537,7 +537,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "False")
add_launch_arg("use_intra_process", "True")
add_launch_arg("use_pointcloud_container", "False")
- add_launch_arg("container_name", "perception_pipeline_container")
+ add_launch_arg("pointcloud_container_name", "pointcloud_container")
+ add_launch_arg("individual_container_name", "ground_segmentation_container")
add_launch_arg("input/pointcloud", "/sensing/lidar/concatenated/pointcloud")
set_container_executable = SetLaunchConfiguration(
diff --git a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml
index 281a52a85af71..244e0940acb70 100644
--- a/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml
+++ b/launch/tier4_perception_launch/launch/occupancy_grid_map/probabilistic_occupancy_grid_map.launch.xml
@@ -7,7 +7,7 @@
-
+
@@ -24,7 +24,7 @@
-
+
@@ -40,7 +40,7 @@
-
+
@@ -56,7 +56,7 @@
-
+
diff --git a/launch/tier4_perception_launch/launch/perception.launch.xml b/launch/tier4_perception_launch/launch/perception.launch.xml
index 4e9f0daafa736..528038c5158b2 100644
--- a/launch/tier4_perception_launch/launch/perception.launch.xml
+++ b/launch/tier4_perception_launch/launch/perception.launch.xml
@@ -127,7 +127,7 @@
-
+
@@ -142,7 +142,7 @@
-
+
@@ -193,7 +193,7 @@
-
+
diff --git a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py
index b99335b0e09ef..62cfa4bcb5228 100644
--- a/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py
+++ b/perception/probabilistic_occupancy_grid_map/launch/laserscan_based_occupancy_grid_map.launch.py
@@ -115,7 +115,7 @@ def launch_setup(context, *args, **kwargs):
]
occupancy_grid_map_container = ComposableNodeContainer(
- name=LaunchConfiguration("container_name"),
+ name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
@@ -126,7 +126,7 @@ def launch_setup(context, *args, **kwargs):
load_composable_nodes = LoadComposableNodes(
composable_node_descriptions=composable_nodes,
- target_container=LaunchConfiguration("container_name"),
+ target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)
@@ -174,7 +174,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("input_obstacle_pointcloud", "false"),
add_launch_arg("input_obstacle_and_raw_pointcloud", "true"),
add_launch_arg("use_pointcloud_container", "false"),
- add_launch_arg("container_name", "occupancy_grid_map_container"),
+ add_launch_arg("pointcloud_container_name", "pointcloud_container"),
+ add_launch_arg("individual_container_name", "occupancy_grid_map_container"),
set_container_executable,
set_container_mt_executable,
]
diff --git a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py
index 49bf228905dcc..29435c4ea8e24 100644
--- a/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py
+++ b/perception/probabilistic_occupancy_grid_map/launch/pointcloud_based_occupancy_grid_map.launch.py
@@ -64,7 +64,7 @@ def launch_setup(context, *args, **kwargs):
]
occupancy_grid_map_container = ComposableNodeContainer(
- name=LaunchConfiguration("container_name"),
+ name=LaunchConfiguration("individual_container_name"),
namespace="",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
@@ -75,7 +75,7 @@ def launch_setup(context, *args, **kwargs):
load_composable_nodes = LoadComposableNodes(
composable_node_descriptions=composable_nodes,
- target_container=LaunchConfiguration("container_name"),
+ target_container=LaunchConfiguration("pointcloud_container_name"),
condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
)
@@ -103,7 +103,8 @@ def add_launch_arg(name: str, default_value=None):
add_launch_arg("use_multithread", "false"),
add_launch_arg("use_intra_process", "true"),
add_launch_arg("use_pointcloud_container", "false"),
- add_launch_arg("container_name", "occupancy_grid_map_container"),
+ add_launch_arg("pointcloud_container_name", "pointcloud_container"),
+ add_launch_arg("individual_container_name", "occupancy_grid_map_container"),
add_launch_arg("input/obstacle_pointcloud", "no_ground/oneshot/pointcloud"),
add_launch_arg("input/raw_pointcloud", "concatenated/pointcloud"),
add_launch_arg("output", "occupancy_grid"),
diff --git a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md
index e1046fa24719d..6f4d4e22aa26e 100644
--- a/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md
+++ b/perception/probabilistic_occupancy_grid_map/synchronized_grid_map_fusion.md
@@ -105,7 +105,7 @@ You need to generate OGMs in each sensor frame before achieving grid map fusion.
-
+
@@ -146,7 +146,7 @@ You can include this launch file like the following.
-
+