Skip to main content
📡 QoSROS 2 · June 2026

ROS 2 QoS Guide 2026

Master ROS 2 Quality of Service: RELIABLE vs BEST_EFFORT, TRANSIENT_LOCAL latched topics, predefined profiles, Deadline policy, and the QoS compatibility table that explains why your subscriber gets no data.

Why QoS Matters

The most common silent bug in ROS 2: a subscriber receives zero messages even though the publisher is running. The cause is almost always a QoS mismatch — publisher and subscriber chose incompatible policies and DDS quietly refuses the connection. ROS 1 had a single transport model; ROS 2 gives you fine-grained control through DDS QoS. Understanding the 5 policies and their compatibility rules prevents hours of debugging.

1

QoS Policy Overview

Quality of Service (QoS) policies control how data is delivered between publishers and subscribers. ROS 2 inherits DDS QoS — more expressive than ROS 1's simple TCP/UDP.

text
ROS 2 QoS Policies (the 5 most important)
═══════════════════════════════════════════════════════
1. RELIABILITY
   RELIABLE    — every message is delivered (retransmit if dropped)
   BEST_EFFORT — fire and forget (faster, but messages may be lost)

2. DURABILITY
   VOLATILE          — subscriber only gets messages published AFTER it subscribes
   TRANSIENT_LOCAL   — publisher keeps last N messages; late subscribers get them
                       (equivalent to ROS 1 "latched" topics)

3. HISTORY
   KEEP_LAST(N)  — buffer the last N messages (default depth=10)
   KEEP_ALL      — buffer everything (bounded by system resources)

4. DEADLINE
   period = Duration(seconds=N)
   Publisher  → must publish at least once every N seconds
   Subscriber → expects a message at least once every N seconds
   Violation triggers on_requested_deadline_missed / on_offered_deadline_missed

5. LIVELINESS
   AUTOMATIC       — node is alive as long as rclpy.ok()
   MANUAL_BY_TOPIC — publisher must call assert_liveliness() periodically
   lease_duration  — how long before considered dead

Rule: Publisher and subscriber QoS MUST be compatible or the connection fails silently.
Compatibility is checked per-policy — see compatibility table below.

QoS incompatibility is silent by default — the subscriber just doesn't receive messages. Use ros2 topic info -v to check QoS on both ends.

2

Reliability — RELIABLE vs BEST_EFFORT

RELIABLE guarantees delivery at the cost of latency. BEST_EFFORT trades guarantees for speed. They are incompatible — publisher and subscriber must match.

python
from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy
from sensor_msgs.msg import Image
from std_msgs.msg import String


# ─── RELIABLE publisher ───────────────────────────────────
# DDS retransmits lost messages until ACK received
# Use for: commands, state changes, configuration, services
reliable_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    history=HistoryPolicy.KEEP_LAST,
    depth=10,
)
self.cmd_pub = self.create_publisher(String, "/cmd", reliable_qos)


# ─── BEST_EFFORT publisher ────────────────────────────────
# No retransmission — ideal for high-rate sensor data
# Use for: camera images, LiDAR, IMU, pointclouds (100+ Hz)
sensor_qos = QoSProfile(
    reliability=ReliabilityPolicy.BEST_EFFORT,
    history=HistoryPolicy.KEEP_LAST,
    depth=1,     # only need the latest frame
)
self.img_pub = self.create_publisher(Image, "/camera/image_raw", sensor_qos)


# ─── Subscriber MUST match publisher reliability ───────────
# RELIABLE pub + BEST_EFFORT sub = INCOMPATIBLE (no data)
# RELIABLE pub + RELIABLE sub   = OK
# BEST_EFFORT pub + RELIABLE sub = INCOMPATIBLE
# BEST_EFFORT pub + BEST_EFFORT sub = OK

# Correct subscriber for BEST_EFFORT publisher:
self.img_sub = self.create_subscription(
    Image, "/camera/image_raw",
    self._image_callback,
    qos_profile=sensor_qos,   # must also be BEST_EFFORT
)

Using RELIABLE for high-rate sensor topics (cameras, LiDAR) can cause queue buildup and latency spikes. Always use BEST_EFFORT for sensor data; RELIABLE for control commands.

3

Durability — VOLATILE vs TRANSIENT_LOCAL

TRANSIENT_LOCAL replaces ROS 1 latched topics. The publisher stores the last N messages and sends them to new subscribers when they connect.

python
from rclpy.qos import QoSProfile, DurabilityPolicy, ReliabilityPolicy, HistoryPolicy, QoSDurabilityPolicy


# ─── TRANSIENT_LOCAL (latched) publisher ──────────────────
# Stores last N messages; new subscribers immediately receive them
# Use for: /map, /robot_description, /tf_static, configuration data
latched_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,   # must be RELIABLE for TRANSIENT_LOCAL
    durability=DurabilityPolicy.TRANSIENT_LOCAL,
    history=HistoryPolicy.KEEP_LAST,
    depth=1,      # keep the last 1 message
)

