tutorial

ROS 2 composable nodes.

Optimizing ROS 2 communication: reducing latency with composableNodes.

tutorial

In our previous post, we explored how computers think and their process structure. In this post, we’ll apply those concepts to ROS 2 in a practical context.

The ROS 2 ComposableNode.

In ROS 2, the basic unit of processing is called a node. Typically, a node serves a single purpose, such as controlling a motor or planning a path. A standard node runs as a single process.

However, ROS 2 introduces the concept of a ComposableNode, which runs inside a container. Important note: This node container is unrelated to a Docker container—instead, think of it as the main process.

Containers in ROS 2 can be SingleThreaded or MultiThreaded:

  • In a single-threaded container, all ComposableNodes execute sequentially.
  • In a multi-threaded container, nodes can run concurrently.

Understanding the differences between single-threaded and multi-threaded containers is crucial for efficient robotics development.

Benefits of ComposableNodes: Shared-memory data transfer.

Another major advantage of using ComposableNodes in a container is the ability to transfer data through shared memory. As discussed in our previous post, threads and processes handle shared data differently.

When a container is created with intra-process communication (IPC) enabled, ComposableNodes within the same container can access shared memory. This significantly improves data transfer efficiency and reduces latency, leading to faster and more reliable robotic applications.

Calculating latency.

In this tutorial, we will use the message Header from the std_msgs library. As you can see, this message is quite small and contains minimal information. However, we will utilize its timestamp element to measure communication latency.

Prerequisites.

As of today, ComposableNodes can only be used with C++. To get started, create a new ROS 2 package in your preferred workspace. Your package should have the following dependencies:

  • rclcpp
  • std_msgs
  • rclcpp_components

Implementing the publisher.

Let’s begin by writing the publisher code. This node will publish a Header message containing a timestamp representing when the message is sent. On the subscriber side, we will use this timestamp to calculate the delay, allowing us to measure communication latency.

Creating the publisher file.

  1. In the src directory of your package, create a new file named publisher.cpp.
  2. Add the necessary headers and namespace to set up the publisher.
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/header.hpp>

namespace composable_node_tutorials {

Now, we will define the HeaderPublisherNode class, which inherits from the Node class. This class will:

  1. Initialize the node: Call the parent class constructor.
  2. Declare a publisher: Publish Header messages to the topic header_topic.
  3. Create a timer: The timer will trigger every 1 second, calling the timer_callback function.
  4. Track message count: Maintain a count_ variable to count the number of published messages.
  5. Print process and thread IDs: These unique OS-generated IDs help identify the running process and thread.
class HeaderPublisherNode : public rclcpp::Node {
public:
  explicit HeaderPublisherNode(const rclcpp::NodeOptions &options)
      : Node("header_publisher_node", options), count_(0) {
    publisher_ = create_publisher<std_msgs::msg::Header>("header_topic", 10);
    timer_ = create_wall_timer(
        std::chrono::seconds(1),
        std::bind(&HeaderPublisherNode::timer_callback, this));

    // Print the process ID and thread ID
    std::thread::id thread_id = std::this_thread::get_id();
    RCLCPP_INFO_STREAM(get_logger(),
                       "Process ID: " << getpid()
                                      << " Thread ID: " << thread_id);
  }

In the private section of the class, define the timer_callback method. This method will create a new message, write the current time to the stamp element, and store the current message count in the frame_id element before publishing the message. Finally, declare the elements used in the node, such as the timer, publisher, and counter. Don’t forget to close the class and namespace.

private:
  void timer_callback() {
    auto message = std_msgs::msg::Header();
    message.stamp = now();
    message.frame_id = std::to_string(count_++);

    RCLCPP_INFO(get_logger(), "Publishing: '%s'", message.frame_id.c_str());
    publisher_->publish(message);
  }

  rclcpp::TimerBase::SharedPtr timer_;
  rclcpp::Publisher<std_msgs::msg::Header>::SharedPtr publisher_;
  uint16_t count_;
};

} // namespace composable_node_tutorials

To use the node as a ComposableNode, add the following lines at the end of the file. This will register the node as a component.

// This function is needed to create a shared pointer to the node
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(composable_node_tutorials::HeaderPublisherNode);

Subscriber node.

Now, let’s create the subscriber node. This node will:

  • Subscribe to the Header message.
  • Calculate the delay between the received timestamp and the current time.
  • Publish the delay to a new topic for comparison.

Later, this node will be used twice:

  1. Within the same process as the publisher.
  2. In a separate process from the publisher.

Creating the subscriber file.

Create a new file named subscriber.cpp, and start by including the necessary headers.

