ROS 2 Intra-Process Communication Guide 2026
When publisher and subscriber live in the same process, ROS 2 can skip serialization entirely and pass a shared pointer directly — zero-copy, sub-microsecond latency. This guide covers enabling IPC, loaned messages, TypeAdapters, and when to use each.
Why Intra-Process?
| Path | Serialization | Copy | Typical Latency |
|---|---|---|---|
| Inter-process (DDS) | ✅ CDR serialize/deserialize | 2+ copies (loopback) | ~500 µs – 2 ms (1080p) |
| Intra-process (IPC) | ❌ none — shared_ptr pass | 0 copies | ~1–5 µs |
| Loaned message (IPC) | ❌ none — middleware buffer | 0 copies | <1 µs |
Key requirement: Publisher and subscriber must be in the same OS process (same component container, or separate nodes composed with rclcpp::executors in one binary).
Enabling IPC: NodeOptions
Set use_intra_process_comms(true) on the NodeOptions passed to every node in the process:
#include "rclcpp/rclcpp.hpp"
#include "sensor_msgs/msg/image.hpp"
class CameraNode : public rclcpp::Node {
public:
explicit CameraNode(const rclcpp::NodeOptions & options)
: Node("camera_node", options)
{
// Publisher with QoS depth=1 is typical for IPC image pipelines
pub_ = this->create_publisher<sensor_msgs::msg::Image>(
"image_raw", rclcpp::QoS(1));
}
void publish_frame(std::unique_ptr<sensor_msgs::msg::Image> msg) {
// Pass unique_ptr — IPC moves ownership, zero copy
pub_->publish(std::move(msg));
}
private:
rclcpp::Publisher<sensor_msgs::msg::Image>::SharedPtr pub_;
};
// In main() or component container:
rclcpp::NodeOptions options;
options.use_intra_process_comms(true);
auto cam = std::make_shared<CameraNode>(options);
auto proc = std::make_shared<ProcessorNode>(options); // same options
rclcpp::executors::SingleThreadedExecutor exec;
exec.add_node(cam);
exec.add_node(proc);
exec.spin();Important: IPC only activates when publisher and subscriber are in the same process AND both were created with use_intra_process_comms(true) AND the QoS history depth is 1 (or both use KEEP_LAST with depth=1). If any condition fails, DDS takes over silently.
Subscriber: Receiving a unique_ptr
Subscribe with a unique_ptr callback to receive exclusive ownership (zero-copy, not shared):
class ProcessorNode : public rclcpp::Node {
public:
explicit ProcessorNode(const rclcpp::NodeOptions & options)
: Node("processor_node", options)
{
// unique_ptr callback = exclusive ownership (zero-copy when IPC active)
sub_ = this->create_subscription<sensor_msgs::msg::Image>(
"image_raw",
rclcpp::QoS(1),
[this](std::unique_ptr<sensor_msgs::msg::Image> msg) {
// msg pointer is valid here — no copy was made
process(std::move(msg));
});
}
private:
rclcpp::Subscription<sensor_msgs::msg::Image>::SharedPtr sub_;
void process(std::unique_ptr<sensor_msgs::msg::Image> img) {
// Modify in-place or pass downstream
RCLCPP_INFO(get_logger(), "Got frame %d x %d", img->width, img->height);
}
};shared_ptr vs unique_ptr callbacks: Use unique_ptr for the final consumer. Use const shared_ptr& when multiple subscribers share the same message (IPC will share the pointer, still zero-copy on the message data).
Loaned Messages (rclcpp::LoanedMessage)
Loaned messages let the middleware allocate the message buffer directly in its own memory (e.g., shared memory segment), avoiding any heap allocation on the publisher side:
auto pub = node->create_publisher<sensor_msgs::msg::Image>("image_raw", 1);
// Borrow a buffer from the middleware
auto loaned_msg = pub->borrow_loaned_message();
// Fill in-place (no copy — we're writing directly into MW memory)
loaned_msg.get().width = 1920;
loaned_msg.get().height = 1080;
loaned_msg.get().encoding = "bgr8";
loaned_msg.get().data.resize(1920 * 1080 * 3);
capture_frame(loaned_msg.get().data.data()); // your camera call
// Publish — loaned_msg is consumed and invalidated
pub->publish(std::move(loaned_msg));Note: Loaned messages require a middleware that supports them (e.g., Eclipse Cyclone DDS or iceoryx). They are silently downgraded to normal allocation if the RMW doesn't support loans. Check with: ros2 doctor --report | grep -A5 middleware
TypeAdapter: Publish cv::Mat Directly
TypeAdapters (ROS 2 Humble+) let you publish native types (cv::Mat, Eigen::MatrixXd) without converting to a ROS message type in user code:
#include "rclcpp/type_adapter.hpp"
#include "sensor_msgs/msg/image.hpp"
#include <opencv2/opencv.hpp>
// Define the adapter (once, in a header)
template<>
struct rclcpp::TypeAdapter<cv::Mat, sensor_msgs::msg::Image> {
using is_specialized = std::true_type;
using custom_type = cv::Mat;
using ros_message_type = sensor_msgs::msg::Image;
static void convert_to_ros_message(
const custom_type & source, ros_message_type & destination)
{
destination.encoding = "bgr8";
destination.width = source.cols;
destination.height = source.rows;
destination.step = source.step;
destination.data.assign(source.datastart, source.dataend);
}
static void convert_to_custom(
const ros_message_type & source, custom_type & destination)
{
destination = cv::Mat(source.height, source.width, CV_8UC3,
const_cast<uint8_t*>(source.data.data()), source.step).clone();
}
};
// In your node:
using ImageAdapter = rclcpp::adapt_type<cv::Mat>::as<sensor_msgs::msg::Image>;
auto pub = node->create_publisher<ImageAdapter>("image_raw", 10);
cv::Mat frame = cv::imread("test.png");
pub->publish(frame); // conversion happens automatically, IPC skips itComponent Container Launch
The standard way to compose multiple nodes in one process for IPC is the component container:
# Python launch file
from launch import LaunchDescription
from launch_ros.actions import ComposableNodeContainer
from launch_ros.descriptions import ComposableNode
def generate_launch_description():
container = ComposableNodeContainer(
name="image_container",
namespace="",
package="rclcpp_components",
executable="component_container",
composable_node_descriptions=[
ComposableNode(
package="my_camera_pkg",
plugin="my_camera::CameraNode",
name="camera_node",
extra_arguments=[{"use_intra_process_comms": True}],
),
ComposableNode(
package="my_proc_pkg",
plugin="my_proc::ProcessorNode",
name="processor_node",
extra_arguments=[{"use_intra_process_comms": True}],
),
],
output="screen",
)
return LaunchDescription([container])Verify IPC Is Actually Active
# Should show "intraprocess" connection type ros2 topic echo --no-arr /image_raw --once 2>&1 | grep -i intra
If you see normal CDR data, IPC failed — check QoS depth and node options.
# Measure round-trip latency IPC vs inter-process ros2 run demo_nodes_cpp talker --ros-args -p use_intra_process_comms:=true ros2 run rclcpp_components component_container ros2 component load /ComponentManager demo_nodes_cpp Talker
# Check if loaned messages are supported by your RMW ros2 doctor --report | grep loan
CycloneDDS supports loans via iceoryx plugin. FastDDS supports them since 2.6.
Next Steps
- → ROS 2 image_transport guide — compress images for inter-process publication once you leave the IPC zone
- → ROS 2 message_filters guide — synchronize multiple IPC topics without copy overhead
- → ROS 2 composition guide — load and unload component nodes at runtime inside the container