publisher.cpp
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 
37 #include <pluginlib/class_loader.h>
38 #include <boost/foreach.hpp>
39 #include <boost/algorithm/string/erase.hpp>
40 
41 namespace image_transport {
42 
44 {
45  Impl()
46  : unadvertised_(false)
47  {
48  }
49 
51  {
52  shutdown();
53  }
54 
55  uint32_t getNumSubscribers() const
56  {
57  uint32_t count = 0;
58  BOOST_FOREACH(const boost::shared_ptr<PublisherPlugin>& pub, publishers_)
59  count += pub->getNumSubscribers();
60  return count;
61  }
62 
63  std::string getTopic() const
64  {
65  return base_topic_;
66  }
67 
68  bool isValid() const
69  {
70  return !unadvertised_;
71  }
72 
73  void shutdown()
74  {
75  if (!unadvertised_) {
76  unadvertised_ = true;
78  pub->shutdown();
79  publishers_.clear();
80  }
81  }
82 
83  void subscriberCB(const SingleSubscriberPublisher& plugin_pub,
84  const SubscriberStatusCallback& user_cb)
85  {
87  boost::bind(&Publisher::Impl::getNumSubscribers, this),
88  plugin_pub.publish_fn_);
89  user_cb(ssp);
90  }
91 
92  std::string base_topic_;
94  std::vector<boost::shared_ptr<PublisherPlugin> > publishers_;
96  //double constructed_;
97 };
98 
99 
100 Publisher::Publisher(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
101  const SubscriberStatusCallback& connect_cb,
102  const SubscriberStatusCallback& disconnect_cb,
103  const ros::VoidPtr& tracked_object, bool latch,
104  const PubLoaderPtr& loader)
105  : impl_(new Impl)
106 {
107  // Resolve the name explicitly because otherwise the compressed topics don't remap
108  // properly (#3652).
109  impl_->base_topic_ = nh.resolveName(base_topic);
110  impl_->loader_ = loader;
111 
112  std::vector<std::string> blacklist_vec;
113  std::set<std::string> blacklist;
114  nh.getParam(impl_->base_topic_ + "/disable_pub_plugins", blacklist_vec);
115  for (size_t i = 0; i < blacklist_vec.size(); ++i)
116  {
117  blacklist.insert(blacklist_vec[i]);
118  }
119 
120  BOOST_FOREACH(const std::string& lookup_name, loader->getDeclaredClasses()) {
121  const std::string transport_name = boost::erase_last_copy(lookup_name, "_pub");
122  if (blacklist.count(transport_name))
123  {
124  continue;
125  }
126 
127  try {
128  boost::shared_ptr<PublisherPlugin> pub = loader->createInstance(lookup_name);
129  impl_->publishers_.push_back(pub);
130  pub->advertise(nh, impl_->base_topic_, queue_size, rebindCB(connect_cb),
131  rebindCB(disconnect_cb), tracked_object, latch);
132  }
133  catch (const std::runtime_error& e) {
134  ROS_DEBUG("Failed to load plugin %s, error string: %s",
135  lookup_name.c_str(), e.what());
136  }
137  }
138 
139  if (impl_->publishers_.empty())
140  throw Exception("No plugins found! Does `rospack plugins --attrib=plugin "
141  "image_transport` find any packages?");
142 }
143 
145 {
146  if (impl_ && impl_->isValid()) return impl_->getNumSubscribers();
147  return 0;
148 }
149 
150 std::string Publisher::getTopic() const
151 {
152  if (impl_) return impl_->getTopic();
153  return std::string();
154 }
155 
156 void Publisher::publish(const sensor_msgs::Image& message) const
157 {
158  if (!impl_ || !impl_->isValid()) {
159  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
160  return;
161  }
162 
163  BOOST_FOREACH(const boost::shared_ptr<PublisherPlugin>& pub, impl_->publishers_) {
164  if (pub->getNumSubscribers() > 0)
165  pub->publish(message);
166  }
167 }
168 
169 void Publisher::publish(const sensor_msgs::ImageConstPtr& message) const
170 {
171  if (!impl_ || !impl_->isValid()) {
172  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
173  return;
174  }
175 
176  BOOST_FOREACH(const boost::shared_ptr<PublisherPlugin>& pub, impl_->publishers_) {
177  if (pub->getNumSubscribers() > 0)
178  pub->publish(message);
179  }
180 }
181 
183 {
184  if (impl_) {
185  impl_->shutdown();
186  impl_.reset();
187  }
188 }
189 
190 Publisher::operator void*() const
191 {
192  return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0;
193 }
194 
195 void Publisher::weakSubscriberCb(const ImplWPtr& impl_wptr,
196  const SingleSubscriberPublisher& plugin_pub,
197  const SubscriberStatusCallback& user_cb)
198 {
199  if (ImplPtr impl = impl_wptr.lock())
200  impl->subscriberCB(plugin_pub, user_cb);
201 }
202 
204 {
205  // Note: the subscriber callback must be bound to the internal Impl object, not
206  // 'this'. Due to copying behavior the Impl object may outlive the original Publisher
207  // instance. But it should not outlive the last Publisher, so we use a weak_ptr.
208  if (user_cb)
209  {
210  ImplWPtr impl_wptr(impl_);
211  return boost::bind(&Publisher::weakSubscriberCb, impl_wptr, _1, user_cb);
212  }
213  else
214  return SubscriberStatusCallback();
215 }
216 
217 } //namespace image_transport
static void weakSubscriberCb(const ImplWPtr &impl_wptr, const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
Definition: publisher.cpp:195
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this Publisher. ...
Definition: publisher.cpp:144
SubscriberStatusCallback rebindCB(const SubscriberStatusCallback &user_cb)
Definition: publisher.cpp:203
boost::weak_ptr< Impl > ImplWPtr
Definition: publisher.h:111
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
uint32_t getNumSubscribers() const
Definition: publisher.cpp:55
void shutdown()
Shutdown the advertisements associated with this Publisher.
Definition: publisher.cpp:182
bool getParam(const std::string &key, std::string &s) const
#define ROS_ASSERT_MSG(cond,...)
std::string resolveName(const std::string &name, bool remap=true) const
std::string getTopic() const
Definition: publisher.cpp:63
void publish(const sensor_msgs::Image &message) const
Publish an image on the topics associated with this Publisher.
Definition: publisher.cpp:156
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
A base class for all image_transport exceptions inheriting from std::runtime_error.
Definition: exception.h:45
void subscriberCB(const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
Definition: publisher.cpp:83
std::vector< boost::shared_ptr< PublisherPlugin > > publishers_
Definition: publisher.cpp:94
std::string getTopic() const
Returns the base topic of this Publisher.
Definition: publisher.cpp:150
#define ROS_DEBUG(...)


image_transport
Author(s): Patrick Mihelich
autogenerated on Mon Feb 28 2022 22:31:45