#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/header.hpp>
#include <std_msgs/msg/u_int32.hpp>

namespace composable_node_tutorials {

The HeaderSubscriberNode will inherit from the Node class. In its constructor method, it will:

  • Create a subscriber for the header_topic.
  • Create a publisher for the ~/time_difference topic, using the UInt32 message type.
  • Print the process and thread IDs to the console for reference.
class HeaderSubscriberNode : public rclcpp::Node {
public:
  explicit HeaderSubscriberNode(const rclcpp::NodeOptions &options)
      : Node("header_subscriber_node", options) {
    subscription_ = create_subscription<std_msgs::msg::Header>(
        "header_topic", 10,
        std::bind(&HeaderSubscriberNode::topic_callback, this,
                  std::placeholders::_1));

    publisher_ =
        create_publisher<std_msgs::msg::UInt32>("~/time_difference_topic", 10);

    // Print the process ID and thread ID
    std::thread::id thread_id = std::this_thread::get_id();
    RCLCPP_INFO_STREAM(get_logger(),
                       "Process ID: " << getpid()
                                      << " Thread ID: " << thread_id);
  }

Implementing the HeaderSubscriberNode.

Private section implementation.

In the private section of the class:

  • Define the subscriber callback:
  • Calculate the time difference (latency) in nanoseconds between the current time and the timestamp in the received Header message.
  • Publish this difference as a UInt32 message.
  • Log the result using RCLCPP_INFO.
  • Declare the publisher and subscriber as class members.
  • Close the class and namespace properly.
  • Register the node as a component using the rclcpp_components library (as done in the publisher code).
private:
  void topic_callback(const std_msgs::msg::Header::SharedPtr msg) const {
    // Get the current time
    auto current_time = now();

    // Calculate the difference in nanoseconds
    auto message_time = rclcpp::Time(msg->stamp);
    auto time_difference = current_time - message_time;

    RCLCPP_INFO(get_logger(), "[%s] Time difference: %ld nanoseconds",
                msg->frame_id.c_str(), time_difference.nanoseconds());

    // Publish the time difference as an Int32 message
    auto time_diff_msg = std::make_unique<std_msgs::msg::UInt32>();
    time_diff_msg->data = static_cast<int32_t>(time_difference.nanoseconds());
    publisher_->publish(std::move(time_diff_msg));
  }

  rclcpp::Subscription<std_msgs::msg::Header>::SharedPtr subscription_;
  rclcpp::Publisher<std_msgs::msg::UInt32>::SharedPtr publisher_;
};

} // namespace composable_node_tutorials

// This function is needed to create a shared pointer to the node
#include <rclcpp_components/register_node_macro.hpp>
RCLCPP_COMPONENTS_REGISTER_NODE(
    composable_node_tutorials::HeaderSubscriberNode);

Launch file and compilation.

  1. Create a launch directory in your package.
  2. Add the following launch file to define two containers:
  • A multi-threaded container (_mt) containing both the publisher and a subscriber.
  • A single-threaded container containing only a subscriber.

To distinguish the two subscribers:

  • The subscriber in the multi-threaded container will be named sub_same_component.
  • The subscriber in the single-threaded container will be named sub_other_component.
import launch
import launch_ros.actions
import launch_ros.descriptions

def generate_launch_description():
    two_nodes_container = launch_ros.actions.ComposableNodeContainer(
        name='two_nodes_container',
        namespace='',
        package='rclcpp_components',
        executable='component_container_mt',
        composable_node_descriptions=[
            launch_ros.descriptions.ComposableNode(
                package='composable_nodes_tutorial',
                plugin='composable_node_tutorials::HeaderPublisherNode',
                name='header_publisher'
            ),
            launch_ros.descriptions.ComposableNode(
                package='composable_nodes_tutorial',
                plugin='composable_node_tutorials::HeaderSubscriberNode',
                name='sub_same_component'
            )
        ],
        output='screen'
    )

    one_node_container = launch_ros.actions.ComposableNodeContainer(
        name='one_node_container',
        namespace='',
        package='rclcpp_components',
        executable='component_container',
        composable_node_descriptions=[
            launch_ros.descriptions.ComposableNode(
                package='composable_nodes_tutorial',
                plugin='composable_node_tutorials::HeaderSubscriberNode',
                name='sub_other_component'
            )
        ],
        output='screen'
    )

    return launch.LaunchDescription([
        two_nodes_container,
        one_node_container
    ])

Modify the CMakeLists.txt file to compile and add the nodes as libraries, then register the components. Once this is done, compile the workspace with colcon and source the installation directory.

