Base class for plugins to Publisher. More...
#include <publisher_plugin.h>
Public Member Functions | |
void | advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, bool latch=true) |
Advertise a topic, simple version. More... | |
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. More... | |
virtual uint32_t | getNumSubscribers () const =0 |
Returns the number of subscribers that are currently connected to this PublisherPlugin. More... | |
virtual std::string | getTopic () const =0 |
Returns the communication topic that this PublisherPlugin will publish on. More... | |
virtual std::string | getTransportName () const =0 |
Get a string identifier for the transport provided by this plugin. More... | |
virtual void | publish (const sensor_msgs::Image &message) const =0 |
Publish an image using the transport associated with this PublisherPlugin. More... | |
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 function can be used to optimize cases where you don't want to fill a ROS message first to avoid useless copies. More... | |
virtual void | publish (const sensor_msgs::ImageConstPtr &message) const |
Publish an image using the transport associated with this PublisherPlugin. More... | |
virtual void | shutdown ()=0 |
Shutdown any advertisements associated with this PublisherPlugin. More... | |
virtual | ~PublisherPlugin () |
Static Public Member Functions | |
static std::string | getLookupName (const std::string &transport_name) |
Return the lookup name of the PublisherPlugin associated with a specific transport identifier. More... | |
Protected Member Functions | |
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. More... | |
Base class for plugins to Publisher.
Definition at line 79 of file publisher_plugin.h.
|
inlinevirtual |
Definition at line 114 of file publisher_plugin.h.
|
inline |
Advertise a topic, simple version.
Definition at line 125 of file publisher_plugin.h.
|
inline |
Advertise a topic with subscriber status callbacks.
Definition at line 135 of file publisher_plugin.h.
|
protectedpure virtual |
Advertise a topic. Must be implemented by the subclass.
Implemented in image_transport::SimplePublisherPlugin< M >, image_transport::SimplePublisherPlugin< sensor_msgs::Image >, and image_transport::SimplePublisherPlugin< image_transport_tutorial::ResizedImage >.
|
inlinestatic |
Return the lookup name of the PublisherPlugin associated with a specific transport identifier.
Definition at line 197 of file publisher_plugin.h.
|
pure virtual |
Returns the number of subscribers that are currently connected to this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >.
|
pure virtual |
Returns the communication topic that this PublisherPlugin will publish on.
Implemented in image_transport::SimplePublisherPlugin< M >.
|
pure virtual |
Get a string identifier for the transport provided by this plugin.
Implemented in image_transport::RawPublisher, and ResizedPublisher.
|
pure virtual |
Publish an image using the transport associated with this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >, image_transport::SimplePublisherPlugin< sensor_msgs::Image >, and image_transport::SimplePublisherPlugin< image_transport_tutorial::ResizedImage >.
|
inlinevirtual |
Publish an image using the transport associated with this PublisherPlugin. This version of the function can be used to optimize cases where you don't want to fill a ROS message first to avoid useless copies.
message | an image message to use information from (but not data) |
data | a pointer to the image data to use to fill the Image message |
Reimplemented in image_transport::RawPublisher.
Definition at line 174 of file publisher_plugin.h.
|
inlinevirtual |
Publish an image using the transport associated with this PublisherPlugin.
Reimplemented in image_transport::RawPublisher.
Definition at line 162 of file publisher_plugin.h.
|
pure virtual |
Shutdown any advertisements associated with this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >, image_transport::SimplePublisherPlugin< sensor_msgs::Image >, and image_transport::SimplePublisherPlugin< image_transport_tutorial::ResizedImage >.