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

As described in the API docs, you can use that argument to publish a message to only the newly connected subscriber. A normal ros::Publisher publishes to every subscriber. It can also tell you the name of the newly subscribed node, which may be useful for debugging.

You almost never actually need that single-subscriber-publishing ability though. The obvious use case is sending the most recently published message to the new subscriber, but you can get that behavior just by advertising with latch=true.

In my code, I often want to know when nodes (un)subscribe to a topic, but I don't need the SingleSubscriberPublisher. I use this idiom:

class CameraDriver
{
  image_transport::ImageTransport it_;
  image_transport::CameraPublisher pub_;

  // NOTE: No SingleSubscriberPublisher argument
  void connectCb()
  {
    if (pub_.getNumSubscribers() == 0)
      stopCamera(); // Don't waste CPU if noone listening!
    else
      startCamera();
  }

  // In constructor or nodelet::onInit()
  CameraDriver()
  {
    // Monitor whether anyone is subscribed to the camera stream
    image_transport::SubscriberStatusCallback image_cb =
      boost::bind(&CameraDriver::connectCb, this);
    ros::SubscriberStatusCallback info_cb =
      boost::bind(&CameraDriver::connectCb, this);
    pub_ = it_.advertiseCamera("image_raw", 1, image_cb, image_cb,
                               info_cb, info_cb);
  }
};

There's a fair amount of C++ magic going on here. Let's break down this line:

ros::SubscriberStatusCallback info_cb = boost::bind(&CameraDriver::connectCb, this);

On the right side, we create a Boost.Bind object, binding our class instance this to its member function connectCb. The Boost.Bind object behaves like a functor; we could call it with no arguments (since connectCb has no arguments), and that would be the same as writing this->connectCb(). A sneaky feature of Boost.Bind is that we could also call it with any number of extra arguments; the Bind object would silently discard the extra arguments and again call this->connectCb().

Now we assign the Bind object to a ros::SubscriberStatusCallback, which is a typedef for boost::function<void(const ros::SingleSubscriberPublisher&)>. In other words, a functor taking a single argument of type ros::SingleSubscriberPublisher. info_cb is a Boost.Function object wrapping a Boost.Bind object wrapping this->connectCb().

Time passes, and a node subscribes to the camera info topic. Somewhere in the bowels of roscpp, our NodeHandle calls info_cb(pub), passing in a ros::SingleSubscriberPublisher. info_cb in turn calls the wrapped Bind object, which discards the argument and finally calls this->connectCb(). Voila!

I've complicated the example by using image_transport, but there's a reason for that. image_transport has its own image_transport::SingleSubscriberPublisher type mirroring the ROS version. By using the Bind trick, I can use connectCb for both image topics (possibly compressed by image_transport) and other message topics.