ROS 2 Composition and ZED ROS 2 Wrapper

Open in ClaudeOpen in ChatGPT

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:

Python
1container_name_val='zed_container'
2 distro = os.environ['ROS_DISTRO']
3 if distro == 'foxy':
4 # Foxy does not support the isolated mode
5 container_exec='component_container'
6 else:
7 container_exec='component_container_isolated'
8
9 zed_container = ComposableNodeContainer(
10 name=container_name_val,
11 namespace=namespace_val,
12 package='rclcpp_components',
13 executable=container_exec,
14 arguments=['--ros-args', '--log-level', 'info'],
15 output='screen',
16 )

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

Python
1# ZED Wrapper component
2 if( camera_model_val=='zed' or
3 camera_model_val=='zedm' or
4 camera_model_val=='zed2' or
5 camera_model_val=='zed2i' or
6 camera_model_val=='zedx' or
7 camera_model_val=='zedxm' or
8 camera_model_val=='virtual'):
9 zed_wrapper_component = ComposableNode(
10 package='zed_components',
11 namespace=namespace_val,
12 plugin='stereolabs::ZedCamera',
13 name=node_name_val,
14 parameters=node_parameters,
15 extra_arguments=[{'use_intra_process_comms': True}]
16 )
17 else: # 'zedxonegs' or 'zedxone4k')
18 zed_wrapper_component = ComposableNode(
19 package='zed_components',
20 namespace=namespace_val,
21 plugin='stereolabs::ZedCameraOne',
22 name=node_name_val,
23 parameters=node_parameters,
24 extra_arguments=[{'use_intra_process_comms': True}]
25 )
26
27 full_container_name = '/' + namespace_val + '/' + container_name_val
28 info = '* Loading ZED node: ' + node_name_val + ' in container: ' + full_container_name
29 return_array.append(LogInfo(msg=TextSubstitution(text=info)))
30
31 load_composable_node = LoadComposableNodes(
32 target_container=full_container_name,
33 composable_node_descriptions=[zed_wrapper_component]
34 )

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.

Python
1 # Call the multi-camera launch file
2 multi_camera_launch_file = os.path.join(
3 get_package_share_directory('zed_multi_camera'),
4 'launch',
5 'zed_multi_camera.launch.py'
6 )
7 zed_multi_camera = IncludeLaunchDescription(
8 launch_description_source=PythonLaunchDescriptionSource(multi_camera_launch_file),
9 launch_arguments={
10 'cam_names': names,
11 'cam_models': models,
12 'cam_serials': serials,
13 'disable_tf': disable_tf
14 }.items()
15 )
16 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.

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

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

Python
1 pc_node = ComposableNode(
2 package='zed_ipc',
3 plugin='stereolabs::PointCloudComponent',
4 name='ipc_point_cloud',
5 namespace='zed_multi',
6 parameters=[{
7 'cam_count': cam_count
8 }],
9 remappings=remappings,
10 extra_arguments=[{'use_intra_process_comms': True}]
11 )

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

Python
1 load_pc_node = LoadComposableNodes(
2 composable_node_descriptions=[pc_node],
3 target_container='/zed_multi/zed_multi_container'
4 )
5 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