Main Content

Manage Quality of Service Policies in ROS 2 Application with TurtleBot

This example demonstrates best practices in managing Quality of Service (QoS) policies for an application using ROS 2. QoS policies allow for the flexible tuning of communication behavior between publishers and subscribers, and change the way that messages are transported within a ROS 2 network. For more information, see Manage Quality of Service Policies in ROS 2.

In this example, you use a MATLAB® script to launch a teleoperation controller for a simulated TurtleBot® to follow a path in based on instructions in the environment.

Start Robot Simulator

Start a ROS 2 simulator for a TurtleBot® and configure the MATLAB connection with the robot simulator.

This example uses a virtual machine (VM). Download the VM using the instructions in Get Started with Gazebo and Simulated TurtleBot.

  • Start the Ubuntu® virtual machine.

  • Select Gazebo ROS2 Maze on the Ubuntu desktop to start the Gazebo world built for this example.

  • Enter these commands in the MATLAB Command Window to verify that the topics from the robot simulator are visible in MATLAB.

setenv('ROS_DOMAIN_ID','25')
ros2('topic','list')
/camera/camera_info
/camera/image_raw
/clock
/cmd_vel
/imu
/joint_states
/odom
/parameter_events
/rosout
/scan
/tf

Set Up ROS 2 Communication

Create two ROS 2 nodes: /robotDataProcessingNode and /humanOperatorNode. The /robotDataProcessingNode receives sensor data to process and publishes messages to keep track of the number of signs detected. The /humanOperatorNode sends velocity commands to drive the TurtleBot around the environment and receives a confirmation whenever a sign is detected.

domainID = 25;
robotDataProcessingNode = ros2node("/robotDataProcessingNode",domainID);
humanOperatorNode = ros2node("/humanOperatorNode",domainID);

This diagram summarizes the interaction between MATLAB and the robot simulator.

Quality of Service Policies for Control Commands

Create publishers and subscribers to relay messages to and from the robot simulator over the ROS 2 network. A publisher and subscriber pair can have compatible, but different QoS policies unless any QoS policies of the subscriber are more stringent than those of the publisher. For example, you must relay the velocity commands in a reliable channel from the publisher to the subscriber. To ensure compatibility, specify the "Reliability" and "Durability" QoS policies of the publisher as "reliable" and "transientlocal", respectively. This configuration indicates the maximum quality that the controller provides for sending messages reliably. If the receiver on the robot is not equipped with good hardware to reliably process the messages, you can set a lower QoS standard for the subscriber. Thus, specify the "Reliability" and "Durability" QoS policies of the subscriber to "besteffort" and "volatile" respectively, which is the minimum quality that the receiver is willing to accept. These QoS settings demonstrate the best practice for specifying "Reliability", and "Durability" parameters. Publishers with policies of "besteffort" or "volatile" do not connect to subscribers with policies of "reliable", or "transientlocal". Because the subscriber is asking for a higher QoS standard than the publisher is offering, delivery of the publisher messages is not guaranteed.

velPub = ros2publisher(humanOperatorNode,"/cmd_vel","geometry_msgs/Twist","Reliability","reliable","Durability","transientlocal","Depth",5);

Quality of Service Policies for High-Frequency Sensor Data

To receive the latest reading of sensor data being published at a high rate, set the "Reliability" QoS policy of the subscriber to "besteffort" and, the "Durability" policy to "volatile", with a small "Depth" value. These settings enable high-speed communication by reducing the overhead time for sending and receiving message confirmation and ensure that the subscribers process the most recent messages. These settings can result in subscribers not receiving messages in lossy or high-traffic networks, or not processing all messages received if the processing cannot keep up. Apply this QoS policy to both the camera and lidar sensor.

imageSub = ros2subscriber(robotDataProcessingNode,"/camera/image_raw","sensor_msgs/Image","Reliability","besteffort","Durability","volatile","Depth",5);
laserSub = ros2subscriber(robotDataProcessingNode,"/scan","sensor_msgs/LaserScan","Reliability","besteffort","Durability","volatile","Depth",5);

Because odometry is critical in placing the lidar scans in context, dropped odometry messages result in misleading lidar readings. To prevent dropped messages, the reliability and durability policies for the odometry publisher in the Gazebo node are "reliable" and "transientlocal", respectively. As this particular algorithm does not need past messages, specify QoS policies for the odometry subscriber as "reliable" and "volatile".

odomSub = ros2subscriber(robotDataProcessingNode,"/odom","nav_msgs/Odometry","Reliability","reliable","Durability","volatile","Depth",5);