self.map_pub = self.create_publisher(OccupancyGrid, "/map", latched_qos)
self.map_pub.publish(map_msg)   # new subscribers immediately get this


# ─── VOLATILE publisher (default) ─────────────────────────
# No message storage; subscriber only gets messages published after connecting
volatile_qos = QoSProfile(
    reliability=ReliabilityPolicy.BEST_EFFORT,
    durability=DurabilityPolicy.VOLATILE,
    history=HistoryPolicy.KEEP_LAST,
    depth=10,
)


# ─── Subscriber must match durability to get latched messages ─
# TRANSIENT_LOCAL pub + TRANSIENT_LOCAL sub = late subscriber gets history
# TRANSIENT_LOCAL pub + VOLATILE sub        = late subscriber gets nothing (no match)

latched_sub_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    durability=DurabilityPolicy.TRANSIENT_LOCAL,
    history=HistoryPolicy.KEEP_LAST,
    depth=1,
)
self.map_sub = self.create_subscription(
    OccupancyGrid, "/map", self._map_cb, latched_sub_qos
)

/tf_static uses TRANSIENT_LOCAL — that's why static transforms are available immediately even if the subscriber starts after the publisher. /tf uses BEST_EFFORT VOLATILE.

4

Predefined QoS Profiles

ROS 2 ships with named profiles that match common use cases. Use them instead of constructing QoSProfile manually for standard topics.

python
from rclpy.qos import (
    qos_profile_sensor_data,        # BEST_EFFORT, VOLATILE, KEEP_LAST(5)
    qos_profile_system_default,     # RELIABLE, VOLATILE, KEEP_LAST(10)
    qos_profile_services_default,   # RELIABLE, VOLATILE, KEEP_LAST(10)
    qos_profile_parameters,         # RELIABLE, VOLATILE, KEEP_LAST(1000)
    qos_profile_parameter_events,   # RELIABLE, VOLATILE, KEEP_ALL
)

# Sensor data — high-rate, drop-tolerant
self.lidar_sub = self.create_subscription(
    LaserScan, "/scan", self._scan_cb, qos_profile_sensor_data
)

# System default — general-purpose
self.status_pub = self.create_publisher(
    String, "/status", qos_profile_system_default
)

# ─── C++ equivalents ─────────────────────────────────────
# rclcpp::SensorDataQoS()          → sensor_data
# rclcpp::SystemDefaultsQoS()      → system_default
# rclcpp::ServicesQoS()            → services_default
# rclcpp::ParametersQoS()          → parameters

# Common mistake: mismatched profile
# /scan is published with SensorDataQoS (BEST_EFFORT)
# but subscribed with SystemDefaultsQoS (RELIABLE) → NO DATA
# Fix: use qos_profile_sensor_data on the subscriber too
5

History — KEEP_LAST(N) vs KEEP_ALL

History controls how many messages the publisher buffers for late-joining subscribers (with TRANSIENT_LOCAL) and how many the subscriber queues before the callback drains them.

python
from rclpy.qos import QoSProfile, HistoryPolicy, ReliabilityPolicy


# KEEP_LAST(N) — circular buffer of N messages
# Most common. N = depth parameter.
keep_last_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    history=HistoryPolicy.KEEP_LAST,
    depth=10,       # buffer up to 10 messages before callbacks drain them
)

# KEEP_ALL — no discard, buffer everything
# Risk: unbounded memory growth if callbacks can't keep up
keep_all_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    history=HistoryPolicy.KEEP_ALL,
)

# ─── Choosing depth ───────────────────────────────────────
# depth=1:   sensor streams — only latest matters (camera, IMU)
# depth=10:  default — moderate buffering for bursty publishers
# depth=100: high-rate topics where processing is slower than publishing
# KEEP_ALL:  logging/recording — never drop a message

# ─── Subscriber queue and callback latency ─────────────────
# If publisher publishes at 100 Hz and callback takes 20ms:
#   depth=1  → drops most messages (callback only sees 50 Hz worth)
#   depth=10 → small lag buffer before dropping
# This is INTENDED for sensor data — don't increase depth to "fix" slow callbacks
# Fix: make callbacks faster, or use a separate processing thread
6

Deadline and Liveliness

Deadline detects when a publisher falls silent. Liveliness detects when a node crashes. Both trigger callbacks you can use for fault detection.

python
from rclpy.qos import QoSProfile, ReliabilityPolicy, QoSDeadlinePolicy, QoSLivelinessPolicy
from rclpy.duration import Duration


# ─── Deadline: publisher must publish every N seconds ─────
deadline_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    deadline=Duration(seconds=1, nanoseconds=0),   # expect message every 1s
)

