35 #ifndef IMAGE_TRANSPORT_PUBLISHER_PLUGIN_H 36 #define IMAGE_TRANSPORT_PUBLISHER_PLUGIN_H 39 #include <sensor_msgs/Image.h> 76 advertiseImpl(nh, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch);
88 virtual std::string
getTopic()
const = 0;
93 virtual void publish(
const sensor_msgs::Image& message)
const = 0;
98 virtual void publish(
const sensor_msgs::ImageConstPtr& message)
const 110 virtual void publish(
const sensor_msgs::Image& message,
const uint8_t* data)
const 112 sensor_msgs::Image msg;
113 msg.header = message.header;
114 msg.height = message.height;
115 msg.width = message.width;
116 msg.encoding = message.encoding;
117 msg.is_bigendian = message.is_bigendian;
118 msg.step = message.step;
119 msg.data = std::vector<uint8_t>(data, data + msg.step*msg.height);
135 return "image_transport/" + transport_name +
"_pub";
void advertise(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=true)
Advertise a topic with subscriber status callbacks.
virtual uint32_t getNumSubscribers() const =0
Returns the number of subscribers that are currently connected to this PublisherPlugin.
static std::string getLookupName(const std::string &transport_name)
Return the lookup name of the PublisherPlugin associated with a specific transport identifier...
virtual void publish(const sensor_msgs::ImageConstPtr &message) const
Publish an image using the transport associated with this PublisherPlugin.
virtual void publish(const sensor_msgs::Image &message) const =0
Publish an image using the transport associated with this PublisherPlugin.
virtual void publish(const sensor_msgs::Image &message, const uint8_t *data) const
Publish an image using the transport associated with this PublisherPlugin. This version of the functi...
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void advertise(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, bool latch=true)
Advertise a topic, simple version.
virtual std::string getTransportName() const =0
Get a string identifier for the transport provided by this plugin.
virtual std::string getTopic() const =0
Returns the communication topic that this PublisherPlugin will publish on.
virtual ~PublisherPlugin()
virtual void shutdown()=0
Shutdown any advertisements associated with this PublisherPlugin.
virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)=0
Advertise a topic. Must be implemented by the subclass.
Base class for plugins to Publisher.