diff --git a/aip_xx1_launch/launch/lidar.launch.xml b/aip_xx1_launch/launch/lidar.launch.xml index 77ec443f..8a8964c7 100644 --- a/aip_xx1_launch/launch/lidar.launch.xml +++ b/aip_xx1_launch/launch/lidar.launch.xml @@ -5,7 +5,7 @@ - + @@ -40,7 +40,6 @@ - @@ -58,7 +57,6 @@ - @@ -76,7 +74,6 @@ - @@ -105,8 +102,8 @@ - - + + diff --git a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py index a2a0fd45..4be97696 100644 --- a/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py +++ b/aip_xx1_launch/launch/pointcloud_preprocessor.launch.py @@ -57,32 +57,25 @@ def launch_setup(context, *args, **kwargs): extra_arguments=[{"use_intra_process_comms": LaunchConfiguration("use_intra_process")}], ) - glog_component = ComposableNode( - package="glog_component", - plugin="GlogComponent", - name="glog_component", - ) - # 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=[glog_component], - 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 concat_loader = LoadComposableNodes( - composable_node_descriptions=[concat_component, glog_component], + composable_node_descriptions=[concat_component], target_container=target_container, condition=IfCondition(LaunchConfiguration("use_concat_filter")), ) @@ -99,8 +92,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/common_sensor_launch/launch/hesai_XT32.launch.xml b/common_sensor_launch/launch/hesai_XT32.launch.xml index ff41b367..56587f72 100644 --- a/common_sensor_launch/launch/hesai_XT32.launch.xml +++ b/common_sensor_launch/launch/hesai_XT32.launch.xml @@ -14,7 +14,6 @@ - @@ -32,7 +31,6 @@ - diff --git a/common_sensor_launch/launch/nebula_node_container.launch.py b/common_sensor_launch/launch/nebula_node_container.launch.py index a79681b8..d1385bce 100644 --- a/common_sensor_launch/launch/nebula_node_container.launch.py +++ b/common_sensor_launch/launch/nebula_node_container.launch.py @@ -200,16 +200,9 @@ def create_parameter_dict(*args): 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,7 +274,6 @@ 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") set_container_executable = SetLaunchConfiguration( diff --git a/common_sensor_launch/launch/velodyne_VLP16.launch.xml b/common_sensor_launch/launch/velodyne_VLP16.launch.xml index f374e1db..faa32305 100644 --- a/common_sensor_launch/launch/velodyne_VLP16.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLP16.launch.xml @@ -15,7 +15,6 @@ - @@ -34,7 +33,6 @@ - diff --git a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml index 531efd4d..c3db6428 100644 --- a/common_sensor_launch/launch/velodyne_VLP32C.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLP32C.launch.xml @@ -15,7 +15,6 @@ - @@ -34,7 +33,6 @@ - diff --git a/common_sensor_launch/launch/velodyne_VLS128.launch.xml b/common_sensor_launch/launch/velodyne_VLS128.launch.xml index 89305c79..f1d32469 100644 --- a/common_sensor_launch/launch/velodyne_VLS128.launch.xml +++ b/common_sensor_launch/launch/velodyne_VLS128.launch.xml @@ -15,7 +15,6 @@ - @@ -34,7 +33,6 @@ -