subscriber.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/subscriber.h"
00036 #include "image_transport/subscriber_plugin.h"
00037 #include <ros/names.h>
00038 #include <pluginlib/class_loader.h>
00039 #include <boost/scoped_ptr.hpp>
00040 
00041 namespace image_transport {
00042 
00043 struct Subscriber::Impl
00044 {
00045   Impl()
00046     : unsubscribed_(false)
00047   {
00048   }
00049 
00050   ~Impl()
00051   {
00052     shutdown();
00053   }
00054 
00055   bool isValid() const
00056   {
00057     return !unsubscribed_;
00058   }
00059 
00060   void shutdown()
00061   {
00062     if (!unsubscribed_) {
00063       unsubscribed_ = true;
00064       if (subscriber_)
00065         subscriber_->shutdown();
00066     }
00067   }
00068   
00069   SubLoaderPtr loader_;
00070   boost::shared_ptr<SubscriberPlugin> subscriber_;
00071   bool unsubscribed_;
00072   //double constructed_;
00073 };
00074 
00075 Subscriber::Subscriber(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00076                        const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
00077                        const ros::VoidPtr& tracked_object, const TransportHints& transport_hints,
00078                        const SubLoaderPtr& loader)
00079   : impl_(new Impl)
00080 {
00081   // Load the plugin for the chosen transport.
00082   std::string lookup_name = SubscriberPlugin::getLookupName(transport_hints.getTransport());
00083   try {
00084     impl_->subscriber_ = loader->createInstance(lookup_name);
00085   }
00086   catch (pluginlib::PluginlibException& e) {
00087     throw TransportLoadException(transport_hints.getTransport(), e.what());
00088   }
00089   // Hang on to the class loader so our shared library doesn't disappear from under us.
00090   impl_->loader_ = loader;
00091 
00092   // Try to catch if user passed in a transport-specific topic as base_topic.
00093   std::string clean_topic = ros::names::clean(base_topic);
00094   size_t found = clean_topic.rfind('/');
00095   if (found != std::string::npos) {
00096     std::string transport = clean_topic.substr(found+1);
00097     std::string plugin_name = SubscriberPlugin::getLookupName(transport);
00098     std::vector<std::string> plugins = loader->getDeclaredClasses();
00099     if (std::find(plugins.begin(), plugins.end(), plugin_name) != plugins.end()) {
00100       std::string real_base_topic = clean_topic.substr(0, found);
00101       ROS_WARN("[image_transport] It looks like you are trying to subscribe directly to a "
00102                "transport-specific image topic '%s', in which case you will likely get a connection "
00103                "error. Try subscribing to the base topic '%s' instead with parameter ~image_transport "
00104                "set to '%s' (on the command line, _image_transport:=%s). "
00105                "See http://ros.org/wiki/image_transport for details.",
00106                clean_topic.c_str(), real_base_topic.c_str(), transport.c_str(), transport.c_str());
00107     }
00108   }
00109 
00110   // Tell plugin to subscribe.
00111   impl_->subscriber_->subscribe(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00112 }
00113 
00114 std::string Subscriber::getTopic() const
00115 {
00116   if (impl_) return impl_->subscriber_->getTopic();
00117   return std::string();
00118 }
00119 
00120 uint32_t Subscriber::getNumPublishers() const
00121 {
00122   if (impl_) return impl_->subscriber_->getNumPublishers();
00123   return 0;
00124 }
00125 
00126 std::string Subscriber::getTransport() const
00127 {
00128   if (impl_) return impl_->subscriber_->getTransportName();
00129   return std::string();
00130 }
00131 
00132 void Subscriber::shutdown()
00133 {
00134   if (impl_) impl_->shutdown();
00135 }
00136 
00137 Subscriber::operator void*() const
00138 {
00139   return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0;
00140 }
00141 
00142 } //namespace image_transport


image_transport
Author(s): Patrick Mihelich
autogenerated on Tue Jun 6 2017 02:33:36