simple_publisher_plugin.h
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
35 #ifndef IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H
36 #define IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H
37 
39 #include <boost/scoped_ptr.hpp>
40 
41 namespace image_transport {
42 
60 template <class M>
62 {
63 public:
65 
66  virtual uint32_t getNumSubscribers() const
67  {
68  if (simple_impl_) return simple_impl_->pub_.getNumSubscribers();
69  return 0;
70  }
71 
72  virtual std::string getTopic() const
73  {
74  if (simple_impl_) return simple_impl_->pub_.getTopic();
75  return std::string();
76  }
77 
78  virtual void publish(const sensor_msgs::Image& message) const
79  {
80  if (!simple_impl_ || !simple_impl_->pub_) {
81  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::SimplePublisherPlugin");
82  return;
83  }
84 
86  }
87 
88  virtual void shutdown()
89  {
90  if (simple_impl_) simple_impl_->pub_.shutdown();
91  }
92 
93 protected:
94  virtual void advertiseImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
95  const SubscriberStatusCallback& user_connect_cb,
96  const SubscriberStatusCallback& user_disconnect_cb,
97  const ros::VoidPtr& tracked_object, bool latch)
98  {
99  std::string transport_topic = getTopicToAdvertise(base_topic);
100  ros::NodeHandle param_nh(transport_topic);
101  simple_impl_.reset(new SimplePublisherPluginImpl(param_nh));
102  simple_impl_->pub_ = nh.advertise<M>(transport_topic, queue_size,
105  tracked_object, latch);
106  }
107 
109  typedef boost::function<void(const M&)> PublishFn;
110 
119  virtual void publish(const sensor_msgs::Image& message, const PublishFn& publish_fn) const = 0;
120 
126  virtual std::string getTopicToAdvertise(const std::string& base_topic) const
127  {
128  return base_topic + "/" + getTransportName();
129  }
130 
137 
144 
148  const ros::NodeHandle& nh() const
149  {
150  return simple_impl_->param_nh_;
151  }
152 
160  {
162  return simple_impl_->pub_;
163  }
164 
165 private:
167  {
169  : param_nh_(nh)
170  {
171  }
172 
175  };
176 
177  boost::scoped_ptr<SimplePublisherPluginImpl> simple_impl_;
178 
180 
186  SubscriberStatusMemFn internal_cb_fn)
187  {
188  ros::SubscriberStatusCallback internal_cb = boost::bind(internal_cb_fn, this, _1);
189  if (user_cb)
190  return boost::bind(&SimplePublisherPlugin::subscriberCB, this, _1, user_cb, internal_cb);
191  else
192  return internal_cb;
193  }
194 
201  const SubscriberStatusCallback& user_cb,
202  const ros::SubscriberStatusCallback& internal_cb)
203  {
204  // First call the internal callback (for sending setup headers, etc.)
205  internal_cb(ros_ssp);
206 
207  // Construct a function object for publishing sensor_msgs::Image through the
208  // subclass-implemented publish() using the ros::SingleSubscriberPublisher to send
209  // messages of the transport-specific type.
210  typedef void (SimplePublisherPlugin::*PublishMemFn)(const sensor_msgs::Image&, const PublishFn&) const;
211  PublishMemFn pub_mem_fn = &SimplePublisherPlugin::publish;
212  ImagePublishFn image_publish_fn = boost::bind(pub_mem_fn, this, _1, bindInternalPublisher(ros_ssp));
213 
215  boost::bind(&SimplePublisherPlugin::getNumSubscribers, this),
216  image_publish_fn);
217  user_cb(ssp);
218  }
219 
220  typedef boost::function<void(const sensor_msgs::Image&)> ImagePublishFn;
221 
228  template <class PubT>
229  PublishFn bindInternalPublisher(const PubT& pub) const
230  {
231  // Bind PubT::publish(const Message&) as PublishFn
232  typedef void (PubT::*InternalPublishMemFn)(const M&) const;
233  InternalPublishMemFn internal_pub_mem_fn = &PubT::publish;
234  return boost::bind(internal_pub_mem_fn, &pub, _1);
235  }
236 };
237 
238 } //namespace image_transport
239 
240 #endif
PublishFn bindInternalPublisher(const PubT &pub) const
const ros::NodeHandle & nh() const
Returns the ros::NodeHandle to be used for parameter lookup.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
virtual std::string getTopic() const
Returns the communication topic that this PublisherPlugin will publish on.
const ros::Publisher & getPublisher() const
Returns the internal ros::Publisher.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void(SimplePublisherPlugin::* SubscriberStatusMemFn)(const ros::SingleSubscriberPublisher &pub)
virtual uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this PublisherPlugin.
boost::function< void(const M &)> PublishFn
Generic function for publishing the internal message type.
virtual std::string getTransportName() const =0
Get a string identifier for the transport provided by this plugin.
void subscriberCB(const ros::SingleSubscriberPublisher &ros_ssp, const SubscriberStatusCallback &user_cb, const ros::SubscriberStatusCallback &internal_cb)
#define ROS_ASSERT_MSG(cond,...)
std::string getSubscriberName() const
virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &user_connect_cb, const SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
Advertise a topic. Must be implemented by the subclass.
virtual void publish(const sensor_msgs::Image &message) const
Publish an image using the transport associated with this PublisherPlugin.
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
boost::scoped_ptr< SimplePublisherPluginImpl > simple_impl_
ros::SubscriberStatusCallback bindCB(const SubscriberStatusCallback &user_cb, SubscriberStatusMemFn internal_cb_fn)
Base class to simplify implementing most plugins to Publisher.
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
virtual void shutdown()
Shutdown any advertisements associated with this PublisherPlugin.
virtual std::string getTopicToAdvertise(const std::string &base_topic) const
Return the communication topic name for a given base topic.
virtual void connectCallback(const ros::SingleSubscriberPublisher &pub)
Function called when a subscriber connects to the internal publisher.
#define ROS_ASSERT(cond)
Base class for plugins to Publisher.
virtual void disconnectCallback(const ros::SingleSubscriberPublisher &pub)
Function called when a subscriber disconnects from the internal publisher.


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:14:58