35 #ifndef IMAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H 36 #define IMAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H 39 #include <boost/scoped_ptr.hpp> 109 simple_impl_.reset(
new SimpleSubscriberPluginImpl(param_nh));
Base class for plugins to Subscriber.
virtual std::string getTransportName() const =0
Get a string identifier for the transport provided by this plugin.
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
const ros::NodeHandle param_nh_
boost::function< void(const sensor_msgs::ImageConstPtr &)> Callback
const ros::NodeHandle & nh() const
Returns the ros::NodeHandle to be used for parameter lookup.
const ros::NodeHandle & getParameterNH() const
SimpleSubscriberPluginImpl(const ros::NodeHandle &nh)
virtual std::string getTopicToSubscribe(const std::string &base_topic) const
Return the communication topic name for a given base topic.
virtual uint32_t getNumPublishers() const
Returns the number of publishers this subscriber is connected to.
Base class to simplify implementing most plugins to Subscriber.
boost::scoped_ptr< SimpleSubscriberPluginImpl > simple_impl_
virtual void internalCallback(const typename M::ConstPtr &message, const Callback &user_cb)=0
Process a message. Must be implemented by the subclass.
virtual ~SimpleSubscriberPlugin()
Stores transport settings for an image topic subscription.
const ros::TransportHints & getRosHints() const
virtual void shutdown()
Unsubscribe the callback associated with this SubscriberPlugin.
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)
Subscribe to an image transport topic. Must be implemented by the subclass.
virtual std::string getTopic() const
Get the transport-specific communication topic.