ROS2 Quality of Service settings are one of those topics that seem optional until they cause a production bug. Then they become very, very relevant.
In devibot, we had a specific problem: the robot’s shutdown request system was unreliable. If the physical power button triggered a shutdown via a /robot/shutdown_request topic, the ROS2 dashboard subscriber sometimes missed it — especially at startup, when nodes were still coming online. The robot would begin shutting down without the dashboard knowing, leaving the UI in a stale state and the operator confused.
Understanding the defaults
ROS2’s default QoS profile is RELIABLE reliability + VOLATILE durability. Here is what that means:
- RELIABLE: the publisher guarantees message delivery to all current subscribers. If a message is lost in transit, it is retransmitted.
- VOLATILE: no message history is stored. If a subscriber joins after a message was published, it never receives that message.
For most topics — sensor data, odometry, velocity commands — VOLATILE is fine. The data is continuous; a subscriber that joins late simply starts receiving from the next publication.
For latched topics — configuration values, system state, critical one-time events — VOLATILE causes exactly the problem we had. The shutdown request was published once. Subscribers that weren’t running at that moment missed it forever.
TRANSIENT_LOCAL: the latched publisher
TRANSIENT_LOCAL durability instructs the publisher to store its last N messages (configurable via depth). When a new subscriber connects, it immediately receives the stored messages — even if they were published before the subscriber existed.
This is equivalent to the latched=True publisher in ROS1, but more explicit and configurable.
from rclpy.qos import QoSProfile, ReliabilityPolicy, DurabilityPolicy, HistoryPolicy
LATCHED_QOS = QoSProfile(
reliability=ReliabilityPolicy.RELIABLE,
durability=DurabilityPolicy.TRANSIENT_LOCAL,
history=HistoryPolicy.KEEP_LAST,
depth=1 # Store only the most recent message
)
# Publisher
self.shutdown_pub = self.create_publisher(
String,
'/robot/shutdown_request',
LATCHED_QOS
)
# Subscriber — must use matching QoS profile
self.shutdown_sub = self.create_subscription(
String,
'/robot/shutdown_request',
self.shutdown_callback,
LATCHED_QOS # Must match publisher
)
Critical: Publisher and subscriber QoS profiles must be compatible. A TRANSIENT_LOCAL publisher and a VOLATILE subscriber will connect, but the subscriber will not receive the stored messages. Always use TRANSIENT_LOCAL on both ends.
When to use RELIABLE + TRANSIENT_LOCAL in devibot
We use this QoS profile for four specific topic categories:
- Shutdown and reboot requests (
/robot/shutdown_request) — must not be missed by any subscriber, even late joiners - Robot configuration (
/robot/config) — initial configuration published once at startup, subscribers must receive it whenever they connect - Cloud sync events (
/cloud/sync_event) — the event-driven sync architecture depends on no events being dropped - Licence status (
/robot/licence_status) — published once on validation, subscribers may connect at any time
When NOT to use TRANSIENT_LOCAL
For high-frequency topics — LiDAR scans, odometry, camera images — TRANSIENT_LOCAL adds unnecessary overhead. The publisher stores messages in memory; for high-frequency topics, this storage grows and adds latency. Use BEST_EFFORT + VOLATILE for sensor data, and RELIABLE + VOLATILE for command topics where you want delivery guarantees but don’t need history.
Debugging QoS mismatches
A publisher-subscriber QoS mismatch in ROS2 does not cause an error — the connection simply doesn’t form, or forms with degraded behaviour. Use these commands to check:
# Check QoS on a running topic
ros2 topic info /robot/shutdown_request --verbose
# Shows publisher and subscriber QoS profiles
# Look for "Offered QoS" vs "Requested QoS" mismatches
QoS configuration in devibot is defined in a shared constants file imported by all nodes — this ensures consistency across the entire system. Questions? Reach out.