Quality of Service Policies for Robot States and Operational Modes

In this example, the information about the current stage of the robot updates at a low frequency, and the value in the latest message received applies until the subscriber receives the next message. Create a publisher that sends messages reliably and stores them for late-joining subscribers. If the "Depth" value of the publisher is large enough, it is possible for subscribers to request the entire history of the publisher when they join the network. Configure the publisher of the /signCounter topic with "Reliability" policy set to "reliable", "Durability" policy set to "transientlocal", and "Depth" value set to 100.

stagePub = ros2publisher(robotDataProcessingNode,"/signCounter","std_msgs/Int8","Reliability","reliable","Durability","transientlocal","Depth",100);

This table summarizes the QoS policies for the five pairs of publishers and subscribers.

Compatibility in Quality of Service Policies

For messages to pass successfully from publisher to subscriber over a topic, their QoS policies must be compatible. The publishers in the table do not always have the same QoS parameters as their corresponding subscribers, but they are still compatible. For example, in the camera sensor, velocity command, and laser scan topics, the "reliable" publishers and "besteffort" subscribers are able to connect. The connection behaves as a "besteffort" connection, with no confirmation when a subscriber receives a message. Similarly, in the odometry and velocity command topics, the "transientlocal" publishers and "volatile" subscribers have compatible QoS policies. The publishers retain the published messages while the subscribers do not request any previously sent messages.

Control Robot Using Teleoperation

Run the teleoperation controller to move the robot. Process the sensor data to help the robot visualize and navigate in the environment. When the robot moves close to a sign, the sign-detecting algorithm outputs a confirmation message with the instruction to find the next sign. This task repeats until the robot reaches the stop sign. For information on running the robot in autonomous mode, see Sign Following Robot with ROS 2 in MATLAB.

[laserPlotObj,imageAxesHandle,signText,axesHandle] = ExampleHelperQoSTurtleBotSetupVisualizer(velPub);
% Wait to receive sensor messages before starting the control loop
receive(laserSub,5);
receive(odomSub,5);
receive(imageSub,5);
% Set callback functions for subscribers
imageSub.NewMessageFcn = @(msg)ExampleHelperQoSTurtleBotPlotImage(msg,imageAxesHandle);
laserSub.NewMessageFcn = @(msg)ExampleHelperQoSTurtleBotPlotScan(msg,laserPlotObj,odomSub);
r = rateControl(10);
LastStage = false;
while ~LastStage
    [~,blobSize,blobX] = ExampleHelperQoSTurtleBotProcessImg(imageSub.LatestMessage); % Process image
    [nextStage,LastStage,stageMsg,textHandle] = ExampleHelperQoSTurtleBotSignDetection(LastStage,signText,blobX,blobSize,stagePub,axesHandle); % Sign detection algorithm
    if nextStage && ~LastStage  % When the algorithm detects a sign, publish a message to keep track of it.    
        send(stagePub,stageMsg);
    end
    waitfor(r);    
end

When sensors detect the stop sign, create a new subscriber in the /humanOperatorNode node to request the past messages in the history of the publisher. Extract information on all the detected signs.

send(stagePub,stageMsg);
stageSub = ros2subscriber(humanOperatorNode,"/signCounter","std_msgs/Int8","Reliability","reliable","Durability","transientlocal","Depth",100);
stageSub.NewMessageFcn = @(msg)ExampleHelperQoSTurtleBotSignCountUpdate(msg,textHandle);
pause(2); % Allow time for the persisting messages to be received and processed

% Clean up entities in ROS 2 to remove them from the network. 
clear laserSub odomSub velPub imageSub stagePub stageSub robotDataProcessingNode humanOperatorNode

Observe Effects of Quality of Service Policies in Lossy Networks

In low-traffic and lossless networks, there is little difference between reliable and best-effort communication. To visualize how different QoS policies handle lossy or high-traffic network connections, use the traffic control utility to simulate a network with delay. On the VM, open a new terminal and enter this command.

sudo tc qdisc add dev ens33 root netem delay 0.5ms

The traffic control utility simulates a fixed amount of delay to all packets on the ens33 network interface. Run the example again, observing the stuttering effect of the image stream due to some dropped frames in "best-effort" communication. If you change the image subscriber to "reliable", the image stream smooths out, but lags behind the actual robot viewpoint slightly due to the network delay.

To clean up, remove the artificial network lag by entering this command.

sudo tc qdisc delete dev ens33 root netem delay 0.5ms