# Subscriber callback when deadline is missed
# Override in your node:
def on_requested_deadline_missed(self, event):
    self.get_logger().warn(
        f"Deadline missed! {event.total_count_change} times"
    )

# Publisher callback when it misses its own deadline
def on_offered_deadline_missed(self, event):
    self.get_logger().error("Publisher missed deadline!")


# ─── Liveliness: detect crashed nodes ────────────────────
liveliness_qos = QoSProfile(
    reliability=ReliabilityPolicy.RELIABLE,
    liveliness=QoSLivelinessPolicy.AUTOMATIC,
    liveliness_lease_duration=Duration(seconds=2),   # declared dead after 2s
)

# Subscriber callback when a publisher goes silent
def on_liveliness_changed(self, event):
    if event.alive_count == 0:
        self.get_logger().error("Publisher died!")
    else:
        self.get_logger().info(f"{event.alive_count} publishers alive")

Deadline and Liveliness are not commonly needed in most robotics applications. Use them for safety-critical systems (e-stop detection, watchdog timers) or distributed multi-robot setups.

7

Checking QoS Compatibility at Runtime

Use ros2 topic info -v to inspect the QoS profile of publishers and subscribers. Incompatible pairs show zero matched connections.

bash
# Show detailed QoS for all publishers and subscribers on a topic
ros2 topic info /scan -v

# Example output:
# Type: sensor_msgs/msg/LaserScan
# Publisher count: 1
# Node name: lidar_node
# Node namespace: /
# Topic type: sensor_msgs/msg/LaserScan
# Endpoint type: PUBLISHER
# GID: ...
# QoS profile:
#   Reliability: BEST_EFFORT
#   Durability: VOLATILE
#   Lifespan: Infinite
#   Deadline: Infinite
#   Liveliness: AUTOMATIC
#   Liveliness lease duration: Infinite
#
# Subscription count: 1
# Node name: slam_node
# QoS profile:
#   Reliability: RELIABLE     ← MISMATCH! No data will flow
#   Durability: VOLATILE

# Check connection count (0 = QoS mismatch or no publisher)
ros2 topic info /scan
# → Publisher count: 1
# → Subscription count: 1

# If connected: echo shows data
ros2 topic echo /scan --once

# Diagnose mismatches
ros2 doctor --report | grep -A3 "incompatib"

If ros2 topic echo shows nothing but both publisher and subscriber are running, check QoS mismatch with ros2 topic info -v. This is the most common silent failure in ROS 2.

8

QoS Compatibility Table

Publisher and subscriber QoS must be compatible for a connection to form. Incompatible pairs are silently rejected by DDS.

text
RELIABILITY Compatibility
──────────────────────────────────────
Publisher      │ Subscriber    │ Match?
───────────────┼───────────────┼───────
RELIABLE       │ RELIABLE      │  ✅
RELIABLE       │ BEST_EFFORT   │  ✅  (sub gets best-effort delivery)
BEST_EFFORT    │ RELIABLE      │  ❌  (sub requests guarantee pub can't give)
BEST_EFFORT    │ BEST_EFFORT   │  ✅

DURABILITY Compatibility
──────────────────────────────────────
Publisher         │ Subscriber         │ Match?
──────────────────┼────────────────────┼───────
TRANSIENT_LOCAL   │ TRANSIENT_LOCAL    │  ✅  (late sub gets history)
TRANSIENT_LOCAL   │ VOLATILE           │  ✅  (but late sub gets nothing)
VOLATILE          │ TRANSIENT_LOCAL    │  ❌
VOLATILE          │ VOLATILE           │  ✅

DEADLINE Compatibility (publisher offers, subscriber requests)
──────────────────────────────────────
Publisher deadline ≥ Subscriber deadline → ✅ compatible
Publisher deadline <  Subscriber deadline → ❌ (pub offers less than sub requests)

GENERAL RULE: Publisher must OFFER at least what the Subscriber REQUESTS.
A "better" publisher (RELIABLE, TRANSIENT_LOCAL) is always compatible with
a "weaker" subscriber (BEST_EFFORT, VOLATILE) — but not vice versa.

QoS Quick Reference

Policy CombinationResult
RELIABLE / RELIABLE✅ Guaranteed delivery
BEST_EFFORT pub / RELIABLE sub❌ Incompatible — no data
TRANSIENT_LOCAL / TRANSIENT_LOCAL✅ Late subscriber gets history
VOLATILE / TRANSIENT_LOCAL sub❌ Incompatible
Sensor data profileBEST_EFFORT, VOLATILE, KEEP_LAST(5)
System default profileRELIABLE, VOLATILE, KEEP_LAST(10)
Latched topicTRANSIENT_LOCAL + RELIABLE + depth=1
High-rate sensorBEST_EFFORT + VOLATILE + depth=1
Check mismatchros2 topic info /topic -v
Deadline missedon_requested_deadline_missed callback