diff --git a/sample_sensor_kit_launch/launch/lidar.launch.xml b/sample_sensor_kit_launch/launch/lidar.launch.xml index 7b75c770..8ee44365 100644 --- a/sample_sensor_kit_launch/launch/lidar.launch.xml +++ b/sample_sensor_kit_launch/launch/lidar.launch.xml @@ -4,7 +4,7 @@ - + @@ -21,7 +21,6 @@ - @@ -39,7 +38,6 @@ - @@ -57,7 +55,6 @@ - @@ -75,7 +72,6 @@ - @@ -84,8 +80,8 @@ - - + + diff --git a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py index 420854dc..e29aa788 100644 --- a/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py +++ b/sample_sensor_kit_launch/launch/pointcloud_preprocessor.launch.py @@ -51,19 +51,19 @@ def launch_setup(context, *args, **kwargs): # set container to run all required components in the same process container = ComposableNodeContainer( - name=LaunchConfiguration("container_name"), + name=LaunchConfiguration("individual_container_name"), namespace="", package="rclcpp_components", executable=LaunchConfiguration("container_executable"), composable_node_descriptions=[], - condition=UnlessCondition(LaunchConfiguration("use_pointcloud_container")), + condition=UnlessCondition(LaunchConfiguration("include_concat_node_in_pointcloud_container")), output="screen", ) target_container = ( container - if UnlessCondition(LaunchConfiguration("use_pointcloud_container")).evaluate(context) - else LaunchConfiguration("container_name") + if UnlessCondition(LaunchConfiguration("include_concat_node_in_pointcloud_container")).evaluate(context) + else LaunchConfiguration("pointcloud_container_name") ) # load concat or passthrough filter @@ -85,8 +85,9 @@ 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("container_name", "pointcloud_preprocessor_container") + add_launch_arg("include_concat_node_in_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/sample_sensor_kit_launch/launch/sensing.launch.xml b/sample_sensor_kit_launch/launch/sensing.launch.xml index 9b40ee8a..c4c762e4 100644 --- a/sample_sensor_kit_launch/launch/sensing.launch.xml +++ b/sample_sensor_kit_launch/launch/sensing.launch.xml @@ -1,7 +1,7 @@ - + @@ -10,7 +10,7 @@ - +