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

Create N subscribers to N topics without knowing value of N

asked 2018-04-18 14:34:40 -0600

JoshMarino gravatar image

updated 2018-04-18 14:35:41 -0600

Hello,

Is there a way to create N subscribers to N topics that all have the same message structure, without knowing beforehand what the value of N is? N will be determined from a ROS parameter.

The topic names will be incrementing, such as /ROBOT_1/joint_states, /ROBOT_2/joint_states, ... , /ROBOT_N/joint_states. I have been able to modify the topicName to subscribe to successfully and confirmed this by logging the topicName from a for loop that goes up to N.

I am unsure of how to create N subscribers though inside the for loop that I am using. Also open to other methods that do not use a for loop if they exist. Any help would be appreciated.

Thanks!

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
3

answered 2018-04-18 16:13:46 -0600

lucasw gravatar image

updated 2018-04-18 16:14:11 -0600

I think you are asking something that makes use of #q63991 , the following example creates n subscribers and passes on information to the callback to be able to distinguish them:

#include "ros/ros.h"
#include "std_msgs/String.h"

void chatterCallback2(const std_msgs::String::ConstPtr& msg, const std::string topic)
{
  ROS_INFO_STREAM(topic << ": I heard: " << msg->data);
}

int main(int argc, char **argv)
{
  ros::init(argc, argv, "listener");
  ros::NodeHandle n;

  std::vector<ros::Subscriber> subs;

  int num = 10;
  ros::param::get("~num", num);
  for (size_t i = 0; i < num; ++i)
  {
    std::stringstream ss;
    ss << "topic_" << i;
    const std::string topic = ss.str();
    ros::Subscriber sub = n.subscribe<std_msgs::String>(topic, 10,
        boost::bind(chatterCallback2, _1, topic));
    subs.push_back(sub);
  }
  ros::spin();

  return 0;
}

A typical pattern a bit more complex than this would be to have a std::map using the topic names as keys and data in the callback is stored or manipulate using that map.

edit flag offensive delete link more

Comments

Thanks, I was able to get it to work with the std::map to access the data I needed. Is there a reason to store the subscriber in a std::vector using subs.push_back(sub)?

JoshMarino gravatar image JoshMarino  ( 2018-04-18 17:18:05 -0600 )edit

No, it is just a slightly simpler/more familiar example container than std::map.

lucasw gravatar image lucasw  ( 2018-04-18 18:03:21 -0600 )edit

Interesting, is it a better way of doing things than subscribing to MessageEvent to get the publisher informations ?

Cyril Jourdan gravatar image Cyril Jourdan  ( 2018-04-19 02:43:27 -0600 )edit

#q68434 suggests that it is- or at least used to be more reliable.

lucasw gravatar image lucasw  ( 2018-04-19 08:48:57 -0600 )edit

Question Tools

1 follower

Stats

Asked: 2018-04-18 14:34:40 -0600

Seen: 243 times

Last updated: Apr 18 '18