ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

how to implement multiple subscribers simply

asked 2020-01-13 01:24:54 -0500

marney gravatar image

I am studying ROS2 dashing. I 'd like to create many simple subscribers which subscribe same topic and test CPU performance. Now I am trying as follws. This is a example which two subscribers run. I'd like to test a case in which ,for example, 100 subscribers are running. Is there any better way to realize multiple such ? Thanks.

//subnodes.hpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/int16.hpp>

class MinimalSubscriber1:public rclcpp::Node{
private:
    rclcpp::Subscription<std_msgs::msg::Int16>::SharedPtr subscription_;
    void topic_callback_(const std_msgs::msg::Int16::SharedPtr msg);
public:
    MinimalSubscriber1();
};

class MinimalSubscriber2:public rclcpp::Node{
private:
    rclcpp::Subscription<std_msgs::msg::Int16>::SharedPtr subscription_;
    void topic_callback_(const std_msgs::msg::Int16::SharedPtr msg);
public:
    MinimalSubscriber2();
};

//subnodes.cpp
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/int16.hpp>
#include "subnodes.hpp"

void MinimalSubscriber1::topic_callback_(const std_msgs::msg::Int16::SharedPtr msg){
    RCLCPP_INFO(this->get_logger(), "No.1 heard:%d",msg->data);
}
 MinimalSubscriber1::MinimalSubscriber1()
:Node("minimal_subscriber_test1"){
    subscription_ = this->create_subscription<std_msgs::msg::Int16>(
        "testtopic",
        std::bind(&MinimalSubscriber1::topic_callback_,this,std::placeholders::_1)
    );
}

void MinimalSubscriber2::topic_callback_(const std_msgs::msg::Int16::SharedPtr msg){
    RCLCPP_INFO(this->get_logger(), "No.2 heard:%d",msg->data);
}
 MinimalSubscriber2::MinimalSubscriber2()
:Node("minimal_subscriber_test2"){
    subscription_ = this->create_subscription<std_msgs::msg::Int16>(
        "testtopic",
        std::bind(&MinimalSubscriber2::topic_callback_,this,std::placeholders::_1)
    );
}

//main.cpp
#include <rclcpp/rclcpp.hpp>
#include "subnodes.hpp"

int main(int argc,char*argv[]){
  rclcpp::init(argc,argv);
  rclcpp::executors::SingleThreadedExecutor exec;

  auto node1 = std::make_shared<MinimalSubscriber1>();
  auto node2 = std::make_shared<MinimalSubscriber2>();
  exec.add_node(node1);
  exec.add_node(node2);
  exec::spin();
  rclcpp::shutdown();
  return 0;
}
edit retag flag offensive close merge delete

Comments

Long answer: Have a look here: https://discourse.ros.org/t/singlethr... And here: https://github.com/nobleo/ros2_perfor...

Short answer: You can create subscribers in a loop but you have to save a pointer to the subscribers outside of the loop

std::vector<rclcpp::Subscription<String>::SharedPtr> sub_refs;

for (int s = 0; s < amount of subs; ++s) {
      auto sub = node->create_subscription<String>("topic_name", qos,
                                                   [](String::SharedPtr) {});
      sub_refs.push_back(sub);
    }

I'm not sure if the example is using the dashing API, but a similar implementation should be possible in dashing. The important thing is that you have the sub_refs declared outside of the loop.

Full example of source code can be found at the nobleo github on the dashing branch in the source folder. Look for ros.cc , that one partly does what you want.

MCornelis gravatar image MCornelis  ( 2020-01-13 02:24:21 -0500 )edit

Just a heads up, working with CPU utilization is not as straight-forward as some people might think. Especially when dealing with big.LITTLE configurations and other factors that might influence CPU utilization. The results you can find in the discourse post and on the nobleo github are all hardware and software specific and the tests may return different results on your setup.

MCornelis gravatar image MCornelis  ( 2020-01-13 02:31:18 -0500 )edit

1 Answer

Sort by ยป oldest newest most voted
1

answered 2020-01-13 02:51:29 -0500

MCornelis gravatar image

updated 2020-01-13 02:55:39 -0500

Simple example to make n nodes that all have 1 subscriber that subscribes to the topic "topic_name":

  #include <rclcpp/rclcpp.hpp>
  #include <std_msgs/msg/string.hpp>

  int main() {
  using namespace std_msgs::msg;
  rclcpp::init(0, nullptr);

  n = 100; // create this many nodes

  rclcpp::executors::SingleThreadedExecutor exec; // create executor
  std::vector<rclcpp::Node::SharedPtr> node_refs; // create vector to store node references
  std::vector<rclcpp::Subscription<String>::SharedPtr> sub_refs; // create vector to store sub references

  for (int i = 0; i < n; i++) { 
    auto node = std::make_shared<rclcpp::Node>("node_" + std::to_string(i)); // create a node
    auto sub = node->create_subscription<String>("topic_name", qos,
                                                   [](String::SharedPtr) {}); // add a sub to the node
    sub_refs.push_back(sub); // save a referene to the sub
    node_refs.push_back(node); // save  a reference to the node
    exec.add_node(node); // add the node with the sub to executor
  } 
  exec.spin(); // spin everything
  rclcpp::shutdown();
  return 0;
}
edit flag offensive delete link more

Comments

Nodes also add CPU overhead btw. An explanation can be found here: https://discourse.ros.org/t/reconside... So you could also consider creating 1 node and adding n subscribers to it (instead of n nodes with 1 sub each).

MCornelis gravatar image MCornelis  ( 2020-01-13 02:55:05 -0500 )edit

Thank you so much for reply. I could test the case in multiple nodes

you could also consider creating 1 node and adding n subscribers to it

Yes, the idea should be considered.

Thanks.

marney gravatar image marney  ( 2020-01-16 21:11:18 -0500 )edit

Question Tools

Stats

Asked: 2020-01-13 01:24:54 -0500

Seen: 3,402 times

Last updated: Jan 13 '20