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_PUBLISHER_PLUGIN_H
00036 #define IMAGE_TRANSPORT_PUBLISHER_PLUGIN_H
00037
00038 #include <ros/ros.h>
00039 #include <sensor_msgs/Image.h>
00040 #include "image_transport/single_subscriber_publisher.h"
00041
00042 namespace image_transport {
00043
00047 class PublisherPlugin : boost::noncopyable
00048 {
00049 public:
00050 virtual ~PublisherPlugin() {}
00051
00056 virtual std::string getTransportName() const = 0;
00057
00061 void advertise(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00062 bool latch = true)
00063 {
00064 advertiseImpl(nh, base_topic, queue_size, SubscriberStatusCallback(),
00065 SubscriberStatusCallback(), ros::VoidPtr(), latch);
00066 }
00067
00071 void advertise(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00072 const SubscriberStatusCallback& connect_cb,
00073 const SubscriberStatusCallback& disconnect_cb = SubscriberStatusCallback(),
00074 const ros::VoidPtr& tracked_object = ros::VoidPtr(), bool latch = true)
00075 {
00076 advertiseImpl(nh, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch);
00077 }
00078
00083 virtual uint32_t getNumSubscribers() const = 0;
00084
00088 virtual std::string getTopic() const = 0;
00089
00093 virtual void publish(const sensor_msgs::Image& message) const = 0;
00094
00098 virtual void publish(const sensor_msgs::ImageConstPtr& message) const
00099 {
00100 publish(*message);
00101 }
00102
00110 virtual void publish(const sensor_msgs::Image& message, const uint8_t* data) const
00111 {
00112 sensor_msgs::Image msg;
00113 msg.header = message.header;
00114 msg.height = message.height;
00115 msg.width = message.width;
00116 msg.encoding = message.encoding;
00117 msg.is_bigendian = message.is_bigendian;
00118 msg.step = message.step;
00119 msg.data = std::vector<uint8_t>(data, data + msg.step*msg.height);
00120
00121 publish(msg);
00122 }
00123
00127 virtual void shutdown() = 0;
00128
00133 static std::string getLookupName(const std::string& transport_name)
00134 {
00135 return "image_transport/" + transport_name + "_pub";
00136 }
00137
00138 protected:
00142 virtual void advertiseImpl(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
00143 const SubscriberStatusCallback& connect_cb,
00144 const SubscriberStatusCallback& disconnect_cb,
00145 const ros::VoidPtr& tracked_object, bool latch) = 0;
00146 };
00147
00148 }
00149
00150 #endif