ROS 2 composition and ZED ROS 2 Wrapper

ROS 2 expanded the concept of nodelet from ROS 1 replacing nodelets with components and introducing the new concept of “Composition”.

Each node can be written as a “Component” which is a shared library loaded at runtime.

This tutorial explains how to:

  • run multiple nodes in separate processes with the benefits of process/fault isolation as well as easier debugging of individual nodes
  • run multiple nodes in a single process with lower overhead and optionally more efficient communication (see Intra Process Communication).

The launch file of the zed_wrapper package is designed to take advantage of both.

Run one ZED camera component in a single process #

You can run a ZED Node in a single process by using the default launch command zed_camera.launch.py as it is:

ros2 launch zed_wrapper zed_camera.launch.py camera_model:=<camera_model>

the launch file creates a ROS 2 Container process called zed_container:

container_name_val='zed_container'
        distro = os.environ['ROS_DISTRO']
        if distro == 'foxy':
            # Foxy does not support the isolated mode
            container_exec='component_container'
        else:
            container_exec='component_container_isolated'
        
        zed_container = ComposableNodeContainer(
                name=container_name_val,
                namespace=namespace_val,
                package='rclcpp_components',
                executable=container_exec,
                arguments=['--ros-args', '--log-level', 'info'],
                output='screen',
        )

then it loads a stereolabs::ZedCamera or stereolabs::ZedCameraOne into it:

# ZED Wrapper component
    if( camera_model_val=='zed' or
        camera_model_val=='zedm' or
        camera_model_val=='zed2' or
        camera_model_val=='zed2i' or
        camera_model_val=='zedx' or
        camera_model_val=='zedxm' or
        camera_model_val=='virtual'):
        zed_wrapper_component = ComposableNode(
            package='zed_components',
            namespace=namespace_val,
            plugin='stereolabs::ZedCamera',
            name=node_name_val,
            parameters=node_parameters,
            extra_arguments=[{'use_intra_process_comms': True}]
        )
    else: # 'zedxonegs' or 'zedxone4k')
        zed_wrapper_component = ComposableNode(
            package='zed_components',
            namespace=namespace_val,
            plugin='stereolabs::ZedCameraOne',
            name=node_name_val,
            parameters=node_parameters,
            extra_arguments=[{'use_intra_process_comms': True}]
        )
    
    full_container_name = '/' + namespace_val + '/' + container_name_val
    info = '* Loading ZED node: ' + node_name_val + ' in container: ' + full_container_name
    return_array.append(LogInfo(msg=TextSubstitution(text=info)))
    
    load_composable_node = LoadComposableNodes(
        target_container=full_container_name,
        composable_node_descriptions=[zed_wrapper_component]
    )

Compose multiple node components in a single process to leverage IPC #

Intra Process Communication (IPC) is an advanced concept of ROS 2 that allows to optimize the performance of nodes running on the same machine.

The ZED IPC tutorial #

The ZED IPC tutorial demonstrates how to leverage ROS 2 Composition and Intra-Process Communication to create a new node component that subscribes to point cloud topics published by all ZED Camera node components running within the same process.

The tutorial guides you through the creation of a new launch file. This launch file utilizes the launch file of the ZED Multi-Camera tutorial to:

  1. Start multiple ZED nodes within a single process.
  2. Load a new node component that subscribes to the point cloud topics.
  3. Achieve zero-copy data transfer for efficient data exchange.

This approach enhances performance and reduces resource consumption by minimizing data copying between nodes within the same process.

The zed_ipc.launch.py launch File #

The zed_ipc.launch.py launch file is designed to facilitate the setup of multiple ZED Camera nodes within a single process, along with a custom node component that subscribes to their point cloud topics. This launch file ensures efficient intra-process communication by leveraging zero-copy data transfer.

Key Features #
  • Multiple ZED Nodes: Initializes and manages multiple ZED Camera nodes within the same process to capture point cloud data.
  • Custom Subscriber Node: Loads a custom node component that subscribes to the point cloud topics published by the ZED Camera nodes.
  • Zero-Copy Data Transfer: Utilizes ROS 2’s intra-process communication capabilities to achieve zero-copy data transfer, enhancing performance and reducing resource usage.
Usage #

To use the zed_ipc.launch.py launch file, execute the following command:

ros2 launch zed_ipc zed_ipc.launch.py cam_names:=[<camera_name_array>] cam_models:=[<camera_model_array>] cam_serials:=[<camera_serial_array>]

This command will start the launch file, initializing the ZED Camera nodes and the custom subscriber node within the same process.

The code explained #

First step: create a ROS 2 Container and load the two ZED camera components nodes inside it. Here we use the multi-camera launch file described in the multi-camera tutorial.

    # Call the multi-camera launch file
    multi_camera_launch_file = os.path.join(
        get_package_share_directory('zed_multi_camera'),
        'launch',
        'zed_multi_camera.launch.py'
    )
    zed_multi_camera = IncludeLaunchDescription(
        launch_description_source=PythonLaunchDescriptionSource(multi_camera_launch_file),
        launch_arguments={
            'cam_names': names,
            'cam_models': models,
            'cam_serials': serials,
            'disable_tf': disable_tf
        }.items()
    )
    actions.append(zed_multi_camera)

Second step: remap the topic names. The demo node that receives the Point Cloud messages subscribes to generic pointcloud_X topic names. The launch file must create a correct remapping between pointcloud_X and each ZED node Point Cloud topic name /zed_multi/<camera_name/point_cloud/cloud_registered.

    # Create topic remappings for the point cloud node
    remappings = []
    name_array = parse_array_param(names.perform(context))
    for i in range(cam_count):
        base_topic = 'pointcloud_' + str(i)
        remap = '/zed_multi/' + name_array[i] + '/point_cloud/cloud_registered'
        remapping = (base_topic, remap)
        remappings.append(remapping)

Third step: create the demo component node that subscribes to the Point Cloud topics and processes the relative messages.

    pc_node = ComposableNode(
        package='zed_ipc',
        plugin='stereolabs::PointCloudComponent',
        name='ipc_point_cloud',
        namespace='zed_multi',
        parameters=[{
            'cam_count': cam_count
        }],
        remappings=remappings,
        extra_arguments=[{'use_intra_process_comms': True}]
    )

Final step: load the Point Cloud component node in the existing ZED Container process to leverage Intra Process Communication.

    load_pc_node = LoadComposableNodes(
        composable_node_descriptions=[pc_node],
        target_container='/zed_multi/zed_multi_container'
    )
    actions.append(load_pc_node)

You can verify that all the nodes are now running into the same container process by using the command ros2 component list.

Example #

Here’s an example for two ZED X cameras named zedx_front and zedx_rear:

  • Launch command:
ros2 launch zed_ipc zed_ipc.launch.py cam_names:=[zedx_front,zedx_rear] cam_models:=[zedx,zedx] cam_serials:=[xxxxxxxxx,yyyyyyyy]
  • Running check:
$ ros2 component list
/zed_multi/zed_multi_container
  1  /zed_multi/zedx_front
  2  /zed_multi/zedx_rear
  3  /zed_multi/ipc_point_cloud