Go to the documentation of this file.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_SIMPLE_SUBSCRIBER_PLUGIN_H
00036 #define IMAGE_TRANSPORT_SIMPLE_SUBSCRIBER_PLUGIN_H
00037
00038 #include "image_transport/subscriber_plugin.h"
00039 #include <boost/scoped_ptr.hpp>
00040
00041 namespace image_transport {
00042
00061 template <class M>
00062 class SimpleSubscriberPlugin : public SubscriberPlugin
00063 {
00064 public:
00065 virtual ~SimpleSubscriberPlugin() {}
00066
00067 virtual std::string getTopic() const
00068 {
00069 if (simple_impl_) return simple_impl_->sub_.getTopic();
00070 return std::string();
00071 }
00072
00073 virtual uint32_t getNumPublishers() const
00074 {
00075 if (simple_impl_) return simple_impl_->sub_.getNumPublishers();
00076 return 0;
00077 }
00078
00079 virtual void shutdown()
00080 {
00081 if (simple_impl_) simple_impl_->sub_.shutdown();
00082 }
00083
00084 protected:
00091 virtual void internalCallback(const typename M::ConstPtr& message, const Callback& user_cb) = 0;
00092
00098 virtual std::string getTopicToSubscribe(const std::string& base_topic) const
00099 {
00100 return base_topic + "/" + getTransportName();
00101 }
00102
00103 virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00104 const Callback& callback, const ros::VoidPtr& tracked_object,
00105 const TransportHints& transport_hints)
00106 {
00107
00108 ros::NodeHandle param_nh(transport_hints.getParameterNH(), getTransportName());
00109 simple_impl_.reset(new SimpleSubscriberPluginImpl(param_nh));
00110
00111 simple_impl_->sub_ = nh.subscribe<M>(getTopicToSubscribe(base_topic), queue_size,
00112 boost::bind(&SimpleSubscriberPlugin::internalCallback, this, _1, callback),
00113 tracked_object, transport_hints.getRosHints());
00114 }
00115
00119 const ros::NodeHandle& nh() const
00120 {
00121 return simple_impl_->param_nh_;
00122 }
00123
00124 private:
00125 struct SimpleSubscriberPluginImpl
00126 {
00127 SimpleSubscriberPluginImpl(const ros::NodeHandle& nh)
00128 : param_nh_(nh)
00129 {
00130 }
00131
00132 const ros::NodeHandle param_nh_;
00133 ros::Subscriber sub_;
00134 };
00135
00136 boost::scoped_ptr<SimpleSubscriberPluginImpl> simple_impl_;
00137 };
00138
00139 }
00140
00141 #endif