Go to the documentation of this file.00001 #ifndef IMAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H
00002 #define IMAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H
00003
00004 #include "image_transport/subscriber_plugin.h"
00005 #include <boost/scoped_ptr.hpp>
00006
00007 namespace image_transport {
00008
00027 template <class M>
00028 class SimpleSubscriberPlugin : public SubscriberPlugin
00029 {
00030 public:
00031 virtual ~SimpleSubscriberPlugin() {}
00032
00033 virtual std::string getTopic() const
00034 {
00035 if (simple_impl_) return simple_impl_->sub_.getTopic();
00036 return std::string();
00037 }
00038
00039 virtual uint32_t getNumPublishers() const
00040 {
00041 if (simple_impl_) return simple_impl_->sub_.getNumPublishers();
00042 return 0;
00043 }
00044
00045 virtual void shutdown()
00046 {
00047 if (simple_impl_) simple_impl_->sub_.shutdown();
00048 }
00049
00050 protected:
00057 virtual void internalCallback(const typename M::ConstPtr& message, const Callback& user_cb) = 0;
00058
00064 virtual std::string getTopicToSubscribe(const std::string& base_topic) const
00065 {
00066 return base_topic + "/" + getTransportName();
00067 }
00068
00069 virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00070 const Callback& callback, const ros::VoidPtr& tracked_object,
00071 const TransportHints& transport_hints)
00072 {
00073
00074 ros::NodeHandle param_nh(transport_hints.getParameterNH(), getTransportName());
00075 simple_impl_.reset(new SimpleSubscriberPluginImpl(param_nh));
00076
00077 simple_impl_->sub_ = nh.subscribe<M>(getTopicToSubscribe(base_topic), queue_size,
00078 boost::bind(&SimpleSubscriberPlugin::internalCallback, this, _1, callback),
00079 tracked_object, transport_hints.getRosHints());
00080 }
00081
00085 const ros::NodeHandle& nh() const
00086 {
00087 return simple_impl_->param_nh_;
00088 }
00089
00090 private:
00091 struct SimpleSubscriberPluginImpl
00092 {
00093 SimpleSubscriberPluginImpl(const ros::NodeHandle& nh)
00094 : param_nh_(nh)
00095 {
00096 }
00097
00098 const ros::NodeHandle param_nh_;
00099 ros::Subscriber sub_;
00100 };
00101
00102 boost::scoped_ptr<SimpleSubscriberPluginImpl> simple_impl_;
00103 };
00104
00105 }
00106
00107 #endif