Main Content

Explore ROS 2 Topics: Publisher and Subscriber Guide

Nodes use individual communication pipelines, known as topics, to communicate with other nodes. Think of topic communication as a group phone call where anyone can speak, and everyone else on the call listens. This resembles a radio station broadcast where messages continuously transmit, and anyone tuned in hears them.

The data type used in topic communication is message. Topics are a key part of the ROS 2 publish/subscribe communication model. You can use topics for continuous data streams, like sensor data.

  • Publisher –– Publishers are nodes which produce data. For instance, Node 1 can publish a specific type of message over a topic and make it available for other nodes, say Node 2.

  • Subscriber –– Subscribers are nodes which consume data. For instance, Node 2 can subscribe to messages or information published on a topic.

ROS 2 Topics publish and subscribe mechanism diagram

Message Interface

Nodes exchange data units known as messages. These messages are described in .msg files and consists of two parts: fields and constants. The fields value represents the data sent within the message, while the constants value defines useful values for interpreting those fields.

ROS 2 messages are structured data types and categorized into different types, based on their purpose. For example, a message designed to move a robot wheel differs from a message intended to capture an image from the robot's camera.

You can view the list of available message types by using ros2 msg list.

ros2 msg list
std_msgs/Bool
std_msgs/Byte
std_msgs/ByteMultiArray
std_msgs/Char
std_msgs/ColorRGBA
std_msgs/Empty
std_msgs/Float32
std_msgs/Float32MultiArray
std_msgs/Float64
std_msgs/Float64MultiArray
std_msgs/Header
std_msgs/Int16
std_msgs/Int16MultiArray
std_msgs/Int32...

This list contains message types of predefined message interface definitions.

You can create a message of any of these predefined types such as example_interfaces/Int32.

firstMsg = ros2message("example_interfaces/Int32")
firstMsg = struct with fields:
    MessageType: 'example_interfaces/Int32'
           data: 0

The firstMsg message contains various attached fields, one of which is the data field. You can set the data field to a supported value of your choice, which is the constant attached to it. The code below sets the data field to a constant - integer value 5.

firstMsg.data = int32(5)
firstMsg = struct with fields:
    MessageType: 'example_interfaces/Int32'
           data: 5

You can also create messages with field set to different constants, with specific data types such as string, float, and bool as shown in these examples respectively.

secondMsg = ros2message("example_interfaces/String");
secondMsg.data = "Hello World!"
secondMsg = struct with fields:
    MessageType: 'example_interfaces/String'
           data: "Hello World!"
thirdMsg = ros2message("example_interfaces/Float32");
thirdMsg.data = 10.05
thirdMsg = struct with fields:
    MessageType: 'example_interfaces/Float32'
           data: 10.0500
fourthMsg = ros2message("example_interfaces/Bool");
fourthMsg.data = true
fourthMsg = struct with fields:
    MessageType: 'example_interfaces/Bool'
           data: 1

For more information on various ways to create, inspect, and populate ROS 2 messages in MATLAB that are commonly encountered in robotics applications, see Work with Basic ROS 2 Messages.

Publish Message to Topic and Subscribe to that Message

This example walks you through the process of creating a battery level monitoring system for a robot using ROS 2 topics in MATLAB®. By leveraging ROS 2 topics, nodes can publish and subscribe to battery level data, enabling real-time monitoring and decision making based on the battery status.

To begin with, create a ROS 2 node named /robot_battery_monitor. This node is the central entity in the ROS 2 network, that manages communication for the battery monitoring system by handling the publishing and subscribing of battery level data.

node = ros2node('/robot_battery_monitor');

Next, create a publisher that acts as a broadcaster and publishes battery level data to the /battery_level topic. The battery level is a whole number percentage (0-100).

Choose the std_msgs/Int32 message type from the list of predefined messages because it supports whole number or integer data.

