45 #include <boost/bind.hpp> 72 (*values)[
"topic"] = parent->getName();
73 (*values)[
"type"] = publisher->getDataType();
74 (*values)[
"md5sum"] = publisher->getMD5Sum();
75 (*values)[
"message_definition"] = publisher->getMessageDefinition();
76 (*values)[
"latching"] = publisher->isLatching() ?
"1" :
"0";
83 boost::recursive_mutex::scoped_lock lock(
drop_mutex_);
100 ROSCPP_LOG_DEBUG(
"Connection to local publisher on topic [%s] dropped", parent->getName().c_str());
102 parent->removePublisherLink(shared_from_this());
108 boost::recursive_mutex::scoped_lock lock(
drop_mutex_);
127 return std::string(
"INTRAPROCESS");
138 boost::recursive_mutex::scoped_lock lock(
drop_mutex_);
149 parent->getPublishTypes(ser, nocopy, ti);
virtual std::string getTransportType()
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
#define ROSCPP_LOG_DEBUG(...)
boost::recursive_mutex drop_mutex_
virtual void handleMessage(const SerializedMessage &m, bool ser, bool nocopy)
Handles handing off a received message to the subscription, where it will be deserialized and called ...
IntraProcessPublisherLink(const SubscriptionPtr &parent, const std::string &xmlrpc_uri, const TransportHints &transport_hints)
Handles a connection to a single publisher on a given topic. Receives messages from a publisher and h...
IntraProcessSubscriberLinkPtr publisher_
virtual ~IntraProcessPublisherLink()
void setPublisher(const IntraProcessSubscriberLinkPtr &publisher)
bool setHeader(const Header &header)
void getPublishTypes(bool &ser, bool &nocopy, const std::type_info &ti)
virtual std::string getTransportInfo()
uint64_t messages_received_