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

Revision history [back]

click to hide/show revision 1
initial version

You can use subscriber status callbacks for this.

See the documentation for NodeHandle::advertise<..>(..):

Advertise a topic, with most of the available options, including subscriber status callbacks

This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.

This version of advertise allows you to pass functions to be called when new subscribers connect and disconnect. With bare functions it can be used like so:

void connectCallback(const ros::SingleSubscriberPublisher& pub)
{
  // Do something
}
handle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)connectCallback);

With class member functions it can be used with boost::bind:

void MyClass::connectCallback(const ros::SingleSubscriberPublisher& pub)
{
  // Do something
}

MyClass my_class;
ros::Publisher pub = handle.advertise<std_msgs::Empty>(
  "my_topic", 1, boost::bind(
    &MyClass::connectCallback, my_class, boost::placeholders::_1));

The callback will be called whenever subscription state changes.

At any one time, only a small number of the final output topics will actually be needed so it would be great if the information about which computation is necessary could ripple back through the network of nodes with each node automatically unsubscribing to the inputs that aren't relevant to the given outputs, and then resubscribing again as and when they recieve new subscribers to the relevant topic.

(I know lazy publishing is a thing, and you can check how many subscribers there are before doing the computational work needed to publish on a topic - but that doesn't help here with chains of nodes)

From your description it does sound like services or actions would be a better choice for the kind of interaction you're trying to implement.

If work should be done when a client wants it, publish-subscribe is not the best pattern to use, as it completely decouples everything, including when something is to be done (ie: the time dimension).

Services and actions place the client firmly in control over when work should be performed.

Using creation and destruction of subscriptions to signal that seems like a poor substitute.

(note: you tagged this with melodic, so this is a ROS 1 answer)

You can use subscriber status callbacks for this.

this. See #q335811 and #q11327.

For the details, see the documentation for NodeHandle::advertise<..>(..):

Advertise a topic, with most of the available options, including subscriber status callbacks

This call connects to the master to publicize that the node will be publishing messages on the given topic. This method returns a Publisher that allows you to publish a message on this topic.

This version of advertise allows you to pass functions to be called when new subscribers connect and disconnect. With bare functions it can be used like so:

void connectCallback(const ros::SingleSubscriberPublisher& pub)
{
  // Do something
}
handle.advertise<std_msgs::Empty>("my_topic", 1, (ros::SubscriberStatusCallback)connectCallback);

With class member functions it can be used with boost::bind:

void MyClass::connectCallback(const ros::SingleSubscriberPublisher& pub)
{
  // Do something
}

MyClass my_class;
ros::Publisher pub = handle.advertise<std_msgs::Empty>(
  "my_topic", 1, boost::bind(
    &MyClass::connectCallback, my_class, boost::placeholders::_1));

The callback will be called whenever subscription state changes.

At any one time, only a small number of the final output topics will actually be needed so it would be great if the information about which computation is necessary could ripple back through the network of nodes with each node automatically unsubscribing to the inputs that aren't relevant to the given outputs, and then resubscribing again as and when they recieve new subscribers to the relevant topic.

(I know lazy publishing is a thing, and you can check how many subscribers there are before doing the computational work needed to publish on a topic - but that doesn't help here with chains of nodes)

From your description it does sound like services or actions would be a better choice for the kind of interaction you're trying to implement.

If work should be done when a client wants it, publish-subscribe is not the best pattern to use, as it completely decouples everything, including when something is to be done (ie: the time dimension).

Services and actions place the client firmly in control over when work should be performed.

Using creation and destruction of subscriptions to signal that seems like a poor substitute.


Edit: an alternative could be to use ros::topic::waitForMessage(..) and create your "chain" like that.

Seems even nastier though.