message_transport::Subscriber Class Reference

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

#include <subscriber.h>

List of all members.

Public Member Functions

template<class M >
int do_subscribe (ros::NodeHandle &nh, const std::string &package_name, const std::string &class_name, const std::string &base_topic, uint32_t queue_size, const boost::function< void(const typename M::ConstPtr &)> &callback, const ros::VoidPtr &tracked_object, const TransportHints &transport_hints)
uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to.
std::string getTopic () const
 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 (ros::NodeHandle &nh)
 Subscriber ()

Private Types

typedef boost::shared_ptr
< SubscriberImplGen
ImplPtr

Private Attributes

ImplPtr impl_

Detailed Description

Manages a subscription callback on a specific topic that can be interpreted as an Message 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 Message callback.

A Subscriber should always be created through a call to MessageTransport::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 59 of file subscriber.h.


Member Typedef Documentation

typedef boost::shared_ptr<SubscriberImplGen> message_transport::Subscriber::ImplPtr [private]

Definition at line 118 of file subscriber.h.


Constructor & Destructor Documentation

message_transport::Subscriber::Subscriber (  )  [inline]

Definition at line 62 of file subscriber.h.

message_transport::Subscriber::Subscriber ( ros::NodeHandle &  nh  ) 

Definition at line 43 of file subscriber.cpp.


Member Function Documentation

template<class M >
int message_transport::Subscriber::do_subscribe ( ros::NodeHandle &  nh,
const std::string &  package_name,
const std::string &  class_name,
const std::string &  base_topic,
uint32_t  queue_size,
const boost::function< void(const typename M::ConstPtr &)> &  callback,
const ros::VoidPtr &  tracked_object,
const TransportHints transport_hints 
) [inline]

Definition at line 83 of file subscriber.h.

uint32_t message_transport::Subscriber::getNumPublishers (  )  const

Returns the number of publishers this subscriber is connected to.

Definition at line 55 of file subscriber.cpp.

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

Definition at line 49 of file subscriber.cpp.

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

Definition at line 66 of file subscriber.cpp.

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

Definition at line 79 of file subscriber.h.

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

Definition at line 78 of file subscriber.h.

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

Definition at line 80 of file subscriber.h.

void message_transport::Subscriber::shutdown (  ) 

Unsubscribe the callback associated with this Subscriber.

Definition at line 61 of file subscriber.cpp.


Member Data Documentation

Definition at line 120 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 Defines


message_transport_common
Author(s): Cedric Pradalier
autogenerated on Fri Jan 11 09:52:59 2013