Robotics StackExchange | Archived questions

maximum number of subscribers per topic

Hi, I'm using ROS2 Bouncy.

I have one node which publishes std_msgs::msg::Header messages on a topic at a relatively slow frequency (4 Hz).

Then I created N other nodes, each of them subscribing to this topic. My goal was to make some performance evaluations.

I noticed that as the number of subscriber nodes increases over 10 I observe that some of them haven't received any message. For example, when running 20 subscribers I have seen up to 8-10 nodes not receiving anything. The exact number changes every time I run my test.

I tried to run each node in a detached std::thread, add all the nodes to a rclcpp::executors::SingleThreadedExecutor or running all them in separate processes. The results are the same.

Do you have any idea why?

If you want to have a look at my code, you can find the std::thread version here (and online):

#include <chrono>
#include <inttypes.h>
#include <memory>
#include <iostream>
#include <thread>
#include <cstdlib>
#include <sstream>
#include <map>
#include <set>
#include <algorithm>
#include <functional>

#include "rclcpp/rclcpp.hpp"
#include "std_msgs/msg/string.hpp"

#include "multi-node.hpp"

int main(int argc, char** argv) {
  rclcpp::init(argc, argv);

  int n_subscribers = 2;
  int n_publishers = 1;
  int test_duration = 5;

  if (argc >= 2) {
    n_subscribers = atoi(argv[1]);

    if (argc >= 3) {
      n_publishers = atoi(argv[2]);

      if (argc >= 4) {
        test_duration = atoi(argv[3]);
      }
    }
  }

  std::vector<std::shared_ptr<MultiNode>> vec;

  for (int i = 0; i < n_subscribers; i++) {
    int node_id = i;
    auto node = std::make_shared<MultiNode>(node_id);

    for (int k = 0; k < n_publishers; k++) {
      int subscriber_id = k + n_subscribers;
      node->add_subscriber(subscriber_id);
    }

    vec.push_back(node);

    std::thread thread1(
        static_cast<void (*)(rclcpp::Node::SharedPtr)>(rclcpp::spin), node);
    thread1.detach();
  }

  std::cout << "Subscribers created!" << std::endl;

  for (int i = 0; i < n_publishers; i++) {
    int node_id = i + n_subscribers;
    auto node = std::make_shared<MultiNode>(node_id);

    int publisher_id = node_id;
    node->add_publisher(publisher_id);

    vec.push_back(node);
    std::thread thread1(&MultiNode::simple_publisher_task, node);
    thread1.detach();
  }

  std::cout << "Publishers created!" << std::endl;

  std::this_thread::sleep_for(std::chrono::seconds(test_duration));

  rclcpp::shutdown();

  std::cout << "rclcpp::shutdown" << std::endl;

  for (int i = 0; i < n_subscribers; i++) {
    std::string name = vec[i]->get_name();

    auto durations_map = vec[i]->stats.subscription_delta_times;

    for (auto const& map_item : durations_map) {
      int topic_id = map_item.first;

      auto duration = map_item.second.first;
      int num_msgs = map_item.second.second;

      float mean = 0;
      if (num_msgs != 0) mean = (float)duration / (float)num_msgs;

      std::cout << name << ": topic " << topic_id << " --> " << mean << "  #"
                << num_msgs << std::endl;
    }
  }

  std::cout << "End test" << std::endl;

  return 0;
}

Asked by alsora on 2018-11-16 19:48:09 UTC

Comments

The example is not too long, so let's keep it here in the question. If your example repository ever disapppears, this question would otherwise lose a lot of its value and future users would not be able to read your code.

Asked by gvdhoorn on 2018-11-17 04:22:43 UTC

Please cross-reference when cross-posting: https://github.com/ros2/rmw_fastrtps/issues/249

Asked by Dirk Thomas on 2019-01-02 14:34:40 UTC

Answers