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

Manages a subscription callback on a specific topic that can be interpreted as an Image topic. More...

#include <subscriber.h>

Classes

struct  Impl
 

Public Member Functions

uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to. More...
 
std::string getTopic () const
 Returns the base image topic. More...
 
std::string getTransport () const
 Returns the name of the transport being used. More...
 
 operator void * () const
 
bool operator!= (const Subscriber &rhs) const
 
bool operator< (const Subscriber &rhs) const
 
bool operator== (const Subscriber &rhs) const
 
void shutdown ()
 Unsubscribe the callback associated with this Subscriber. More...
 
 Subscriber ()
 

Private Types

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

Private Member Functions

 Subscriber (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints, const SubLoaderPtr &loader)
 

Private Attributes

ImplPtr impl_
 

Friends

class ImageTransport
 

Detailed Description

Manages a subscription callback on a specific topic that can be interpreted as an Image topic.

Subscriber is the client-side counterpart to Publisher. By loading the appropriate plugin, it can subscribe to a base image topic using any available transport. The complexity of what transport is actually used is hidden from the user, who sees only a normal Image callback.

A Subscriber should always be created through a call to ImageTransport::subscribe(), or copied from one that was. Once all copies of a specific Subscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all Subscriber for a given topic go out of scope the topic will be unsubscribed.

Definition at line 94 of file subscriber.h.

Member Typedef Documentation

◆ ImplPtr

Definition at line 165 of file subscriber.h.

◆ ImplWPtr

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

Definition at line 167 of file subscriber.h.

Constructor & Destructor Documentation

◆ Subscriber() [1/2]

image_transport::Subscriber::Subscriber ( )
inline

Definition at line 129 of file subscriber.h.

◆ Subscriber() [2/2]

image_transport::Subscriber::Subscriber ( ros::NodeHandle nh,
const std::string &  base_topic,
uint32_t  queue_size,
const boost::function< void(const sensor_msgs::ImageConstPtr &)> &  callback,
const ros::VoidPtr tracked_object,
const TransportHints transport_hints,
const SubLoaderPtr loader 
)
private

Definition at line 107 of file subscriber.cpp.

Member Function Documentation

◆ getNumPublishers()

uint32_t image_transport::Subscriber::getNumPublishers ( ) const

Returns the number of publishers this subscriber is connected to.

Definition at line 152 of file subscriber.cpp.

◆ getTopic()

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

Returns the base image topic.

The Subscriber may actually be subscribed to some transport-specific topic that differs from the base topic.

Definition at line 146 of file subscriber.cpp.

◆ getTransport()

std::string image_transport::Subscriber::getTransport ( ) const

Returns the name of the transport being used.

Definition at line 158 of file subscriber.cpp.

◆ operator void *()

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

Definition at line 169 of file subscriber.cpp.

◆ operator!=()

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

Definition at line 156 of file subscriber.h.

◆ operator<()

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

Definition at line 155 of file subscriber.h.

◆ operator==()

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

Definition at line 157 of file subscriber.h.

◆ shutdown()

void image_transport::Subscriber::shutdown ( )

Unsubscribe the callback associated with this Subscriber.

Definition at line 164 of file subscriber.cpp.

Friends And Related Function Documentation

◆ ImageTransport

friend class ImageTransport
friend

Definition at line 171 of file subscriber.h.

Member Data Documentation

◆ impl_

ImplPtr image_transport::Subscriber::impl_
private

Definition at line 169 of file subscriber.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