diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py
index a79681b8..6dabce18 100644
--- a/common_sensor_launch/launch/nebula_node_container.launch.py
+++ b/common_sensor_launch/launch/nebula_node_container.launch.py
@@ -195,21 +195,14 @@ def create_parameter_dict(*args):
# set container to run all required components in the same process
container = ComposableNodeContainer(
- name=LaunchConfiguration("container_name"),
+ name=LaunchConfiguration("lidar_container_name"),
namespace="pointcloud_preprocessor",
package="rclcpp_components",
executable=LaunchConfiguration("container_executable"),
composable_node_descriptions=nodes,
- condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")),
output="screen",
)
- component_loader = LoadComposableNodes(
- composable_node_descriptions=nodes,
- target_container=LaunchConfiguration("container_name"),
- condition=IfCondition(LaunchConfiguration("use_pointcloud_container")),
- )
-
driver_component = ComposableNode(
package="nebula_ros",
plugin=sensor_make + "HwInterfaceRosWrapper",
@@ -238,19 +231,13 @@ def create_parameter_dict(*args):
],
)
- target_container = (
- container
- if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context)
- else LaunchConfiguration("container_name")
- )
-
driver_component_loader = LoadComposableNodes(
composable_node_descriptions=[driver_component],
- target_container=target_container,
+ target_container=container,
condition=IfCondition(LaunchConfiguration("launch_driver")),
)
- return [container, component_loader, driver_component_loader]
+ return [container, driver_component_loader]
def generate_launch_description():
@@ -287,8 +274,7 @@ def add_launch_arg(name: str, default_value=None, description=None):
)
add_launch_arg("use_multithread", "False", "use multithread")
add_launch_arg("use_intra_process", "False", "use ROS 2 component container communication")
- add_launch_arg("use_pointcloud_container", "false")
- add_launch_arg("container_name", "nebula_node_container")
+ add_launch_arg("lidar_container_name", "nebula_node_container")
set_container_executable = SetLaunchConfiguration(
"container_executable",
diff --git a/common_sensor_launch/launch/velodyne_VLP16.launch.xml b/common_sensor_launch/launch/velodyne_VLP16.launch.xml
index 6197bd14..127709f3 100644
--- a/common_sensor_launch/launch/velodyne_VLP16.launch.xml
+++ b/common_sensor_launch/launch/velodyne_VLP16.launch.xml
@@ -13,8 +13,7 @@
-
-
+
@@ -32,8 +31,7 @@
-
-
+
diff --git a/common_sensor_launch/launch/velodyne_VLS128.launch.xml b/common_sensor_launch/launch/velodyne_VLS128.launch.xml
index 76c24f22..6098e744 100644
--- a/common_sensor_launch/launch/velodyne_VLS128.launch.xml
+++ b/common_sensor_launch/launch/velodyne_VLS128.launch.xml
@@ -13,8 +13,7 @@
-
-
+
@@ -32,8 +31,7 @@
-
-
+
diff --git a/sample_sensor_kit_launch/launch/lidar.launch.xml b/sample_sensor_kit_launch/launch/lidar.launch.xml
index 8ee44365..ff4cf91f 100644
--- a/sample_sensor_kit_launch/launch/lidar.launch.xml
+++ b/sample_sensor_kit_launch/launch/lidar.launch.xml
@@ -21,7 +21,6 @@
-
@@ -38,7 +37,6 @@
-
@@ -55,7 +53,6 @@
-
@@ -72,7 +69,6 @@
-
@@ -80,7 +76,7 @@
-
+
diff --git a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py
index 3427b2d4..0c525ed4 100644
--- a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py
+++ b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py
@@ -64,9 +64,7 @@ def launch_setup(context, *args, **kwargs):
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 +87,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")