For experienced robotics engineers, the challenge of handling high-bandwidth sensor data in a real-time system is a familiar one. While ROS 2 has brought significant improvements, the fundamental problem of efficiently moving massive sensor_msgs/PointCloud2 messages between nodes remains a critical bottleneck. Serialization and deserialization overhead can consume valuable CPU cycles, introduce unacceptable latency, and compromise the determinism of your entire system.
At Ouster, we believe a great sensor deserves an equally great software experience. That’s why our official ROS 2 driver is not a mere ROS 1 port. It's an actively maintained, comprehensive package designed from the ground up to address the core challenges of high-performance robotics. Our approach focuses on two key architectural pillars: a component-based design and a robust implementation of ROS 2's Node Lifecycle Management.
How component-based architecture reduces serialization overhead
In ROS 2, the component-based architecture and Intra-Process Communication (IPC) are game-changers for performance-critical applications like lidar processing. They directly address the massive overhead of data serialization and deserialization that was a bottleneck in ROS 1.
The problem: A "Before" picture with separate nodes
Imagine a traditional ROS 1 or a non-component ROS 2 system for processing Ouster lidar data. You would likely have at least two separate nodes: a ouster_driver node to talk to the physical lidar sensor, and a perception_filter node to process the data for the navigation stack.
With an Ouster lidar generating several megabytes of data per frame, every single frame would undergo a costly process:
The ouster_driver node constructs a sensor_msgs/msg/PointCloud2 message.
The message is serialized into a byte stream.
This byte stream is sent across the network via the ROS 2 middleware (DDS).
The perception_filter node receives the byte stream.
The byte stream is deserialized back into a message object.
This CPU-intensive process is repeated for every single frame, introducing significant latency and consuming resources that could be used for more critical tasks like SLAM or perception.
The Solution: The "After" picture with a component manager
The Ouster ROS 2 driver is designed as a set of components that can be loaded into a single process, managed by a ComponentManager. This allows for zero-copy data transfer through Intra-Process Communication (IPC).
Here's how this changes the data flow:
The OusterDriver component receives raw data.
It processes the data and constructs a sensor_msgs/msg/PointCloud2 message in the shared process memory.
Instead of serializing the data, the component's publisher sends a pointer or reference to the message in memory.
The PointCloudProcessor component's subscriber receives this pointer.
The PerceptionFilter can immediately access the message data directly from memory without any serialization or deserialization.
This completely bypasses the most expensive part of the process, drastically reducing CPU usage and message latency.
Illustrative Code Snippet (Conceptual)
Imagine you have the following component that consumes PointCloud2 message data from the Ouster driver and performs filtering for the perception pipeline:
<perception_filter.hpp>
#include "rclcpp/rclcpp.hpp"
#include "rclcpp_components/register_node_macro.hpp"
#include "sensor_msgs/msg/point_cloud2.hpp"
// Perception Filter
class PerceptionFilterComponent : public rclcpp::Node
{
public:
PerceptionFilterComponent() : Node("perception_filter")
{
pc_sub_ = this->create_subscription<sensor_msgs::msg::PointCloud2>(
"/ouster/points",
rclcpp::QoS(10),
std::bind(&PerceptionFilterComponent::filter_callback, this, std::placeholders::_1);
}
private:
void filter_callback(std::unique_ptr<sensor_msgs::msg::PointCloud2> msg)
{
// Process the PointCloud2 message
}
rclcpp::Subscription<sensor_msgs::msg::PointCloud2>::SharedPtr pc_sub_;
};
// Make sure to register the ROS node as a component node
RCLCPP_COMPONENTS_REGISTER_NODE(PerceptionFilterComponent)
Now we want to composite this PerceptionFilter component with the OusterDriver driver component together thus creating a single node and allow Intraprocess Communication. We can achieve this in one of two ways: either by using Static Composition within the code or by using Dynamic Composition with the use of launch files, we’ll only give an example of the dynamic composition here:
Dynamic Composition Example
<launch>
<arg name="sensor_hostname"
description="hostname or IP of the sensor"/>
<node_container pkg="rclcpp_components" exec="component_container_mt" name="os_container" output="screen" namespace="">
<composable_node pkg="ouster_ros" plugin="ouster_ros::OusterDriver" name="os_driver">
<param name="sensor_hostname" value="$(var sensor_hostname)"/>
<!-- Add other OusterDriver params --->
</composable_node>
<composable_node pkg="example" plugin="PerceptionFilter" name="ex_filter">
<!-- Add other PerceptionFilter params --->
</composable_node>
</node_container>
</launch>
In the provided ros2 launch xml file, we first define a container node then added both the OusterDriver and PerceptionFilter components as composable nodes, ROS2 launch command will parse the xml file and create a single node allowing both components to run within the same process without having to statically link the OusterDriver with PerceptionFilter module.
The Power of Control: Ouster’s Lifecycle Management
Performance is nothing without reliability. In a complex, safety-critical system like an autonomous forklift on a factory floor, a lidar sensor cannot simply begin streaming data the moment the robot powers on. It needs a controlled, predictable sequence of startup and shutdown. This is where ROS 2's Node Lifecycle Management becomes absolutely critical.
Our driver fully implements the Node Lifecycle interface, ensuring a robust, deterministic system.
Let's walk through a specific state transition, from a deactivated to an activated state, as managed by a higher-level supervisor node in a real-world application:
Initial State: deactivated
The Ouster driver node is in a stable, dormant state.
The physical sensor is configured but is not streaming data. No data is being published on ROS 2 topics like /ouster/points or /ouster/imu.
All necessary resources (network sockets, threads) have been created but are not yet active or utilized.
The Transition: The on_activate() Callback The supervisor node sends a ros2 lifecycle change_state command to the Ouster driver, triggering its on_activate() callback function. Within this callback, the driver performs the following critical steps in a controlled, sequential manner:
Initiate Sensor Streaming: The driver starts listening to incoming sensor data via UDP and handles the raw packet to the remaining of the pipeline for processing. Packet handling runs separately from data processing to allow unobstructed data flow to the driver.
Enable Data Processing: The driver begins processing the raw imu and lidar packets to produce the PointCloud data and other ROS messages including the IMU.
Activate ROS 2 Publishers: The /ouster/points and /ouster/imu publishers are now enabled and ready to publish messages.
Begin Data Publication: As processed data becomes available, the driver begins pushing messages onto the active ROS 2 topics.
Final State: active
The Ouster driver node is now in the active state.
The physical Ouster lidar is actively streaming data.
Point cloud and IMU data are being continuously published on the ROS 2 topics, and other nodes in the system (e.g., navigation, perception) can now subscribe and receive the live data.
This controlled process prevents race conditions, reduces data loss, and avoids unexpected behavior, providing a layer of safety and reliability for integrating apps.
Engineered for What Matters
At Ouster, our ROS 2 driver is more than just a piece of software to get data from A to B. It’s a core component engineered with the performance, reliability, and control that experienced robotics engineers demand. By leveraging the power of ROS 2’s component-based architecture and node lifecycle management, we provide a solution that is ready for the high-stakes world of autonomous vehicles and industrial robotics.
In our next blog post, we’ll dive deeper into the driver's dynamic configuration and data customization features, showing you how to tailor data streams on-the-fly to optimize your entire robotics stack.
To see our driver in action and learn how it can streamline your development, check out the official Ouster ROS 2 driver on our GitHub repository - https://github.com/ouster-lidar/ouster-ros