00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035 #ifndef IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00036 #define IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00037
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include <boost/noncopyable.hpp>
00041 #include "image_transport/transport_hints.h"
00042
00043 namespace image_transport {
00044
00048 class SubscriberPlugin : boost::noncopyable
00049 {
00050 public:
00051 typedef boost::function<void(const sensor_msgs::ImageConstPtr&)> Callback;
00052
00053 virtual ~SubscriberPlugin() {}
00054
00059 virtual std::string getTransportName() const = 0;
00060
00064 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00065 const Callback& callback, const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00066 const TransportHints& transport_hints = TransportHints())
00067 {
00068 return subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00069 }
00070
00074 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00075 void(*fp)(const sensor_msgs::ImageConstPtr&),
00076 const TransportHints& transport_hints = TransportHints())
00077 {
00078 return subscribe(nh, base_topic, queue_size,
00079 boost::function<void(const sensor_msgs::ImageConstPtr&)>(fp),
00080 ros::VoidPtr(), transport_hints);
00081 }
00082
00086 template<class T>
00087 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00088 void(T::*fp)(const sensor_msgs::ImageConstPtr&), T* obj,
00089 const TransportHints& transport_hints = TransportHints())
00090 {
00091 return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
00092 }
00093
00097 template<class T>
00098 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00099 void(T::*fp)(const sensor_msgs::ImageConstPtr&),
00100 const boost::shared_ptr<T>& obj,
00101 const TransportHints& transport_hints = TransportHints())
00102 {
00103 return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
00104 }
00105
00109 virtual std::string getTopic() const = 0;
00110
00114 virtual uint32_t getNumPublishers() const = 0;
00115
00119 virtual void shutdown() = 0;
00120
00125 static std::string getLookupName(const std::string& transport_type)
00126 {
00127 return "image_transport/" + transport_type + "_sub";
00128 }
00129
00130 protected:
00134 virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00135 const Callback& callback, const ros::VoidPtr& tracked_object,
00136 const TransportHints& transport_hints) = 0;
00137 };
00138
00139 }
00140
00141 #endif