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>

List of all members.

Classes

struct  Impl

Public Member Functions

uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to.
std::string getTopic () const
 Returns the base image topic.
std::string getTransport () const
 Returns the name of the transport being used.
 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.
 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 61 of file subscriber.h.


Member Typedef Documentation

typedef boost::shared_ptr<Impl> image_transport::Subscriber::ImplPtr [private]

Definition at line 100 of file subscriber.h.

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

Definition at line 102 of file subscriber.h.


Constructor & Destructor Documentation

image_transport::Subscriber::Subscriber (  )  [inline]

Definition at line 64 of file subscriber.h.

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 75 of file subscriber.cpp.


Member Function Documentation

uint32_t image_transport::Subscriber::getNumPublishers (  )  const

Returns the number of publishers this subscriber is connected to.

Definition at line 120 of file subscriber.cpp.

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 114 of file subscriber.cpp.

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

Returns the name of the transport being used.

Definition at line 126 of file subscriber.cpp.

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

Definition at line 137 of file subscriber.cpp.

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

Definition at line 91 of file subscriber.h.

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

Definition at line 90 of file subscriber.h.

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

Definition at line 92 of file subscriber.h.

void image_transport::Subscriber::shutdown (  ) 

Unsubscribe the callback associated with this Subscriber.

Definition at line 132 of file subscriber.cpp.


Friends And Related Function Documentation

friend class ImageTransport [friend]

Definition at line 106 of file subscriber.h.


Member Data Documentation

Definition at line 104 of file subscriber.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 09:40:42 2013