cmake_minimum_required(VERSION 3.8)
project(composable_nodes_tutorial)

if(CMAKE_COMPILER_IS_GNUCXX OR CMAKE_CXX_COMPILER_ID MATCHES "Clang")
  add_compile_options(-Wall -Wextra -Wpedantic)
endif()

# find dependencies
find_package(ament_cmake REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(std_msgs REQUIRED)

add_library(publisher SHARED
  src/publisher.cpp)
ament_target_dependencies(publisher rclcpp rclcpp_components std_msgs)

add_library(subscriber SHARED
  src/subscriber.cpp)
ament_target_dependencies(subscriber rclcpp rclcpp_components std_msgs)

rclcpp_components_register_node(
  publisher
  PLUGIN "composable_node_tutorials::HeaderPublisherNode"
  EXECUTABLE publisher_node
)

rclcpp_components_register_node(
  subscriber
  PLUGIN "composable_node_tutorials::HeaderSubscriberNode"
  EXECUTABLE subscriber_node
)

install(TARGETS publisher subscriber
        ARCHIVE DESTINATION lib
        LIBRARY DESTINATION lib
        RUNTIME DESTINATION bin
)

install(DIRECTORY launch
  DESTINATION share/${PROJECT_NAME}
)

ament_package()

Run the launch file and examine the results. You will see a lot of text related to the instantiation of the libraries. Look for the process and thread ID information that we printed for each topic.

In my case, the process ID for the container running both the publisher and subscriber is 53372. You can see in the console that the nodes header_publisher and sub_same_component share this process ID but have different thread IDs. This is because the container is multi-threaded, and each node runs in its own thread.

On the other hand, the node sub_other_component has a different process ID and thread ID, indicating that it runs in a separate process.

$ ros2 launch composable_nodes_tutorial composable_mt.launch.py 
[...]
**[component_container_mt-1] [INFO] [1741515035.935176176] [header_publisher]: Process ID: 53372 Thread ID: 140560229117760**
[...]
**[component_container-2] [INFO] [1741515035.939799439] [sub_other_component]: Process ID: 53374 Thread ID: 138242171260736**
**[component_container_mt-1] [INFO] [1741515035.940882304] [sub_same_component]: Process ID: 53372 Thread ID: 1405598490967**68

Once the nodes start running, you will be able to observe the latency of each communication. The sub_same_component node has a lower time difference, indicating reduced communication latency. This is because the nodes share data within the same process, which is inherently more efficient.

[component_container_mt-1] [INFO] [1741515036.935450044] [header_publisher]: Publishing: '0'
[component_container-2] [INFO] [1741515036.936191389] [**sub_other_component**]: [0] Time difference: **744809** nanoseconds
[component_container_mt-1] [INFO] [1741515036.936214070] [**sub_same_component**]: [0] Time difference: **770013** nanoseconds
[component_container_mt-1] [INFO] [1741515037.935411120] [header_publisher]: Publishing: '1'
[component_container_mt-1] [INFO] [1741515037.935697283] [**sub_same_component**]: [1] Time difference: **287670** nanoseconds
[component_container-2] [INFO] [1741515037.935809505] [**sub_other_component**]: [1] Time difference: **402620** nanoseconds

Visualize latency differences using Foxglove.

You can use Foxglove to better visualize the latency differences between nodes.

  1. Run the launch file along with a foxglove_bridge instance.
  2. Open Foxglove and add a Plot panel.
  3. Visualize the time_difference_topic for each node.

Interpreting the results.

  • The subscriber running in a different process (blue) experiences higher latency compared to the one in the same process (orange).
  • A higher time difference indicates worse performance.

Foxglove provides customized visualizations that can help with debugging. This method allows you to analyze latency between nodes and identify communication bottlenecks more effectively.

Exploring further with ComposableNodes.

Now that you understand how to improve your nodes’ communication, take a deeper dive into the possibilities that ComposableNodes offer.

In this tutorial, we used a simple message to demonstrate the latency difference between nodes running in separate processes. Now, imagine the potential latency reduction when using larger messages, such as a PointCloud.

There are even more configurations to experiment with and compare. For example:

  • What happens if the container is not multi-threaded?
  • How does message size impact communication latency?

By testing different setups, you can further optimize your ROS 2 nodes and gain deeper insights into efficient communication strategies.

In upcoming posts, we will dive deeper into how communication works in ROS 2 using DDS (Data Distribution Service).

Stay connected, ask questions, and join the discussion in our Discord community—we’d love to hear from you!

Read more

Start building with Foxglove.

Get started