batteryLevelPub = ros2publisher(node, "/battery_level", "std_msgs/Int32")
batteryLevelPub = 

  ros2publisher with properties:

        TopicName: '/battery_level'
      MessageType: 'std_msgs/Int32'
         NodeName: '/robot_battery_monitor'
          History: 'keeplast'
            Depth: 10
      Reliability: 'reliable'
       Durability: 'volatile'
         Deadline: Inf
         Lifespan: Inf
       Liveliness: 'automatic'
    LeaseDuration: Inf

Define a callback function named batteryLevelCallback that processes incoming battery level messages. This function prints the battery level and takes action based on the battery status, such as stopping the robot or sending it back to the recharge station. The callback function executes each time the subscribed topic receives a new message.

function batteryLevelCallback(msg)
    batteryLevel = msg.data;  % Ensure the data is of type int32
    fprintf('Battery Level: %d%%\n', batteryLevel);
    
    if batteryLevel <= 0
        fprintf('Battery depleted. Robot stopping...\n');
    elseif batteryLevel <= 20
        fprintf('Battery depleting. Send back to recharge station...\n');
    else
        fprintf('Battery sufficient for operation.\n');
    end
end

Create a subscriber that listens to the /battery_level topic and calls the batteryLevelCallback function when a new message is received. This allows the system to react promptly to changes in battery level.

batteryLevelSub = ros2subscriber(node, "/battery_level", "std_msgs/Int32", @batteryLevelCallback)
batteryLevelSub = 

  ros2subscriber with properties:

        TopicName: '/battery_level'
    LatestMessage: []
      MessageType: 'std_msgs/Int32'
         NodeName: '/robot_battery_monitor'
    NewMessageFcn: @batteryLevelCallback
          History: 'keeplast'
            Depth: 10
      Reliability: 'reliable'
       Durability: 'volatile'
         Deadline: Inf
         Lifespan: Inf
       Liveliness: 'automatic'
    LeaseDuration: Inf

Simulate the publishing of battery levels by creating a loop that decreases the battery level from 100% to 0% in steps of 10%. For each battery level, create a message, set the data, and publish it to the /battery_level topic.

for batteryLevel = 100:-10:0
    % Create a message
    msg = ros2message(batteryLevelPub);
    msg.data = int32(batteryLevel);
    
    % Publish the message
    send(batteryLevelPub, msg);
    
    % Pause to simulate time passing
    pause(1);
end
Battery Level: 100%
Battery sufficient for operation.
Battery Level: 90%
Battery sufficient for operation.
Battery Level: 80%
Battery sufficient for operation.
Battery Level: 70%
Battery sufficient for operation.
Battery Level: 60%
Battery sufficient for operation.
Battery Level: 50%
Battery sufficient for operation.
Battery Level: 40%
Battery sufficient for operation.
Battery Level: 30%
Battery sufficient for operation.
Battery Level: 20%
Battery depleting. Send back to recharge station...
Battery Level: 10%
Battery depleting. Send back to recharge station...
Battery Level: 0%
Battery depleted. Robot stopping...

Custom Message Support for ROS 2 Topics

Utilizing predefined interface definitions is generally considered a best practice. However, there are situations where the standard message types may not align with the specific requirements of your robotic application. For instance, if you require a message format for managing inventory that includes fields for item name, quantity, and storage location, you need to create custom ROS 2 messages. ROS Toolbox supports ROS 2 custom message generation which is elaborated in ROS 2 Custom Message Support.

You can generate ROS 2 custom messages by reading ROS 2 custom message definitions in the specified folder path by using ros2genmsg. The function folder must contain one or more ROS 2 packages. These packages contain the message definitions in .msg files. You can also create a shareable ZIP archive of the generated custom messages and use this ZIP archive to register the custom messages in another machine by using ros2RegisterMessages.

In MATLAB, you do not typically write .msg files directly. Instead, you create custom messages using ROS 2 package tools and then use them in MATLAB.

See Also

| |

Related Topics

External Websites