ros::Subscription Class Reference

Manages a subscription on a single topic. More...

#include <subscription.h>

List of all members.

Classes

struct  CallbackInfo
struct  LatchInfo
class  PendingConnection

Public Types

typedef std::map< std::string,
std::string > 
M_string
typedef boost::shared_ptr
< PendingConnection
PendingConnectionPtr

Public Member Functions

bool addCallback (const SubscriptionCallbackHelperPtr &helper, const std::string &md5sum, CallbackQueueInterface *queue, int32_t queue_size, const VoidConstPtr &tracked_object, bool allow_concurrent_callbacks)
void addLocalConnection (const PublicationPtr &pub)
const std::string datatype ()
void drop ()
 Terminate all our PublisherLinks.
void getInfo (XmlRpc::XmlRpcValue &info)
const std::string & getName () const
uint32_t getNumCallbacks () const
uint32_t getNumPublishers ()
void getPublishTypes (bool &ser, bool &nocopy, const std::type_info &ti)
XmlRpc::XmlRpcValue getStats ()
uint32_t handleMessage (const SerializedMessage &m, bool ser, bool nocopy, const boost::shared_ptr< M_string > &connection_header, const PublisherLinkPtr &link)
 Called to notify that a new message has arrived from a publisher. Schedules the callback for invokation with the callback queue.
void headerReceived (const PublisherLinkPtr &link, const Header &h)
bool isDropped ()
 Returns whether this Subscription has been dropped or not.
const std::string md5sum ()
bool negotiateConnection (const std::string &xmlrpc_uri)
 Negotiates a connection with a publisher.
void pendingConnectionDone (const PendingConnectionPtr &pending_conn, XmlRpc::XmlRpcValue &result)
bool pubUpdate (const std::vector< std::string > &pubs)
 Handle a publisher update list received from the master. Creates/drops PublisherLinks based on the list. Never handles new self-subscriptions.
void removeCallback (const SubscriptionCallbackHelperPtr &helper)
void removePublisherLink (const PublisherLinkPtr &pub_link)
 Removes a subscriber from our list.
void shutdown ()
 Terminate all our PublisherLinks and join our callback thread if it exists.
 Subscription (const std::string &name, const std::string &md5sum, const std::string &datatype, const TransportHints &transport_hints)
virtual ~Subscription ()

Private Types

typedef boost::shared_ptr
< CallbackInfo
CallbackInfoPtr
typedef std::map
< PublisherLinkPtr, LatchInfo
M_PublisherLinkToLatchInfo
typedef std::set
< PendingConnectionPtr
S_PendingConnection
typedef std::vector
< CallbackInfoPtr
V_CallbackInfo
typedef std::vector
< PublisherLinkPtr
V_PublisherLink
typedef std::vector< std::pair
< const std::type_info
*, MessageDeserializerPtr > > 
V_TypeAndDeserializer

Private Member Functions

void addPublisherLink (const PublisherLinkPtr &link)
void dropAllConnections ()
Subscriptionoperator= (const Subscription &)
 Subscription (const Subscription &)

Private Attributes

V_TypeAndDeserializer cached_deserializers_
V_CallbackInfo callbacks_
boost::mutex callbacks_mutex_
std::string datatype_
bool dropped_
M_PublisherLinkToLatchInfo latched_messages_
std::string md5sum_
boost::mutex md5sum_mutex_
std::string name_
uint32_t nonconst_callbacks_
S_PendingConnection pending_connections_
boost::mutex pending_connections_mutex_
V_PublisherLink publisher_links_
boost::mutex publisher_links_mutex_
boost::mutex shutdown_mutex_
bool shutting_down_
TransportHints transport_hints_

Detailed Description

Manages a subscription on a single topic.

Definition at line 57 of file subscription.h.


Member Typedef Documentation

typedef boost::shared_ptr<CallbackInfo> ros::Subscription::CallbackInfoPtr [private]

Definition at line 196 of file subscription.h.

Definition at line 229 of file subscription.h.

typedef std::map<std::string, std::string> ros::Subscription::M_string

Definition at line 94 of file subscription.h.

Definition at line 170 of file subscription.h.

Definition at line 211 of file subscription.h.

typedef std::vector<CallbackInfoPtr> ros::Subscription::V_CallbackInfo [private]

Definition at line 197 of file subscription.h.

typedef std::vector<PublisherLinkPtr> ros::Subscription::V_PublisherLink [private]

Definition at line 215 of file subscription.h.

typedef std::vector<std::pair<const std::type_info*, MessageDeserializerPtr> > ros::Subscription::V_TypeAndDeserializer [private]

Definition at line 232 of file subscription.h.


Constructor & Destructor Documentation

ros::Subscription::Subscription ( const std::string &  name,
const std::string &  md5sum,
const std::string &  datatype,
const TransportHints transport_hints 
)

Definition at line 71 of file subscription.cpp.

ros::Subscription::~Subscription (  )  [virtual]

Definition at line 82 of file subscription.cpp.

ros::Subscription::Subscription ( const Subscription  )  [private]

Member Function Documentation

