Public Member Functions | Protected Member Functions | List of all members
image_transport::RawPublisher Class Reference

The default PublisherPlugin. More...

#include <raw_publisher.h>

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

Public Member Functions

virtual std::string getTransportName () const
 Get a string identifier for the transport provided by this plugin. 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 ~RawPublisher ()
 
- Public Member Functions inherited from image_transport::SimplePublisherPlugin< sensor_msgs::Image >
virtual uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this PublisherPlugin. More...
 
virtual std::string getTopic () const
 Returns the communication topic that this PublisherPlugin will publish on. More...
 
virtual void publish (const sensor_msgs::Image &message) const
 Publish an image using the transport associated with this PublisherPlugin. More...
 
virtual void shutdown ()
 Shutdown any advertisements associated with this PublisherPlugin. More...
 
virtual ~SimplePublisherPlugin ()
 
- Public Member Functions inherited from image_transport::PublisherPlugin
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 ~PublisherPlugin ()
 

Protected Member Functions

virtual std::string getTopicToAdvertise (const std::string &base_topic) const
 Return the communication topic name for a given base topic. More...
 
virtual void publish (const sensor_msgs::Image &message, const PublishFn &publish_fn) const
 Publish an image using the specified publish function. Must be implemented by the subclass. More...
 
- Protected Member Functions inherited from image_transport::SimplePublisherPlugin< sensor_msgs::Image >
virtual void advertiseImpl (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &user_connect_cb, const SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
 Advertise a topic. Must be implemented by the subclass. More...
 
virtual void connectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber connects to the internal publisher. More...
 
virtual void disconnectCallback (const ros::SingleSubscriberPublisher &pub)
 Function called when a subscriber disconnects from the internal publisher. More...
 
const ros::PublishergetPublisher () const
 Returns the internal ros::Publisher. More...
 
const ros::NodeHandlenh () const
 Returns the ros::NodeHandle to be used for parameter lookup. More...
 

Additional Inherited Members

- Static Public Member Functions inherited from image_transport::PublisherPlugin
static std::string getLookupName (const std::string &transport_name)
 Return the lookup name of the PublisherPlugin associated with a specific transport identifier. More...
 
- Protected Types inherited from image_transport::SimplePublisherPlugin< sensor_msgs::Image >
typedef boost::function< void(const sensor_msgs::Image &)> PublishFn
 Generic function for publishing the internal message type. More...
 

Detailed Description

The default PublisherPlugin.

RawPublisher is a simple wrapper for ros::Publisher, publishing unaltered Image messages on the base topic.

Definition at line 48 of file raw_publisher.h.

Constructor & Destructor Documentation

virtual image_transport::RawPublisher::~RawPublisher ( )
inlinevirtual

Definition at line 51 of file raw_publisher.h.

Member Function Documentation

virtual std::string image_transport::RawPublisher::getTopicToAdvertise ( const std::string &  base_topic) const
inlineprotectedvirtual

Return the communication topic name for a given base topic.

Defaults to <base topic>/<transport name>.

Reimplemented from image_transport::SimplePublisherPlugin< sensor_msgs::Image >.

Definition at line 74 of file raw_publisher.h.

virtual std::string image_transport::RawPublisher::getTransportName ( ) const
inlinevirtual

Get a string identifier for the transport provided by this plugin.

Implements image_transport::PublisherPlugin.

Definition at line 53 of file raw_publisher.h.

virtual void image_transport::RawPublisher::publish ( const sensor_msgs::ImageConstPtr &  message) const
inlinevirtual

Publish an image using the transport associated with this PublisherPlugin.

Reimplemented from image_transport::PublisherPlugin.

Definition at line 60 of file raw_publisher.h.

virtual void image_transport::RawPublisher::publish ( const sensor_msgs::Image &  message,
const uint8_t *  data 
) const
virtual

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 from image_transport::PublisherPlugin.

virtual void image_transport::RawPublisher::publish ( const sensor_msgs::Image &  message,
const PublishFn publish_fn 
) const
inlineprotectedvirtual

Publish an image using the specified publish function. Must be implemented by the subclass.

The PublishFn publishes the transport-specific message type. This indirection allows SimpleSubscriberPlugin to use this function for both normal broadcast publishing and single subscriber publishing (in subscription callbacks).

Implements image_transport::SimplePublisherPlugin< sensor_msgs::Image >.

Definition at line 69 of file raw_publisher.h.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Thu Jun 6 2019 19:22:47