35 #ifndef IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H 36 #define IMAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H 39 #include <sensor_msgs/Image.h> 40 #include <boost/noncopyable.hpp> 51 typedef boost::function<void(const sensor_msgs::ImageConstPtr&)>
Callback;
68 return subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
75 void(*fp)(
const sensor_msgs::ImageConstPtr&),
78 return subscribe(nh, base_topic, queue_size,
79 boost::function<
void(
const sensor_msgs::ImageConstPtr&)>(fp),
88 void(T::*fp)(
const sensor_msgs::ImageConstPtr&), T* obj,
91 return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj, _1),
ros::VoidPtr(), transport_hints);
99 void(T::*fp)(
const sensor_msgs::ImageConstPtr&),
103 return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
109 virtual std::string
getTopic()
const = 0;
127 return "image_transport/" + transport_type +
"_sub";
135 const Callback& callback,
const ros::VoidPtr& tracked_object,
Base class for plugins to Subscriber.
void subscribe(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), T *obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with bare pointer. ...
virtual uint32_t getNumPublishers() const =0
Returns the number of publishers this subscriber is connected to.
virtual void subscribeImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints)=0
Subscribe to an image transport topic. Must be implemented by the subclass.
void subscribe(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(T::*fp)(const sensor_msgs::ImageConstPtr &), const boost::shared_ptr< T > &obj, const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for class member function with shared_ptr.
virtual std::string getTransportName() const =0
Get a string identifier for the transport provided by this plugin.
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
void subscribe(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
static std::string getLookupName(const std::string &transport_type)
Return the lookup name of the SubscriberPlugin associated with a specific transport identifier...
virtual ~SubscriberPlugin()
virtual std::string getTopic() const =0
Get the transport-specific communication topic.
virtual void shutdown()=0
Unsubscribe the callback associated with this SubscriberPlugin.
Stores transport settings for an image topic subscription.
void subscribe(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, void(*fp)(const sensor_msgs::ImageConstPtr &), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for bare function.