Classes | Public Member Functions | Private Types | Private Member Functions | Static Private Member Functions | Private Attributes | Friends | List of all members
image_transport::Publisher Class Reference

Manages advertisements of multiple transport options on an Image topic. More...

#include <publisher.h>

Classes

struct  Impl
 

Public Member Functions

uint32_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this Publisher. More...
 
std::string getTopic () const
 Returns the base topic of this Publisher. More...
 
 operator void * () const
 
bool operator!= (const Publisher &rhs) const
 
bool operator< (const Publisher &rhs) const
 
bool operator== (const Publisher &rhs) const
 
void publish (const sensor_msgs::Image &message) const
 Publish an image on the topics associated with this Publisher. More...
 
void publish (const sensor_msgs::ImageConstPtr &message) const
 Publish an image on the topics associated with this Publisher. More...
 
 Publisher ()
 
void shutdown ()
 Shutdown the advertisements associated with this Publisher. More...
 

Private Types

typedef boost::shared_ptr< ImplImplPtr
 
typedef boost::weak_ptr< ImplImplWPtr
 

Private Member Functions

 Publisher (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, const PubLoaderPtr &loader)
 
SubscriberStatusCallback rebindCB (const SubscriberStatusCallback &user_cb)
 

Static Private Member Functions

static void weakSubscriberCb (const ImplWPtr &impl_wptr, const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb)
 

Private Attributes

ImplPtr impl_
 

Friends

class ImageTransport
 

Detailed Description

Manages advertisements of multiple transport options on an Image topic.

Publisher is a drop-in replacement for ros::Publisher when publishing Image topics. In a minimally built environment, they behave the same; however, Publisher is extensible via plugins to publish alternative representations of the image on related subtopics. This is especially useful for limiting bandwidth and latency over a network connection, when you might (for example) use the theora plugin to transport the images as streamed video. All topics are published only on demand (i.e. if there are subscribers).

A Publisher should always be created through a call to ImageTransport::advertise(), or copied from one that was. Once all copies of a specific Publisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all Publisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.

Definition at line 96 of file publisher.h.

Member Typedef Documentation

◆ ImplPtr

Definition at line 173 of file publisher.h.

◆ ImplWPtr

typedef boost::weak_ptr<Impl> image_transport::Publisher::ImplWPtr
private

Definition at line 175 of file publisher.h.

Constructor & Destructor Documentation

◆ Publisher() [1/2]

image_transport::Publisher::Publisher ( )
inline

Definition at line 131 of file publisher.h.

◆ Publisher() [2/2]

image_transport::Publisher::Publisher ( 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,
const PubLoaderPtr loader 
)
private

Definition at line 132 of file publisher.cpp.

Member Function Documentation

◆ getNumSubscribers()

uint32_t image_transport::Publisher::getNumSubscribers ( ) const

Returns the number of subscribers that are currently connected to this Publisher.

Returns the total number of subscribers to all advertised topics.

Definition at line 176 of file publisher.cpp.

◆ getTopic()

std::string image_transport::Publisher::getTopic ( ) const

Returns the base topic of this Publisher.

Definition at line 182 of file publisher.cpp.

◆ operator void *()

image_transport::Publisher::operator void * ( ) const

Definition at line 222 of file publisher.cpp.

◆ operator!=()

bool image_transport::Publisher::operator!= ( const Publisher rhs) const
inline

Definition at line 163 of file publisher.h.

◆ operator<()

bool image_transport::Publisher::operator< ( const Publisher rhs) const
inline

Definition at line 162 of file publisher.h.

◆ operator==()

bool image_transport::Publisher::operator== ( const Publisher rhs) const
inline

Definition at line 164 of file publisher.h.

◆ publish() [1/2]

void image_transport::Publisher::publish ( const sensor_msgs::Image &  message) const

Publish an image on the topics associated with this Publisher.

Definition at line 188 of file publisher.cpp.

◆ publish() [2/2]

void image_transport::Publisher::publish ( const sensor_msgs::ImageConstPtr &  message) const

Publish an image on the topics associated with this Publisher.

Definition at line 201 of file publisher.cpp.

◆ rebindCB()

SubscriberStatusCallback image_transport::Publisher::rebindCB ( const SubscriberStatusCallback user_cb)
private

Definition at line 235 of file publisher.cpp.

◆ shutdown()

void image_transport::Publisher::shutdown ( )

Shutdown the advertisements associated with this Publisher.

Definition at line 214 of file publisher.cpp.

◆ weakSubscriberCb()

void image_transport::Publisher::weakSubscriberCb ( const ImplWPtr impl_wptr,
const SingleSubscriberPublisher plugin_pub,
const SubscriberStatusCallback user_cb 
)
staticprivate

Definition at line 227 of file publisher.cpp.

Friends And Related Function Documentation

◆ ImageTransport

friend class ImageTransport
friend

Definition at line 185 of file publisher.h.

Member Data Documentation

◆ impl_

ImplPtr image_transport::Publisher::impl_
private

Definition at line 177 of file publisher.h.


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