subscriber_plugin.h
Go to the documentation of this file.
00001 #ifndef MESSAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00002 #define MESSAGE_TRANSPORT_SUBSCRIBER_PLUGIN_H
00003 
00004 #include <ros/ros.h>
00005 #include <boost/function.hpp>
00006 #include <boost/noncopyable.hpp>
00007 #include "message_transport/transport_hints.h"
00008 
00009 namespace message_transport {
00010 
00014         class SubscriberPluginGen : boost::noncopyable
00015         {
00016                 public:
00017                         virtual ~SubscriberPluginGen() {}
00018 
00023                         virtual std::string getTransportName() const = 0;
00024 
00028                         virtual std::string getTopic() const = 0;
00029 
00033                         virtual uint32_t getNumPublishers() const = 0;
00034 
00038                         virtual void shutdown() = 0;
00039 
00044                         static std::string getLookupName(const std::string& transport_type)
00045                         {
00046                                 return transport_type + "_sub";
00047                         }
00048 
00049                 protected:
00050         };
00051 
00052         template <class M>
00053                 class SubscriberPlugin : public SubscriberPluginGen
00054         {
00055                 public:
00056                         typedef boost::function<void(const typename M::ConstPtr&)> Callback;
00057 
00058                         virtual ~SubscriberPlugin() {}
00059 
00063                         void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00064                                         const Callback& callback, const ros::VoidPtr& tracked_object = ros::VoidPtr(),
00065                                         const TransportHints& transport_hints = TransportHints())
00066                         {
00067                                 return subscribeImpl(nh, base_topic, queue_size, callback, tracked_object, transport_hints);
00068                         }
00069 
00073                         void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00074                                         void(*fp)(const typename M::ConstPtr&),
00075                                         const TransportHints& transport_hints = TransportHints())
00076                         {
00077                                 return subscribe(nh, base_topic, queue_size,
00078                                                 boost::function<void(const typename M::ConstPtr&)>(fp),
00079                                                 ros::VoidPtr(), transport_hints);
00080                         }
00081 
00085                         template<class T>
00086                                 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00087                                                 void(T::*fp)(const typename M::ConstPtr&), T* obj,
00088                                                 const TransportHints& transport_hints = TransportHints())
00089                                 {
00090                                         return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj, _1), ros::VoidPtr(), transport_hints);
00091                                 }
00092 
00096                         template<class T>
00097                                 void subscribe(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00098                                                 void(T::*fp)(const typename M::ConstPtr&),
00099                                                 const boost::shared_ptr<T>& obj,
00100                                                 const TransportHints& transport_hints = TransportHints())
00101                                 {
00102                                         return subscribe(nh, base_topic, queue_size, boost::bind(fp, obj.get(), _1), obj, transport_hints);
00103                                 }
00104 
00105                 protected:
00109                         virtual void subscribeImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00110                                         const Callback& callback, const ros::VoidPtr& tracked_object,
00111                                         const TransportHints& transport_hints) = 0;
00112         };
00113 
00114 } //namespace message_transport
00115 
00116 #endif


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sat Dec 28 2013 16:56:55