subscriber_plugin.h
Go to the documentation of this file.
00001 #ifndef IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00002 #define IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00003 
00004 #include <ros/ros.h>
00005 #include <sensor_msgs/Image.h>
00006 #include <boost/noncopyable.hpp>
00007 #include "image_transport/transport_hints.h"
00008 
00009 namespace image_transport {
00010 
00014 class SubscriberPlugin : boost::noncopyable
00015 {
00016 public:
00017   typedef boost::function<void(const sensor_msgs::ImageConstPtr&)> Callback;
00018   
00019   virtual ~SubscriberPlugin() {}
00020 
00025   virtual std::string getTransportName() const = 0;
00026 
00030   void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00031                  const Callback& callback, const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00032                  const TransportHints& transport_hints = TransportHints())
00033   {
00034     return subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00035   }
00036 
00040   void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00041                  void(*fp)(const sensor_msgs::ImageConstPtr&),
00042                  const TransportHints& transport_hints = TransportHints())
00043   {
00044     return subscribe(nh, base_topic, queue_size,
00045                      boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
00046                      ros::VoidPtr(), transport_hints);
00047   }
00048 
00052   template<class T>
00053   void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00054                  void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
00055                  const TransportHints& transport_hints = TransportHints())
00056   {
00057     return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
00058   }
00059 
00063   template<class T>
00064   void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00065                  void(T::*fp)(const sensor_msgs::ImageConstPtr&),
00066                  const boost::shared_ptr<T>& obj,
00067                  const TransportHints& transport_hints = TransportHints())
00068   {
00069     return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
00070   }
00071 
00075   virtual std::string getTopic() const = 0;
00076 
00080   virtual uint32_t getNumPublishers() const = 0;
00081 
00085   virtual void shutdown() = 0;
00086 
00091   static std::string getLookupName(const std::string& transport_type)
00092   {
00093     return "image_transport/" + transport_type + "_sub";
00094   }
00095 
00096 protected:
00100   virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00101                              const Callback& callback, const ros::VoidPtr& tracked_object,
00102                              const TransportHints& transport_hints) = 0;
00103 };
00104 
00105 } //namespace image_transport
00106 
00107 #endif


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