publisher_plugin.h
Go to the documentation of this file.
00001 #ifndef MESSAGE_TRANSPORT_PUBLISHER_PLUGIN_H
00002 #define MESSAGE_TRANSPORT_PUBLISHER_PLUGIN_H
00003 
00004 #include <ros/ros.h>
00005 #include "message_transport/single_subscriber_publisher.h"
00006 
00007 namespace message_transport {
00008 
00012         class PublisherPluginGen : boost::noncopyable
00013         {
00014                 public:
00015                         virtual ~PublisherPluginGen() {}
00016 
00021                         virtual std::string getTransportName() const = 0;
00022 
00026                         virtual void advertise(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size,
00027                                         bool latch = true) = 0;
00028 
00033                         virtual uint32_t getNumSubscribers() const = 0;
00034 
00038                         virtual std::string getTopic() const = 0;
00039 
00043                         virtual void shutdown() = 0;
00044 
00049                         static std::string getLookupName(const std::string& transport_name)
00050                         {
00051                                 return transport_name + "_pub";
00052                         }
00053 
00054                 protected:
00055         };
00056 
00060         template <class M>
00061                 class PublisherPlugin : public PublisherPluginGen
00062         {
00063                 public:
00064                         virtual ~PublisherPlugin() {}
00065 
00066                         virtual void advertise(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size,
00067                                         bool latch = true) {
00068                                 advertiseImpl(nh,base_topic, queue_size, 
00069                                                 typename message_transport::SingleSubscriberPublisher<M>::StatusCB(),
00070                                                 typename message_transport::SingleSubscriberPublisher<M>::StatusCB(), ros::VoidPtr(), latch);
00071 
00072                         }
00073 
00078                         void advertise(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size,
00079                                         const typename message_transport::SingleSubscriberPublisher<M>::StatusCB& connect_cb,
00080                                         const typename message_transport::SingleSubscriberPublisher<M>::StatusCB& disconnect_cb = SingleSubscriberPublisher<M>::StatusCB(),
00081                                         const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = true)
00082                         {
00083                                 advertiseImpl(nh,base_topic, queue_size, 
00084                                                 connect_cb, disconnect_cb, tracked_object, latch);
00085                         }
00086 
00090                         virtual void publish(const M& message) const = 0;
00091 
00095                         virtual void publish(const typename M::ConstPtr& message) const
00096                         {
00097                                 publish(*message);
00098                         }
00099 
00100                 protected:
00104                         virtual void advertiseImpl(ros::NodeHandle & nh, const std::string& base_topic, uint32_t queue_size,
00105                                         const typename message_transport::SingleSubscriberPublisher<M>::StatusCB& connect_cb,
00106                                         const typename message_transport::SingleSubscriberPublisher<M>::StatusCB& disconnect_cb,
00107                                         const ros::VoidPtr& tracked_object, bool latch) = 0;
00108         };
00109 
00110 } //namespace message_transport
00111 
00112 #endif


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Sun Oct 5 2014 23:48:49