subscriber.h
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 #ifndef MESSAGE_TRANSPORT_SUBSCRIBER_H
00036 #define MESSAGE_TRANSPORT_SUBSCRIBER_H
00037 
00038 #include <ros/ros.h>
00039 #include "message_transport/transport_hints.h"
00040 #include "message_transport/subscriber_impl.h"
00041 
00042 namespace message_transport {
00043 
00059         class Subscriber
00060         {
00061                 public:
00062                         Subscriber() {}
00063                         Subscriber(ros::NodeHandle& nh);
00064 
00065                         std::string getTopic() const;
00066 
00070                         uint32_t getNumPublishers() const;
00071 
00075                         void shutdown();
00076 
00077                         operator void*() const;
00078                         bool operator< (const Subscriber& rhs) const { return impl_ <  rhs.impl_; }
00079                         bool operator!=(const Subscriber& rhs) const { return impl_ != rhs.impl_; }
00080                         bool operator==(const Subscriber& rhs) const { return impl_ == rhs.impl_; }
00081 
00082                         template <class M>
00083                                 int do_subscribe(ros::NodeHandle& nh, 
00084                                                 const std::string & package_name, const std::string & class_name, 
00085                                                 const std::string& base_topic, uint32_t queue_size,
00086                                                 const boost::function<void(const typename M::ConstPtr&)>& callback,
00087                                                 const ros::VoidPtr& tracked_object, const TransportHints& transport_hints)
00088                                 {
00089                                         // Tell plugin to subscribe.
00090                                         impl_.reset(new SubscriberImpl<M>(package_name,class_name));
00091                                         // Load the plugin for the chosen transport.
00092                                         impl_.get()->reset(transport_hints);
00093 
00094                                         // Try to catch if user passed in a transport-specific topic as base_topic.
00095                                         std::string clean_topic = ros::names::clean(base_topic);
00096                                         size_t found = clean_topic.rfind('/');
00097                                         if (found != std::string::npos) {
00098                                                 std::string transport = clean_topic.substr(found+1);
00099                                                 std::string plugin_name = SubscriberPluginGen::getLookupName(transport);
00100                                                 std::vector<std::string> plugins = impl_->getDeclaredClasses();
00101                                                 if (std::find(plugins.begin(), plugins.end(), plugin_name) != plugins.end()) {
00102                                                         std::string real_base_topic = clean_topic.substr(0, found);
00103                                                         ROS_WARN("[message_transport] It looks like you are trying to subscribe directly to a "
00104                                                                         "transport-specific image topic '%s', in which case you will likely get a connection "
00105                                                                         "error. Try subscribing to the base topic '%s' instead with parameter ~message_transport "
00106                                                                         "set to '%s' (on the command line, _message_transport:=%s). "
00107                                                                         "See http://ros.org/wiki/message_transport for details.",
00108                                                                         clean_topic.c_str(), real_base_topic.c_str(), transport.c_str(), transport.c_str());
00109                                                 }
00110                                         }
00111 
00112                                         impl_->getTemplateSubscriber<M>()->subscribe(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00113                                         return 0;
00114                                 }
00115 
00116                 private:
00117 
00118                         typedef boost::shared_ptr<SubscriberImplGen> ImplPtr;
00119 
00120                         ImplPtr impl_;
00121 
00122         };
00123 
00124 } //namespace message_transport
00125 
00126 #endif


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sat Dec 28 2013 16:56:55