bool ros::Subscription::addCallback ( const SubscriptionCallbackHelperPtr helper,
const std::string &  md5sum,
CallbackQueueInterface queue,
int32_t  queue_size,
const VoidConstPtr tracked_object,
bool  allow_concurrent_callbacks 
)

Definition at line 678 of file subscription.cpp.

void ros::Subscription::addLocalConnection ( const PublicationPtr pub  ) 

Definition at line 181 of file subscription.cpp.

void ros::Subscription::addPublisherLink ( const PublisherLinkPtr link  )  [private]

Definition at line 785 of file subscription.cpp.

const std::string ros::Subscription::datatype (  ) 

Definition at line 829 of file subscription.cpp.

void ros::Subscription::drop (  ) 

Terminate all our PublisherLinks.

Definition at line 151 of file subscription.cpp.

void ros::Subscription::dropAllConnections (  )  [private]

Definition at line 161 of file subscription.cpp.

void ros::Subscription::getInfo ( XmlRpc::XmlRpcValue &  info  ) 

Definition at line 128 of file subscription.cpp.

const std::string& ros::Subscription::getName (  )  const [inline]

Definition at line 110 of file subscription.h.

uint32_t ros::Subscription::getNumCallbacks (  )  const [inline]

Definition at line 111 of file subscription.h.

uint32_t ros::Subscription::getNumPublishers (  ) 

Definition at line 145 of file subscription.cpp.

void ros::Subscription::getPublishTypes ( bool &  ser,
bool &  nocopy,
const std::type_info &  ti 
)

Definition at line 806 of file subscription.cpp.

XmlRpcValue ros::Subscription::getStats (  ) 

Definition at line 98 of file subscription.cpp.

uint32_t ros::Subscription::handleMessage ( const SerializedMessage &  m,
bool  ser,
bool  nocopy,
const boost::shared_ptr< M_string > &  connection_header,
const PublisherLinkPtr link 
)

Called to notify that a new message has arrived from a publisher. Schedules the callback for invokation with the callback queue.

Definition at line 599 of file subscription.cpp.

void ros::Subscription::headerReceived ( const PublisherLinkPtr link,
const Header h 
)

Definition at line 776 of file subscription.cpp.

bool ros::Subscription::isDropped (  )  [inline]

Returns whether this Subscription has been dropped or not.

Definition at line 87 of file subscription.h.

const std::string ros::Subscription::md5sum (  ) 

Definition at line 834 of file subscription.cpp.

bool ros::Subscription::negotiateConnection ( const std::string &  xmlrpc_uri  ) 

Negotiates a connection with a publisher.

Parameters:
xmlrpc_uri The XMLRPC URI to connect to to negotiate the connection

Definition at line 342 of file subscription.cpp.

Subscription& ros::Subscription::operator= ( const Subscription  )  [private]
void ros::Subscription::pendingConnectionDone ( const PendingConnectionPtr pending_conn,
XmlRpc::XmlRpcValue &  result 
)
bool ros::Subscription::pubUpdate ( const std::vector< std::string > &  pubs  ) 

Handle a publisher update list received from the master. Creates/drops PublisherLinks based on the list. Never handles new self-subscriptions.

Definition at line 209 of file subscription.cpp.

void ros::Subscription::removeCallback ( const SubscriptionCallbackHelperPtr helper  ) 

Definition at line 753 of file subscription.cpp.

void ros::Subscription::removePublisherLink ( const PublisherLinkPtr pub_link  ) 

Removes a subscriber from our list.

Definition at line 790 of file subscription.cpp.

void ros::Subscription::shutdown (  ) 

Terminate all our PublisherLinks and join our callback thread if it exists.

Definition at line 88 of file subscription.cpp.


Member Data Documentation

Definition at line 233 of file subscription.h.

Definition at line 204 of file subscription.h.

boost::mutex ros::Subscription::callbacks_mutex_ [private]

Definition at line 203 of file subscription.h.

std::string ros::Subscription::datatype_ [private]

Definition at line 202 of file subscription.h.

Definition at line 207 of file subscription.h.

Definition at line 230 of file subscription.h.

std::string ros::Subscription::md5sum_ [private]

Definition at line 201 of file subscription.h.

boost::mutex ros::Subscription::md5sum_mutex_ [private]

Definition at line 200 of file subscription.h.

std::string ros::Subscription::name_ [private]

Definition at line 199 of file subscription.h.

Definition at line 205 of file subscription.h.

Definition at line 212 of file subscription.h.

Definition at line 213 of file subscription.h.

Definition at line 216 of file subscription.h.

Definition at line 217 of file subscription.h.

boost::mutex ros::Subscription::shutdown_mutex_ [private]

Definition at line 209 of file subscription.h.

Definition at line 208 of file subscription.h.

Definition at line 219 of file subscription.h.


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


roscpp
Author(s): Morgan Quigley mquigley@cs.stanford.edu, Josh Faust jfaust@willowgarage.com, Brian Gerkey gerkey@willowgarage.com
autogenerated on Fri Jan 11 10:08:41 2013