Single Thread of ROS 2, Not Necessarily FIFO. Could be "Round Robin"

May 12, 2023
This article describes the "round robin" property of callback queue handling in single threaded executioner of ROS2.
  • A topic is being published at every 0.1s. But what if the subscription callback takes 2s to complete?

  • Things more difficult: assume another topic is being published at every 1s, and the corresponding callback takes 2s to complete. What will happen?

As always, full repo (opens in a new tab) will help you understand my article.

System description

1. Publisher node

As seen in my repo, publisher node (opens in a new tab) sends two topics:

  • short_topic (std_msgs::msg::String) contains "Short message (seq=n)". published at every 0.1 seconds.
  • long_topic (std_msgs::msg::String) contains "Long message with more characters (seq=n)" published at every 1 seconds

The terminal running this node will be filled with:

jbs@jbs:~/ros2_ws$ ros2 run simple_thread_tester publisher_node
[INFO] [1683887896.059494499] [publisher_node]: Short message (seq=0)
[INFO] [1683887896.159467510] [publisher_node]: Short message (seq=1)
[INFO] [1683887896.259429220] [publisher_node]: Short message (seq=2)
[INFO] [1683887896.359399631] [publisher_node]: Short message (seq=3)
[INFO] [1683887896.459470942] [publisher_node]: Short message (seq=4)
[INFO] [1683887896.559485153] [publisher_node]: Short message (seq=5)
[INFO] [1683887896.659439163] [publisher_node]: Short message (seq=6)
[INFO] [1683887896.759430374] [publisher_node]: Short message (seq=7)
[INFO] [1683887896.859516185] [publisher_node]: Short message (seq=8)
[INFO] [1683887896.959506295] [publisher_node]: Short message (seq=9)
[INFO] [1683887896.959585095] [publisher_node]: Long message with more characters (seq=0)
[INFO] [1683887897.059511206] [publisher_node]: Short message (seq=10)
[INFO] [1683887897.159551517] [publisher_node]: Short message (seq=11)

2. Subscriber node

This node (opens in a new tab) receives the messages and add stars to the strings in the callbacks. We assume that the process takes 2s. It logs when the processed messages are assigned to member variables processed_[short|long]_string_.

std::string
SingleThreadSubscriber::ProcessString(const std::string &raw_string) {
  std::this_thread::sleep_for(
      std::chrono::seconds(2));
  return "** " + raw_string + " **";
};
 
void SingleThreadSubscriber::ShortTopicCallback(
    const std_msgs::msg::String::SharedPtr msg) {
  auto processed_string = ProcessString(msg->data);
  processed_short_string_ = processed_string;
 
  RCLCPP_INFO(get_logger(), "Setting processed:  %s", processed_string.c_str());
  processed_long_string_ = processed_string;
}

In this example, queue size for each topic is 10.

Results

When we have only one subscription (short_topic)

For the warm start of this article, we turn off long_topic for this moment. This is what you got: (ran the subscriber first and then run the publisher to receive the first message (seq=0)).

jbs@jbs:~/ros2_ws$ ros2 run simple_thread_tester single_thread_subscriber_node
[INFO] [1683892563.019044644] [subscriber_node]: Setting processed:  ** Short message (seq=0) **
[INFO] [1683892565.019393903] [subscriber_node]: Setting processed:  ** Short message (seq=11) **
[INFO] [1683892567.019764462] [subscriber_node]: Setting processed:  ** Short message (seq=31) **
[INFO] [1683892569.020280921] [subscriber_node]: Setting processed:  ** Short message (seq=51) **
[INFO] [1683892571.020717795] [subscriber_node]: Setting processed:  ** Short message (seq=71) **
[INFO] [1683892573.021227080] [subscriber_node]: Setting processed:  ** Short message (seq=91) **

We can understand this by below figure:

Basically, all the un-processed but received messages are kept in the queue which keeps the last 10 recent ones. In the queue, the callback executes the oldest message, meaning this is FIFO for a windowed queue.

When we have multiple subscriptions (short_topic + long_topic)

How about multiple subscriptions? Look at the result:

jbs@jbs:~/ros2_ws$ ros2 run simple_thread_tester publisher_node
[INFO] [1683894668.624166654] [publisher_node]: Short message (seq=0)
[INFO] [1683894668.724130171] [publisher_node]: Short message (seq=1)
...
[INFO] [1683894669.324059245] [publisher_node]: Short message (seq=7)
[INFO] [1683894669.424071655] [publisher_node]: Short message (seq=8)
[INFO] [1683894669.524063964] [publisher_node]: Short message (seq=9)
[INFO] [1683894669.524152364] [publisher_node]: Long message with more characters (seq=0)
[INFO] [1683894669.624062974] [publisher_node]: Short message (seq=10)
[INFO] [1683894669.724067284] [publisher_node]: Short message (seq=11)
...
[INFO] [1683894670.324058842] [publisher_node]: Short message (seq=17)
[INFO] [1683894670.424134452] [publisher_node]: Short message (seq=18)
[INFO] [1683894670.524142561] [publisher_node]: Short message (seq=19)
[INFO] [1683894670.524231561] [publisher_node]: Long message with more characters (seq=1)
[INFO] [1683894670.624083071] [publisher_node]: Short message (seq=20)
[INFO] [1683894670.724145681] [publisher_node]: Short message (seq=21)
[INFO] [1683894670.824147191] [publisher_node]: Short message (seq=22)
[INFO] [1683894670.924142000] [publisher_node]: Short message (seq=23)
[INFO] [1683894671.024082010] [publisher_node]: Short message (seq=24)
...
[INFO] [1683894673.524314353] [publisher_node]: Long message with more characters (seq=4)
[INFO] [1683894673.624170363] [publisher_node]: Short message (seq=50)
[INFO] [1683894673.724175873] [publisher_node]: Short message (seq=51)
[INFO] [1683894673.824151782] [publisher_node]: Short message (seq=52)
...
 

If the callback is processed FIFO way, the below result cannot happen:

jbs@jbs:~/ros2_ws$ ros2 run simple_thread_tester single_thread_subscriber_node
[INFO] [1683894670.625043871] [subscriber_node]: Setting processed:  ** Short message (seq=0) **
[INFO] [1683894672.625351266] [subscriber_node]: Setting processed:  ** Short message (seq=11) **
[INFO] [1683894674.625609360] [subscriber_node]: Setting processed:  ** Long message with more characters (seq=0) **
[INFO] [1683894676.626140755] [subscriber_node]: Setting processed:  ** Short message (seq=51) **
[INFO] [1683894678.626555792] [subscriber_node]: Setting processed:  ** Long message with more characters (seq=1) **
[INFO] [1683894680.626834938] [subscriber_node]: Setting processed:  ** Short message (seq=91) **
[INFO] [1683894682.627043984] [subscriber_node]: Setting processed:  ** Long message with more characters (seq=2) **
[INFO] [1683894684.627390029] [subscriber_node]: Setting processed:  ** Short message (seq=131) **

Callbacks for long and short messages are taking turns regardless of their published orders. This is due to the policy of callback processing order (opens in a new tab): round-robin (opens in a new tab) across topics.