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. | |
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. | |
virtual std::string | getTopic () const =0 |
Returns the communication topic that this PublisherPlugin will publish on. | |
virtual std::string | getTransportName () const =0 |
Get a string identifier for the transport provided by this plugin. | |
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::ImageConstPtr &message) const |
Publish an image using the transport associated with this PublisherPlugin. | |
virtual void | shutdown ()=0 |
Shutdown any advertisements associated with this PublisherPlugin. | |
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. | |
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. |
Base class for plugins to Publisher.
Definition at line 13 of file publisher_plugin.h.
virtual image_transport::PublisherPlugin::~PublisherPlugin | ( | ) | [inline, virtual] |
Definition at line 16 of file publisher_plugin.h.
void image_transport::PublisherPlugin::advertise | ( | ros::NodeHandle & | nh, |
const std::string & | base_topic, | ||
uint32_t | queue_size, | ||
bool | latch = true |
||
) | [inline] |
Advertise a topic, simple version.
Definition at line 27 of file publisher_plugin.h.
void image_transport::PublisherPlugin::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 |
||
) | [inline] |
Advertise a topic with subscriber status callbacks.
Definition at line 37 of file publisher_plugin.h.
virtual void image_transport::PublisherPlugin::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 | ||
) | [protected, pure virtual] |
Advertise a topic. Must be implemented by the subclass.
Implemented in image_transport::SimplePublisherPlugin< M >, and image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
static std::string image_transport::PublisherPlugin::getLookupName | ( | const std::string & | transport_name | ) | [inline, static] |
Return the lookup name of the PublisherPlugin associated with a specific transport identifier.
Definition at line 78 of file publisher_plugin.h.
virtual uint32_t image_transport::PublisherPlugin::getNumSubscribers | ( | ) | const [pure virtual] |
Returns the number of subscribers that are currently connected to this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >, and image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
virtual std::string image_transport::PublisherPlugin::getTopic | ( | ) | const [pure virtual] |
Returns the communication topic that this PublisherPlugin will publish on.
Implemented in image_transport::SimplePublisherPlugin< M >, and image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
virtual std::string image_transport::PublisherPlugin::getTransportName | ( | ) | const [pure virtual] |
Get a string identifier for the transport provided by this plugin.
Implemented in image_transport::RawPublisher.
virtual void image_transport::PublisherPlugin::publish | ( | const sensor_msgs::Image & | message | ) | const [pure virtual] |
Publish an image using the transport associated with this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >, and image_transport::SimplePublisherPlugin< sensor_msgs::Image >.
virtual void image_transport::PublisherPlugin::publish | ( | const sensor_msgs::ImageConstPtr & | message | ) | const [inline, virtual] |
Publish an image using the transport associated with this PublisherPlugin.
Reimplemented in image_transport::RawPublisher.
Definition at line 64 of file publisher_plugin.h.
virtual void image_transport::PublisherPlugin::shutdown | ( | ) | [pure virtual] |
Shutdown any advertisements associated with this PublisherPlugin.
Implemented in image_transport::SimplePublisherPlugin< M >, and image_transport::SimplePublisherPlugin< sensor_msgs::Image >.