Public Member Functions | Protected Member Functions | List of all members
ResizedPublisher Class Reference

#include <resized_publisher.h>

Inheritance diagram for ResizedPublisher:
Inheritance graph
[legend]

Public Member Functions

virtual std::string getTransportName () const
 Get a string identifier for the transport provided by this plugin. More...
 
- Public Member Functions inherited from image_transport::SimplePublisherPlugin< image_transport_tutorial::ResizedImage >
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 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 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 ~PublisherPlugin ()
 

Protected Member Functions

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< image_transport_tutorial::ResizedImage >
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...
 
virtual std::string getTopicToAdvertise (const std::string &base_topic) const
 Return the communication topic name for a given base topic. 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< image_transport_tutorial::ResizedImage >
typedef boost::function< void(const image_transport_tutorial::ResizedImage &)> PublishFn
 Generic function for publishing the internal message type. More...
 

Detailed Description

Definition at line 4 of file resized_publisher.h.

Member Function Documentation

◆ getTransportName()

virtual std::string ResizedPublisher::getTransportName ( ) const
inlinevirtual

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

Implements image_transport::PublisherPlugin.

Definition at line 7 of file resized_publisher.h.

◆ publish()

void ResizedPublisher::publish ( const sensor_msgs::Image &  message,
const PublishFn publish_fn 
) const
protectedvirtual

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< image_transport_tutorial::ResizedImage >.

Definition at line 5 of file resized_publisher.cpp.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50