Go to the documentation of this file.
28 #ifndef ROSCPP_SUBSCRIPTION_H
29 #define ROSCPP_SUBSCRIPTION_H
32 #include "ros/common.h"
40 #include <boost/thread.hpp>
41 #include <boost/shared_ptr.hpp>
42 #include <boost/enable_shared_from_this.hpp>
50 class SubscriptionCallback;
65 class ROSCPP_DECL
Subscription :
public boost::enable_shared_from_this<Subscription>
83 bool pubUpdate(
const std::vector<std::string> &pubs);
88 bool negotiateConnection(
const std::string& xmlrpc_uri);
102 typedef std::map<std::string, std::string>
M_string;
111 const std::string
md5sum();
118 const std::string&
getName()
const {
return name_; }
120 uint32_t getNumPublishers();
129 , udp_transport_(udp_transport)
131 , remote_uri_(remote_uri)
161 if (client_->executeCheckDone(result))
163 parent->pendingConnectionDone(boost::dynamic_pointer_cast<PendingConnection>(shared_from_this()), result);
182 void getPublishTypes(
bool& ser,
bool& nocopy,
const std::type_info& ti);
190 void dropAllConnections();
std::set< PendingConnectionPtr > S_PendingConnection
std::vector< CallbackInfoPtr > V_CallbackInfo
boost::shared_ptr< SubscriptionCallbackHelper > SubscriptionCallbackHelperPtr
XmlRpc::XmlRpcClient * getClient() const
boost::shared_ptr< MessageDeserializer > MessageDeserializerPtr
boost::shared_ptr< PendingConnection > PendingConnectionPtr
SerializedMessage message
boost::mutex md5sum_mutex_
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
std::map< PublisherLinkPtr, LatchInfo > M_PublisherLinkToLatchInfo
TransportUDPPtr udp_transport_
V_TypeAndDeserializer cached_deserializers_
std::vector< PublisherLinkPtr > V_PublisherLink
void addSource(XmlRpcSource *source, unsigned eventMask)
TransportUDPPtr getUDPTransport() const
boost::mutex shutdown_mutex_
const std::string & getName() const
uint32_t nonconst_callbacks_
boost::shared_ptr< PublisherLink > PublisherLinkPtr
XmlRpc::XmlRpcClient * client_
boost::shared_ptr< SubscriptionCallback > SubscriptionCallbackPtr
V_CallbackInfo callbacks_
bool isDropped()
Returns whether this Subscription has been dropped or not.
void removeSource(XmlRpcSource *source)
boost::weak_ptr< Subscription > SubscriptionWPtr
CallbackQueueInterface * callback_queue_
boost::shared_ptr< CallbackInfo > CallbackInfoPtr
PendingConnection(XmlRpc::XmlRpcClient *client, TransportUDPPtr udp_transport, const SubscriptionWPtr &parent, const std::string &remote_uri)
StatisticsLogger statistics_
SubscriptionCallbackHelperPtr helper_
virtual void removeFromDispatch(XmlRpc::XmlRpcDispatch *disp)
boost::shared_ptr< std::map< std::string, std::string > > connection_header
boost::weak_ptr< void const > VoidConstWPtr
virtual void addToDispatch(XmlRpc::XmlRpcDispatch *disp)
boost::mutex publisher_links_mutex_
std::map< std::string, std::string > M_string
boost::mutex callbacks_mutex_
M_PublisherLinkToLatchInfo latched_messages_
S_PendingConnection pending_connections_
uint32_t getNumCallbacks() const
const std::string & getRemoteURI()
boost::shared_ptr< SubscriptionQueue > SubscriptionQueuePtr
VoidConstWPtr tracked_object_
Manages a subscription on a single topic.
This class logs statistics data about a ROS connection and publishs them periodically on a common top...
SubscriptionQueuePtr subscription_queue_
std::vector< std::pair< const std::type_info *, MessageDeserializerPtr > > V_TypeAndDeserializer
Abstract base class used by subscriptions to deal with concrete message types through a common interf...
TransportHints transport_hints_
V_PublisherLink publisher_links_
boost::mutex pending_connections_mutex_
Abstract interface for a queue used to handle all callbacks within roscpp.
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
, Jacob Perron
autogenerated on Sat Sep 14 2024 02:59:36