39 #include <boost/scoped_ptr.hpp> 
   43 struct Subscriber::Impl
 
   76                        const boost::function<
void(
const sensor_msgs::ImageConstPtr&)>& callback,
 
   84     impl_->subscriber_ = loader->createInstance(lookup_name);
 
   90   impl_->loader_ = loader;
 
   94   size_t found = clean_topic.rfind(
'/');
 
   95   if (found != std::string::npos) {
 
   96     std::string transport = clean_topic.substr(found+1);
 
   98     std::vector<std::string> plugins = loader->getDeclaredClasses();
 
   99     if (std::find(plugins.begin(), plugins.end(), plugin_name) != plugins.end()) {
 
  100       std::string real_base_topic = clean_topic.substr(0, found);
 
  101       ROS_WARN(
"[image_transport] It looks like you are trying to subscribe directly to a " 
  102                "transport-specific image topic '%s', in which case you will likely get a connection " 
  103                "error. Try subscribing to the base topic '%s' instead with parameter ~image_transport " 
  104                "set to '%s' (on the command line, _image_transport:=%s). " 
  105                "See http://ros.org/wiki/image_transport for details.",
 
  106                clean_topic.c_str(), real_base_topic.c_str(), transport.c_str(), transport.c_str());
 
  111   impl_->subscriber_->subscribe(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
 
  116   if (
impl_) 
return impl_->subscriber_->getTopic();
 
  117   return std::string();
 
  122   if (
impl_) 
return impl_->subscriber_->getNumPublishers();
 
  128   if (
impl_) 
return impl_->subscriber_->getTransportName();
 
  129   return std::string();
 
  137 Subscriber::operator 
void*() 
const 
  139   return (
impl_ && 
impl_->isValid()) ? (
void*)1 : (
void*)0;