Manage Quality of Service Policies in ROS 2
Quality of Service (QoS) policy options allow for changing the behavior of communication within a ROS 2 network. QoS policies are modified for specific communication objects, such as publishers and subscribers, and change the way that messages are handled in the object handles the messages and transported between them. For any messages to pass between two communication objects, their QoS policies must be compatible.
The available Quality of Service policies in ROS 2 are:
History
- Message queue modeDepth
- Message queue sizeReliability
- Delivery guarantee of messagesDurability
- Persistence of messagesDeadline
- Expected interval between consecutive messagesLifespan
- Message validity window after receptionLiveliness
- Entity aliveness asserting protocolLeaseDuration
- Maximum time window between liveliness assertions
For more information, see About Quality of Service Settings.
History and Depth
The History
and Depth
QoS policies determine the behavior of communication objects when messages are being made available faster than they can be processed. This is primarily a concern for subscribers that are receiving messages while still processing the previous message. Messages are placed into a processing queue, which can affect publishers as well. History
has the options of:
"keeplast"
- The message processing queue has a maximum size equal to theDepth
value. If the queue is full, the oldest messages are dropped to make room for newer ones."keepall"
- The message processing queue attempts to keep all messages received in the queue until processed.
Under either History
setting, the queue size is subject to hardware resource limits. If the subscriber calls a callback when new messages are received, the queue size is also limited by the maximum recursion limit.
In situations where it is important to process all messages, increasing the Depth
value or using History,"keepall"
is recommended.
This example shows how to set up a publisher and subscriber for sending and receiving point cloud messages. The publisher Depth
is 20 and the subscriber History
is set to "keepall"
. The subscriber uses a call back to plot the time stamp for each message to show the timing of processing each message. The initial messages take longer to process, but all the messages are eventually processed from the queue.
% Create a publisher to provide sensor data robotNode = ros2node("/simple_robot"); lidarPub = ros2publisher(robotNode,"/laser_scan","sensor_msgs/PointCloud2",... "History","keeplast","Depth",20); % Create a subscriber representing localization, requiring all scan data hFig = figure; hAxesLidar = axes("Parent",hFig); title("Message Timeline (Keep All)")
localizationSub = ros2subscriber(robotNode,"/laser_scan",... @(msg)exampleHelperROS2PlotTimestamps(msg,hAxesLidar),... "History","keepall"); % Send messages, simulating an extremely fast sensor load robotPoseLidarData.mat lidarScans for iMsg = 1:numel(lidarScans) send(lidarPub,lidarScans(iMsg)) end % Allow messages to arrive, then remove the localization subscriber pause(3) clear localizationSub
In situations where messages being dropped is less important, and only the most up-to-date information really matters, a smaller queue is recommended to improve performance and ensure the most recent information is being used. This example shows quicker processing of the first messages and still gets all the messages. Depending on your resources however, you may see messages get dropped.
% Create a subscriber representing user interface display hFig = figure; hAxesLidar2 = axes("Parent",hFig); title("Message Timeline (Keep Last 1)")
scanDisplaySub = ros2subscriber(robotNode,"/laser_scan",... @(msg)exampleHelperROS2PlotTimestamps(msg,hAxesLidar2),... "History","keeplast","Depth",1); for iMsg = 1:numel(lidarScans) send(lidarPub,lidarScans(iMsg)) end % Allow messages to arrive, then remove the subscriber and publisher pause(3) clear lidarPub scanDisplaySub
Reliability
The Reliability
QoS policy determines whether to guarantee delivery of messages, and has the options:
"reliable"
- The publisher continuously sends the message to the subscriber until the subscriber confirms receipt of the message."besteffort"
- The publisher sends the message only once, and does not confirm that the subscriber receives it.
Reliable
A "reliable"
connection is useful when all of the data must be processed, and any dropped messages may impact the result. This example publishes Odometry
messages and uses a subscriber callback to plot the position. Because for the "reliable"
setting, all the positions are plotted in the figure.
% Create a publisher for odometry data odomPub = ros2publisher(robotNode,"/odom","nav_msgs/Odometry",... "Reliability","reliable"); % Create a subscriber for localization hFig = figure; hAxesReliable = axes("Parent",hFig); title("Robot Position (Reliable Connection)") xlabel("X (m)") ylabel("Y (m)")
odomPlotSub = ros2subscriber(robotNode,"/odom",... @(msg)exampleHelperROS2PlotOdom(msg,hAxesReliable,"ok"),... "Reliability","reliable"); % Send messages, simulating an extremely fast sensor load robotPoseLidarData.mat odomData for iMsg = 1:numel(odomData) send(odomPub,odomData(iMsg)) end pause(5) % Allow messages to arrive and be plotted % Temporarily prevent reliable subscriber from reacting to new messages odomPlotSub.NewMessageFcn = [];
Best Effort
A "besteffort"
connection is useful to avoid impacting performance if dropped messages are acceptable. If a publisher is set to "reliable"
, and a subscriber is set to "besteffort"
, the publisher treats that connection as only requiring "besteffort"
, and does not confirm delivery. Connections with "reliable"
subscribers on the same topic are guaranteed delivery from the same publisher.
This example uses a "besteffort"
subscriber, but still receives all messages due to the low impact on the network.
hFig = figure; hAxesBestEffort = axes("Parent",hFig); title("Message Timeline (Best Effort Connection)")
odomTimingSub = ros2subscriber(robotNode,"/odom",... @(msg)exampleHelperROS2PlotTimestamps(msg,hAxesBestEffort),... "Reliability","besteffort"); for iMsg = 1:numel(odomData) send(odomPub,odomData(iMsg)) end pause(3) % Allow messages to arrive and be plotted
Compatibility
Ensuring compatibility is an important consideration when setting Reliability
. A subscriber with a "reliable"
option set requires a publisher that meets that standard. Any "besteffort"
publishers do not connect to a "reliable"
subscriber because messages are not guaranteed to be delivered. In the opposite situation, a "reliable"
publisher and a "besteffort"
subscriber do connect, but the connection behaves as "besteffort"
with no confirmation when receiving messages. This example shows a "besteffort"
publisher sending messages to the "besteffort"
subscriber already set up. Again, due to the low impact on the network, the "besteffort"
connection is sufficient to process all the messages.
% Reactivate reliable subscriber to show no messages received odomPlotSub.NewMessageFcn = @(msg)exampleHelperROS2PlotOdom(msg,hAxesReliable,"*r"); % Send messages from a best-effort publisher bestEffortOdomPub = ros2publisher(robotNode,"/odom","nav_msgs/Odometry",... "Reliability","besteffort"); for iMsg = 1:numel(odomData) send(bestEffortOdomPub,odomData(iMsg)) end % Allow messages to arrive, then remove odometry publishers and subscribers pause(3) % Allow messages to arrive and be plotted clear odomPub bestEffortOdomPub odomPlotSub odomTimingSub
Durability and Depth
The Durability
QoS policy controls the persistence of messages for late-joining connections, and has the options:
"transientlocal"
- For a publisher, messages that have already been sent are maintained. If a subscriber joins the network with"transientlocal"
Durability
after that, then the publisher sends the persisted messages to the subscriber."volatile"
- Publishers do not persist messages after sending them, and subscribers do not request persisted messages from publishers.
The number of messages persisted by publishers with "transientlocal"
Durability
is also controlled by the Depth
input. Subscribers only request the number of recent messages based on their individual Depth
settings. Publishers can still store more messages for other subscribers to get more. For example, a full list of the robot position may be useful for visualizing its path, but a localization algorithm may only be interested in the last known location. This example illustrates that by using a localization subscriber to display the current position and a plotting subscriber to show all positions in the queue.
% Publish robot location information posePub = ros2publisher(robotNode,"/bot_position","geometry_msgs/Pose2D",... "Durability","transientlocal","Depth",100); load robotPoseLidarData.mat robotPositions for iMsg = 1:numel(robotPositions) send(posePub,robotPositions(iMsg)) pause(0.2) % Allow for processing time end % Create a localization update subscriber that only needs current position localUpdateSub = ros2subscriber(robotNode,"/bot_position",@disp,... "Durability","transientlocal","Depth",1); pause(1) % Allow message to arrive
x: 0.1047 y: -2.3168 theta: -8.5194
% Create a visualization subscriber to show where the robot has been hFig = figure; hAxesMoreMsgs = axes("Parent",hFig); title("Robot Position (Transient Local Connection)") xlabel("X (m)") ylabel("Y (m)") hold on
posePlotSub = ros2subscriber(robotNode,"/bot_position",... @(msg)plot(hAxesMoreMsgs,msg.x,msg.y,"ok"),... "Durability","transientlocal","Depth",20); pause(3) % Allow messages to arrive and be plotted
Compatibility
Similar to Reliability
, incompatible Durability
settings can prevent communication between publishers and subscribers. A subscriber with "transientlocal"
Durability
requires a publisher with "transientlocal"
Durability
. If a publisher is "volatile"
, no connection is established with "transientlocal"
subscribers. If a publisher is "transientlocal"
and the subscriber "volatile
", then that connection is created, without sending persisting messages to the subscriber.
% Reset plotting behavior posePlotSub.NewMessageFcn = @(msg)plot(hAxesMoreMsgs,msg.x,msg.y,"xr"); % Send messages from volatile publisher volatilePosePub = ros2publisher(robotNode,"/bot_position",... "Durability","volatile"); for iMsg = 1:numel(robotPositions) send(volatilePosePub,robotPositions(iMsg)) pause(0.2) % Allow for processing time end
No messages are received by either "transientlocal"
subscriber.
% Remove pose publishers and subscribers clear posePub volatilePosePub localUpdateSub posePlotSub robotNode
Deadline
The Deadline
QoS policy defines the expected interval for publishing consecutive messages to a topic. It sets the duration permitted between messages.
For subscribers, it outlines the permissible duration between message receptions. Coming to publishers, it specifies the allowed duration between message transmissions.
If the user does not set the Deadline
QoS policy, it indicates an unspecified duration. This means that the underlying middleware typically interprets this as an infinitely long duration.
In this example, the publisher is responsible for providing robot position data, while the subscriber is set up to receive and plot this data. The 3-second Deadline
specifies that every succeeding message is published to the /laser_scan
topic within 3 seconds of publishing the preceding message.
% Create a publisher to provide sensor data robotNode = ros2node("/simple_robot"); lidarPub = ros2publisher(robotNode,"/laser_scan","sensor_msgs/PointCloud2", "Deadline",5); % Create a subscriber representing localization, requiring all scan data hFig = figure; hAxesLidar = axes("Parent",hFig); title("Message Timeline (Deadline)")
localizationSub = ros2subscriber(robotNode,"/laser_scan",... @(msg)exampleHelperROS2PlotTimestamps(msg,hAxesLidar),"Deadline",5); % Send messages, simulating an extremely fast sensor load robotPoseLidarData.mat lidarScans for iMsg = 1:numel(lidarScans) send(lidarPub,lidarScans(iMsg)) end % Allow messages to arrive, then remove the localization subscriber pause(2) clear localizationSub
Compatibility
Compatibility must be established while setting the Deadline
QoS policy. A publisher with unset Deadline
policy can connect to a subscriber meeting the same standards only. If a publisher has duration set to an arbitrary value, say "x"
, then it can communicate to a subscriber with the following options:
QoS policy is unset which means that the duration is equal to an infinite value.
Duration is set to the same arbitrary value
"x"
.Duration is set to a different arbitrary value
"y"
, where"y"
>"x".
Lifespan
The Lifespan
QoS policy defines the maximum duration between publishing and message reception without considering the message as stale or expired. It sets the duration for which a message remains valid.
For subscriptions, it defines the duration a message is deemed valid, beyond which it will not be received. For Publishers, it sets the timeframe a message is considered valid, after which it will be deleted from the topic history and no longer sent to Subscribers.
Messages that have expired are silently discarded. If the user does not set the Lifespan
QoS policy, it indicates an unspecified duration. This means that the underlying middleware typically interprets this as an infinitely long duration.
In this example, the publisher is set up to provide sensor data related to laser scans, and the Lifespan
QoS policy is specifically set to 5 seconds. This means that any message published by the publisher will be considered valid for 5 seconds before it is no longer remains valid.
% Create a publisher to provide laser scan sensor data robotNode = ros2node("/simple_robot"); lidarPub = ros2publisher(robotNode,"/laser_scan","sensor_msgs/PointCloud2",... "Lifespan", 5); % Create a subscriber representing localization, requiring all scan data hFig = figure; hAxesLidar = axes("Parent",hFig); title("Message Timeline (Lifespan)")
localizationSub = ros2subscriber(robotNode,"/laser_scan",... @(msg)exampleHelperROS2PlotTimestamps(msg,hAxesLidar),... "Lifespan", 5); % Send messages, simulating an extremely fast sensor load robotPoseLidarData.mat lidarScans for iMsg = 1:numel(lidarScans) send(lidarPub,lidarScans(iMsg)) end % Allow messages to arrive, then remove the localization subscriber pause(3) clear localizationSub
Liveliness
The Liveliness
QoS policy sets the protocol for entities to declare their level of their liveliness.
For Subscriptions, it determines the reporting standard expected from the Publishers to which they are subscribed. For Publishers, it defines the reporting level they will offer to notify Subscribers that they are alive.
Since this QoS policy does not represent a duration, the default value will utilize the underlying middleware's default setting, configured as "automatic"
. This implies that when any of the publishers has published a message, the system will consider all publishers of the node to be alive for an additional LeaseDuration
.
Compatibility
A publisher with Liveliness
QoS policy set to "automatic"
can create a compatible connection with a subscriber having "automatic" Liveliness
only.
LeaseDuration
The LeaseDuration
QoS policy defines the maximum duration allowed to a publisher to demonstrate its liveliness before the system considers it to have lost liveliness. Losing liveliness could serve as an indication of failure.
If the user does not set the LeaseDuration
QoS policy, it indicates an unspecified duration. This means that the underlying middleware typically interprets this as an infinitely long duration.
Compatibility
Publishers and subscribers with LeaseDuration
QoS policy follow the same pattern of compatibility for connecting as that of Deadline
QoS policy. A publisher with unset LeaseDuration
policy can connect to a subscriber meeting the same standards only. If a publisher has LeaseDuration
set to an arbitrary value, say "x"
, then it can communicate to a subscriber with the following options:
QoS policy is unset which means that the duration is equal to an infinite value.
Duration set to the same arbitrary value
"x"
.Duration set to a different arbitrary value
"y"
, where"y"
>"x".
In this example, when any of the publishers has published a message, the system will consider all publishers of the node to be alive for an additional LeaseDuration
of 5 seconds.
% Create a publisher for odometry data with Liveliness QoS policy set to automatic odomPub = ros2publisher(robotNode,"/odom","nav_msgs/Odometry",... "Liveliness", "automatic", "LeaseDuration", 5); % Create a subscriber for localization with Liveliness QoS policy set to automatic hFig = figure; hAxesLiveliness = axes("Parent",hFig); title("Robot Position (Automatic Liveliness)") xlabel("X (m)") ylabel("Y (m)")
odomPlotSub = ros2subscriber(robotNode,"/odom",... @(msg)exampleHelperROS2PlotOdom(msg,hAxesLiveliness,"ok"),... "Liveliness", "automatic", "LeaseDuration", 5); % Send messages, simulating an extremely fast sensor load robotPoseLidarData.mat odomData for iMsg = 1:numel(odomData) send(odomPub,odomData(iMsg)) end pause(5) % Allow messages to arrive and be plotted % Temporarily prevent subscriber from reacting to new messages odomPlotSub.NewMessageFcn = [];
QoS Events
Some of the discussed QoS policies have certain events related to them, that are essential for handling incoming data and performing actions based on that data. In MATLAB®, these events trigger default warnings and allow users to define custom callbacks as response to these events. In Simulink®, these QoS events trigger default warnings only.
Incompatible QoS
This event triggers when publisher or subscriber do not have compatible QoS policies in their settings.
To view and act upon this event, create a ROS 2 node.
imageNode = ros2node("/image_processing_node");
Create a publisher with Deadline
QoS policy at its default setting.
imagePub = ros2publisher(imageNode, "/image_data_topic", "sensor_msgs/Image");
Now, create a subscriber with Deadline
set to 1.
imageSub = ros2subscriber(imageNode, "/image_data_topic", "sensor_msgs/Image", "Deadline", 1);
This triggers default warning for both publisher and subscriber.
Now, create the publisher on the /image_data_topic
topic with the message type sensor_msgs/Image,
specify the callback function incompatibleQoS_callback
.
You can use this custom callback to log a warning or adjust the subscription's QoS settings to align with the received message.
imagePub = ros2publisher(imageNode, "/image_data_topic", "sensor_msgs/Image", "IncompatibleQoSCallback", @incompatibleQoS_callback); function incompatibleQoS_callback(total_count, total_count_change, last_kind_policy) fprintf('Incompatible QoS event detected:\n'); fprintf('Total count: %d\n', total_count); fprintf('Total count change: %d\n', total_count_change); fprintf('Last kind of policy: %s\n', last_kind_policy); end
Deadline Missed
This event triggers when publisher fails to publish messages or subscriber does not receive any messages within the specified deadline.
To view and act upon this QoS event, create a ROS 2 node.
odomNode = ros2node("/simple_robot");
Create a publisher with Deadline
QoS policy set to 1.
odomPub = ros2publisher(odomNode, "/odom_data_topic", "nav_msgs/Odometry", "Deadline", 1);
Now, create a subscriber with Deadline
at its default setting.
odomSub = ros2subscriber(odomNode, "/odom_data_topic", "nav_msgs/Odometry");
Create a ROS 2 message to be published and send it twice with a 2-second pause in between.
msg = ros2message(odomPub); for i = 1:2 send(odomPub, msg); pause(2); end
This will trigger default warning for the publisher.
Use clear
all to clear the node, publisher and subscriber and stop the warnings.
Now, recreate the publisher on the /odom_data_topic
topic with the message type nav_msgs/Odometry,
specify the callback function deadlineMissed_callback
, and send message again. This triggers the custom callback for the publisher.
You can also specify the callback function for the subscriber instead of the publisher in order to trigger the custom callback for the subscriber.
odomPub = ros2publisher(odomNode, "/odom_data_topic", "nav_msgs/Odometry", "Deadline", 1, "DeadlineCallback", @deadlineMissed_callback); msg = ros2message(odomPub); for i = 1:2 send(odomPub, msg); pause(2); end function deadlineMissed_callback(total_count, total_count_change) fprintf('Deadline missed event detected:\n'); fprintf('Total count: %d\n', total_count); fprintf('Total count change: %d\n', total_count_change); end
Liveliness Changed
This event triggers when publisher is no longer alive to assert its liveliness. It produces no default warning but you can assign a custom callback to handle this event.
To view and act upon this QoS event, create a ROS 2 node.
imageNode = ros2node("/image_processing_node");
Create a publisher with LeaseDuration
QoS policy set to 1.
imagePub = ros2publisher(imageNode, "/image_data_topic", "sensor_msgs/Image", "LeaseDuration", 1);
Create a subscriber on the /image_data_topic
topic with the message type sensor_msgs/Image
and specify the callback function livelinessChanged_callback
.
imageSub = ros2subscriber(imageNode, "/image_data_topic", "sensor_msgs/Image", "LeaseDuration", 1, "LivelinessCallback", @livelinessChanged_callback); function livelinessChanged_callback(alive_count, alive_count_change, not_alive_count, not_alive_count_change) fprintf('Liveliness changed event detected:\n'); fprintf('Alive count: %d\n', alive_count); fprintf('Alive count change: %d\n', alive_count_change); fprintf('Not alive count: %d\n', not_alive_count); fprintf('Not alive count change: %d\n', not_alive_count_change); end
Create a ROS 2 message to be published and send it twice with a 2-second pause in between. This triggers the custom callback for the subscriber.
msg = ros2message(imagePub); for i = 1:2 send(imagePub, msg); pause(2); end
You can also specify the callback function for the publisher instead of the subscriber in order to trigger the custom callback for the publisher.
Message Lost
This event triggers when a subscriber loses messages due to issues such as network problems, buffer overflows, or other communication errors.
In this example, user publishes large-sized message data without any pause (as fast as possible) which triggers this event, causing messages to get lost in the process. Consequently, the subscriber fails to receive all of them.
To view and act upon this QoS event in the above specific scenario, create a ROS 2 node.
imageNode = ros2node("/image_processing_node");
Create a publisher on image_topic
topic with message type sensor_msgs/Image
.
imagePub = ros2publisher(imageNode, "image_topic", "sensor_msgs/Image", "Depth", 1, "Reliability", "besteffort");
Create a ROS 2 message of type sensor_msgs/Image
and set messge size to 8MB.
message_size = 1024 * 1024 * 8;
msg = ros2message("sensor_msgs/Image");
msg.data = uint8(ones(1, message_size));
Define publishMessage
function within an infinite loop to continuously publish message with an updated timestamp and incrementing counter value.
function publishMessage(imagePub, msg, imageNode, i) % Update timestamp x = ros2time(imageNode, "now"); msg.data(1) = i; msg.header.stamp.sec = x.sec; % Publish the message send(imagePub, msg); end % Initialize message counter i = 0; % Continuous loop to publish messages while true publishMessage(imagePub, msg, imageNode, i); i = i + 1; end
Now create a subscriber on the same topic with the same message type as that of the publisher with an infinite loop to listen for incoming messages on the topic.
For each received message, it fetches the first element of the data
array within the message and prints it to the command window. This loop will run indefinitely until it is manually interrupted or an internal mechanism stops it.
This triggers default warning for the subscriber. The Message Lost
event produces warning for subscribers only.
Note: To ensure triggering of the Message Lost
event, it is recommended to create the subscriber in a different MATLAB session.
imageSub = ros2subscriber(imageNode, "image_topic", "sensor_msgs/Image", "Depth", 1, "Reliability", "besteffort"); % Continuous loop to receive messages while true msg = receive(imageSub); disp(msg.data(1)) end
Recreate the subscriber on the /image_topic
topic with the message type sensor_msgs/Image
and specify the callback function messageLost_callback
. Run the infinite loop for the subscriber to listen to the incoming messages again. This triggers custom callback for the subscriber.
imageSub = ros2subscriber(node, "image_topic", "sensor_msgs/Image", "Depth", 1, "Reliability", "besteffort", "MessageLostCallback", @messageLost_callback); % Continuous loop to receive messages while true msg = receive(imageSub); disp(msg.data(1)) end function messageLost_callback(total_count, total_count_change) % Callback function to handle message lost events fprintf('Message lost event detected\n'); fprintf('Total count: %d\n', total_count); fprintf('Total count change: %d\n', total_count_change); end
QoS Callback Events Support for RMW Implementations
RMW Implementation | Incompatible QoS | Deadline Missed | Liveliness Changed | Message Lost |
---|---|---|---|---|
eProsima Fast DDS | Supported | Supported | Supported | Supported |
Eclipse Cyclone DDS | Supported | Supported | Supported | Not Supported |
RTI Connext DDS | Supported | Supported | Supported | Supported |
Eclipse Iceoryx Middleware | Not Supported | Not Supported | Not Supported | Not Supported |
eCAL Middleware | Not Supported | Not Supported | Not Supported | Not Supported |