28 #ifndef ROSCPP_PUBLISHER_LINK_H 29 #define ROSCPP_PUBLISHER_LINK_H 31 #include "ros/common.h" 35 #include <boost/thread/mutex.hpp> 36 #include <boost/shared_array.hpp> 37 #include <boost/weak_ptr.hpp> 38 #include <boost/enable_shared_from_this.hpp> 56 class ROSCPP_DECL
PublisherLink :
public boost::enable_shared_from_this<PublisherLink>
64 : bytes_received_(0), messages_received_(0), drops_(0) { }
72 const std::string& getPublisherXMLRPCURI();
82 virtual void handleMessage(
const SerializedMessage& m,
bool ser,
bool nocopy) = 0;
83 virtual std::string getTransportType() = 0;
84 virtual std::string getTransportInfo() = 0;
85 virtual void drop() = 0;
87 const std::string& getMD5Sum();
106 #endif // ROSCPP_PUBLISHER_LINK_H
std::string publisher_xmlrpc_uri_
const std::string & getCallerID()
boost::shared_ptr< Connection > ConnectionPtr
unsigned int connection_id_
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
boost::weak_ptr< Subscription > SubscriptionWPtr
Handles a connection to a single publisher on a given topic. Receives messages from a publisher and h...
boost::shared_ptr< Subscription > SubscriptionPtr
TransportHints transport_hints_
int getConnectionID() const
uint64_t messages_received_