Public Member Functions | Static Public Member Functions | Protected Member Functions | List of all members
image_transport::PublisherPlugin Class Referenceabstract

Base class for plugins to Publisher. More...

#include <publisher_plugin.h>

Inheritance diagram for image_transport::PublisherPlugin:
Inheritance graph
[legend]

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::ImageConstPtr &message) const
 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 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...
 

Detailed Description

Base class for plugins to Publisher.

Definition at line 47 of file publisher_plugin.h.

Constructor & Destructor Documentation

virtual image_transport::PublisherPlugin::~PublisherPlugin ( )
inlinevirtual

Definition at line 50 of file publisher_plugin.h.

Member Function Documentation

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 61 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 71 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 
)
protectedpure virtual
static std::string image_transport::PublisherPlugin::getLookupName ( const std::string &  transport_name)
inlinestatic

Return the lookup name of the PublisherPlugin associated with a specific transport identifier.

Definition at line 133 of file publisher_plugin.h.

virtual uint32_t image_transport::PublisherPlugin::getNumSubscribers ( ) const
pure virtual
virtual std::string image_transport::PublisherPlugin::getTopic ( ) const
pure virtual
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, and ResizedPublisher.

virtual void image_transport::PublisherPlugin::publish ( const sensor_msgs::Image &  message) const
pure virtual
virtual void image_transport::PublisherPlugin::publish ( const sensor_msgs::ImageConstPtr &  message) const
inlinevirtual

Publish an image using the transport associated with this PublisherPlugin.

Reimplemented in image_transport::RawPublisher.

Definition at line 98 of file publisher_plugin.h.

virtual void image_transport::PublisherPlugin::publish ( const sensor_msgs::Image &  message,
const uint8_t *  data 
) const
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.

Parameters
messagean image message to use information from (but not data)
dataa pointer to the image data to use to fill the Image message

Reimplemented in image_transport::RawPublisher.

Definition at line 110 of file publisher_plugin.h.

virtual void image_transport::PublisherPlugin::shutdown ( )
pure virtual

The documentation for this class was generated from the following file:


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:14:58