Hi all, I am working on Investigate adding in explicit IPC for Nav2 nodes again this week. I have some findings that I think would be worth sharing here.
Minimal Example
To demonstrate the behavior of intra-process communication and subscription callback signatures, I created a minimal example based on the ROS 2 demos and uploaded it in my fork: demos/src/two_node_pipeline/two_node_pipeline.cpp at IPC · mini-1235/demos · GitHub
The setup is simple:
- 1 publisher node
- publishes using a
std::unique_ptr
- publishes using a
- 2 consumer nodes
- Each consumer contains 3 subscriptions to the same topic
- They are running in the same executor
The only variables being changed between runs are:
- use_intra_process_comms: enabled / disabled for different nodes
- Subscription callback type (
SharedPtrvsConstSharedPtrvsconst Msg &)
Result Summary
| Subscription Type | Subscription Type | Copies |
|---|---|---|
SharedPtr |
IPC disabled for all nodes | 1 |
SharedPtr |
IPC enabled for all nodes | n-1 for n subscribers |
SharedPtr |
Producer intra, consumers mixed intra + inter | 1 (inter) + n-1(intra) |
SharedPtr |
Producer inter, consumers intra | 1 |
ConstSharedPtr |
IPC disabled for all nodes | 1 |
ConstSharedPtr |
IPC enabled for all nodes | 0 |
ConstSharedPtr |
Producer intra, consumers mixed intra + inter | 1 |
ConstSharedPtr |
Producer inter, consumers intra | 1 |
const Msg & |
IPC disabled for all nodes | 1 |
const Msg & |
IPC enabled for all nodes | n-1 for n subscribers |
const Msg & |
Producer intra, consumers mixed intra + inter | 1 (inter) + n-1(intra) |
const Msg & |
Producer inter, consumers intra | 1 |
As shown in the table above, SharedPtr , ConstSharedPtr , and const Msg & behave differently when Intra-process communication is enabled: ConstSharedPtr can achieve zero-copy delivery, whereas SharedPtr and Const Msg & may introduce additional copies. It is also worth noting that SharedPtr is actually deprecated, see Deprecated subscription callback signatures are still compiling · Issue #2972 · ros2/rclcpp · GitHub
For reference, I will also put the link of the design document here.
Testing with Nav2
In addition to the minimal example, I also tested different combinations of IPC settings, RMW implementations, and subscription callback types in a full Nav2 setup.
Test Environment
OS: Ubuntu 24.04.3 LTS (x86_64)
Kernel: 6.8.0-88-generic
CPU: Intel i7-12700H (20 cores)
GPU: Intel Iris Xe + NVIDIA RTX 3050 Ti Mobile
Memory: 32 GB
Setup A: Full Simulation (With RViz and Gazebo enabled)
- launch command:
ros2 launch nav2_bringup tb4_simulation_launch.py - Baseline measurements correspond to the latest rolling commit at the time of testing.
- The CPU Usage reported here refers specifically to the nav2_container process
CPU Usage Result
| Middleware | Configuration | CPU Usage (%) |
|---|---|---|
| Zenoh | Baseline | 4.5% |
| Zenoh | IPC enabled (with SharedPtr used in most of the stack) | 6.0% |
| Zenoh | IPC + ConstSharedPtr | 5.8% |
| CycloneDDS | Baseline | 18.3% |
| CycloneDDS | IPC enabled (with SharedPtr used in most of the stack) | 17.8% |
| CycloneDDS | IPC + ConstSharedPtr | 16.1% |
| FastDDS | Baseline | 6.8% |
| FastDDS | IPC enabled (with SharedPtr used in most of the stack) | 7.8% |
| FastDDS | IPC + ConstSharedPtr | 7.8% |
As shown in the table, enabling intra-process communication leads to increased CPU usage for FastDDS and Zenoh, while CycloneDDS shows a reduction in CPU usage.
Setup B: Loopback Simulation (With RViz and Gazebo disabled)
- launch command:
ros2 launch nav2_bringup tb4_loopback_simulation_launch.py use_rviz:=false - Baseline measurements correspond to the latest rolling commit at the time of testing
- The CPU Usage reported here refers specifically to the nav2_container process
CPU Usage Result
| Middleware | Configuration | CPU Usage (%) |
|---|---|---|
| Zenoh | Baseline | 0.8% |
| Zenoh | IPC enabled (with SharedPtr used in most of the stack) | 0.8% |
| Zenoh | IPC + ConstSharedPtr | 0.8% |
| CycloneDDS | Baseline | 1.6% |
| CycloneDDS | IPC enabled (with SharedPtr used in most of the stack) | 1.7% |
| CycloneDDS | IPC + ConstSharedPtr | 1.7% |
| FastDDS | Baseline | 1.2% |
| FastDDS | IPC enabled (with SharedPtr used in most of the stack) | 1.2% |
| FastDDS | IPC + ConstSharedPtr | 1.2% |
Under the loopback simulation with RViz and Gazebo disabled, CPU usage remains effectively unchanged across different IPC and subscription callback settings for all three middleware.
Discussion
Based on the first experiments above, I would expect some performance gains when enabling intra-process communication and using ConstSharedPtr . However, this expectation was not met when testing in a full Nav2 setup, and in the full simulation setup we even observed performance drop with FastDDS and Zenoh.
Therefore, I would like to invite community members as well as the ros2 team to share their experiences and insights on these results.









