Go to the documentation of this file.00001 #ifndef MESSAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H
00002 #define MESSAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H
00003
00004 #include "message_transport/subscriber_plugin.h"
00005 #include <boost/scoped_ptr.hpp>
00006
00007 namespace message_transport {
00008
00027 template <class Base, class M>
00028 class SimpleSubscriberPlugin : public SubscriberPlugin<Base>
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,
00058 const typename SubscriberPlugin<Base>::Callback& user_cb) = 0;
00059
00065 virtual std::string getTopicToSubscribe(const std::string& base_topic) const
00066 {
00067 return base_topic + "/" + this->getTransportName();
00068 }
00069
00070 virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00071 const typename SubscriberPlugin<Base>::Callback& callback, const ros::VoidPtr& tracked_object,
00072 const TransportHints& transport_hints)
00073 {
00074 simple_impl_.reset(new SimpleSubscriberPluginImpl(nh, getTopicToSubscribe(base_topic)));
00075
00076 simple_impl_->sub_ = nh.subscribe<M>(getTopicToSubscribe(base_topic), queue_size,
00077 boost::bind(&SimpleSubscriberPlugin::internalCallback, this, _1, callback),
00078 tracked_object, transport_hints.getRosHints());
00079 }
00080
00084 ros::NodeHandle& nh()
00085 {
00086 return simple_impl_->param_nh_;
00087 }
00088
00089 private:
00090 struct SimpleSubscriberPluginImpl
00091 {
00092 SimpleSubscriberPluginImpl(ros::NodeHandle & nh, const std::string& new_topic)
00093 : param_nh_(nh,new_topic)
00094 {
00095 }
00096
00097 ros::NodeHandle param_nh_;
00098 ros::Subscriber sub_;
00099 };
00100
00101 boost::scoped_ptr<SimpleSubscriberPluginImpl> simple_impl_;
00102 };
00103
00104 }
00105
00106 #endif