publisher.cpp
Go to the documentation of this file.
00001 /*********************************************************************
00002 * Software License Agreement (BSD License)
00003 * 
00004 *  Copyright (c) 2009, Willow Garage, Inc.
00005 *  All rights reserved.
00006 * 
00007 *  Redistribution and use in source and binary forms, with or without
00008 *  modification, are permitted provided that the following conditions
00009 *  are met:
00010 * 
00011 *   * Redistributions of source code must retain the above copyright
00012 *     notice, this list of conditions and the following disclaimer.
00013 *   * Redistributions in binary form must reproduce the above
00014 *     copyright notice, this list of conditions and the following
00015 *     disclaimer in the documentation and/or other materials provided
00016 *     with the distribution.
00017 *   * Neither the name of the Willow Garage nor the names of its
00018 *     contributors may be used to endorse or promote products derived
00019 *     from this software without specific prior written permission.
00020 * 
00021 *  THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
00022 *  "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
00023 *  LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
00024 *  FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
00025 *  COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
00026 *  INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
00027 *  BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
00028 *  LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00029 *  CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
00030 *  LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
00031 *  ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
00032 *  POSSIBILITY OF SUCH DAMAGE.
00033 *********************************************************************/
00034 
00035 #include "image_transport/publisher.h"
00036 #include "image_transport/publisher_plugin.h"
00037 #include <pluginlib/class_loader.h>
00038 #include <boost/ptr_container/ptr_vector.hpp>
00039 #include <boost/foreach.hpp>
00040 #include <boost/algorithm/string/erase.hpp>
00041 
00042 // Workaround for #5357, #5380: failure to compile in some cases because for some
00043 // compilers Boost.Foreach's const rvalue detection fails, and it tries to make a
00044 // copy of abstract class PublisherPlugin.
00045 // See https://svn.boost.org/trac/boost/ticket/3996 for details.
00046 namespace boost { namespace foreach {
00047   template <>
00048   struct is_noncopyable<ptr_vector<image_transport::PublisherPlugin> > : mpl::true_ {};
00049 }}
00050 
00051 namespace image_transport {
00052 
00053 struct Publisher::Impl
00054 {
00055   Impl()
00056     : unadvertised_(false)
00057   {
00058   }
00059 
00060   ~Impl()
00061   {
00062     shutdown();
00063   }
00064 
00065   uint32_t getNumSubscribers() const
00066   {
00067     uint32_t count = 0;
00068     BOOST_FOREACH(const PublisherPlugin& pub, publishers_)
00069       count += pub.getNumSubscribers();
00070     return count;
00071   }
00072 
00073   std::string getTopic() const
00074   {
00075     return base_topic_;
00076   }
00077 
00078   bool isValid() const
00079   {
00080     return !unadvertised_;
00081   }
00082   
00083   void shutdown()
00084   {
00085     if (!unadvertised_) {
00086       unadvertised_ = true;
00087       BOOST_FOREACH(PublisherPlugin& pub, publishers_)
00088         pub.shutdown();
00089       publishers_.clear();
00090     }
00091   }
00092 
00093   void subscriberCB(const SingleSubscriberPublisher& plugin_pub,
00094                     const SubscriberStatusCallback& user_cb)
00095   {
00096     SingleSubscriberPublisher ssp(plugin_pub.getSubscriberName(), getTopic(),
00097                                   boost::bind(&Publisher::Impl::getNumSubscribers, this),
00098                                   plugin_pub.publish_fn_);
00099     user_cb(ssp);
00100   }
00101   
00102   std::string base_topic_;
00103   PubLoaderPtr loader_;
00104   boost::ptr_vector<PublisherPlugin> publishers_;
00105   bool unadvertised_;
00106   //double constructed_;
00107 };
00108 
00109 
00110 Publisher::Publisher(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00111                      const SubscriberStatusCallback& connect_cb,
00112                      const SubscriberStatusCallback& disconnect_cb,
00113                      const ros::VoidPtr& tracked_object, bool latch,
00114                      const PubLoaderPtr& loader)
00115   : impl_(new Impl)
00116 {
00117   // Resolve the name explicitly because otherwise the compressed topics don't remap
00118   // properly (#3652).
00119   impl_->base_topic_ = nh.resolveName(base_topic);
00120   impl_->loader_ = loader;
00121   
00122   BOOST_FOREACH(const std::string& lookup_name, loader->getDeclaredClasses()) {
00123     try {
00124       PublisherPlugin* pub = loader->createClassInstance(lookup_name);
00125       impl_->publishers_.push_back(pub);
00126       pub->advertise(nh, impl_->base_topic_, queue_size, rebindCB(connect_cb),
00127                      rebindCB(disconnect_cb), tracked_object, latch);
00128     }
00129     catch (const std::runtime_error& e) {
00130       ROS_DEBUG("Failed to load plugin %s, error string: %s",
00131                 lookup_name.c_str(), e.what());
00132     }
00133   }
00134 
00135   if (impl_->publishers_.empty())
00136     throw Exception("No plugins found! Does `rospack plugins --attrib=plugin "
00137                     "image_transport` find any packages?");
00138 }
00139 
00140 uint32_t Publisher::getNumSubscribers() const
00141 {
00142   if (impl_ && impl_->isValid()) return impl_->getNumSubscribers();
00143   return 0;
00144 }
00145 
00146 std::string Publisher::getTopic() const
00147 {
00148   if (impl_) return impl_->getTopic();
00149   return std::string();
00150 }
00151 
00152 void Publisher::publish(const sensor_msgs::Image& message) const
00153 {
00154   if (!impl_ || !impl_->isValid()) {
00155     ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
00156     return;
00157   }
00158   
00159   BOOST_FOREACH(const PublisherPlugin& pub, impl_->publishers_) {
00160     if (pub.getNumSubscribers() > 0)
00161       pub.publish(message);
00162   }
00163 }
00164 
00165 void Publisher::publish(const sensor_msgs::ImageConstPtr& message) const
00166 {
00167   if (!impl_ || !impl_->isValid()) {
00168     ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::Publisher");
00169     return;
00170   }
00171   
00172   BOOST_FOREACH(const PublisherPlugin& pub, impl_->publishers_) {
00173     if (pub.getNumSubscribers() > 0)
00174       pub.publish(message);
00175   }
00176 }
00177 
00178 void Publisher::shutdown()
00179 {
00180   if (impl_) {
00181     impl_->shutdown();
00182     impl_.reset();
00183   }
00184 }
00185 
00186 Publisher::operator void*() const
00187 {
00188   return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0;
00189 }
00190 
00191 void Publisher::weakSubscriberCb(const ImplWPtr& impl_wptr,
00192                                  const SingleSubscriberPublisher& plugin_pub,
00193                                  const SubscriberStatusCallback& user_cb)
00194 {
00195   if (ImplPtr impl = impl_wptr.lock())
00196     impl->subscriberCB(plugin_pub, user_cb);
00197 }
00198 
00199 SubscriberStatusCallback Publisher::rebindCB(const SubscriberStatusCallback& user_cb)
00200 {
00201   // Note: the subscriber callback must be bound to the internal Impl object, not
00202   // 'this'. Due to copying behavior the Impl object may outlive the original Publisher
00203   // instance. But it should not outlive the last Publisher, so we use a weak_ptr.
00204   if (user_cb)
00205   {
00206     ImplWPtr impl_wptr(impl_);
00207     return boost::bind(&Publisher::weakSubscriberCb, impl_wptr, _1, user_cb);
00208   }
00209   else
00210     return SubscriberStatusCallback();
00211 }
00212 
00213 } //namespace image_transport


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 3 2014 11:24:08