51 #include <boost/bind.hpp> 60 , retry_timer_handle_(-1)
98 header[
"topic"] = parent->getName();
99 header[
"md5sum"] = parent->md5sum();
101 header[
"type"] = parent->datatype();
120 parent->removePublisherLink(shared_from_this());
172 uint32_t len = *((uint32_t*)buffer.get());
174 if (len > 1000000000)
176 ROS_ERROR(
"a message of over a gigabyte was " \
177 "predicted in tcpros. that seems highly " \
178 "unlikely, so I'll assume protocol " \
179 "synchronization is lost.");
189 if (!success && !conn)
199 if (success || !
connection_->getTransport()->requiresHeader())
221 if (
connection_->getTransport()->getType() == std::string(
"TCPROS"))
223 std::string topic = parent ? parent->getName() :
"unknown";
227 const std::string& host = old_transport->getConnectedHost();
228 int port = old_transport->getConnectedPort();
230 ROSCPP_CONN_LOG_DEBUG(
"Retrying connection to [%s:%d] for topic [%s]", host.c_str(), port, topic.c_str());
233 if (transport->connect(host, port))
244 ROSCPP_CONN_LOG_DEBUG(
"connect() failed when retrying connection to [%s:%d] for topic [%s]", host.c_str(), port, topic.c_str());
249 parent->removePublisherLink(shared_from_this());
270 std::string topic = parent ? parent->getName() :
"unknown";
286 shared_from_this(),
false);
319 return connection_->getTransport()->getTransportInfo();
void onHeaderWritten(const ConnectionPtr &conn)
bool getTCPNoDelay()
Returns whether or not this TransportHints has specified TCP_NODELAY.
ROSCPP_DECL InternalTimerManagerPtr getInternalTimerManager()
WallDuration retry_period_
ROSCPP_DECL const std::string & getName()
Returns the name of the current node.
bool onHeaderReceived(const ConnectionPtr &conn, const Header &header)
const ConnectionPtr & getConnection()
boost::function< bool(const ConnectionPtr &, const Header &)> HeaderReceivedFunc
virtual std::string getTransportInfo()
Provides a way of specifying network transport hints to ros::NodeHandle::subscribe() and someday ros:...
std::map< std::string, std::string > M_string
ConnectionPtr connection_
static const ConnectionManagerPtr & instance()
virtual std::string getTransportType()
void onRetryTimer(const ros::SteadyTimerEvent &)
Handles a connection to a single publisher on a given topic. Receives messages from a publisher and h...
CallbackQueuePtr getInternalCallbackQueue()
TransportHints transport_hints_
void onMessageLength(const ConnectionPtr &conn, const boost::shared_array< uint8_t > &buffer, uint32_t size, bool success)
Structure passed as a parameter to the callback invoked by a ros::SteadyTimer.
bool initialize(const ConnectionPtr &connection)
virtual ~TransportPublisherLink()
TransportPublisherLink(const SubscriptionPtr &parent, const std::string &xmlrpc_uri, const TransportHints &transport_hints)
static const PollManagerPtr & instance()
#define ROSCPP_CONN_LOG_DEBUG(...)
int32_t retry_timer_handle_
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 ...
bool setHeader(const Header &header)
void onMessage(const ConnectionPtr &conn, const boost::shared_array< uint8_t > &buffer, uint32_t size, bool success)
void onConnectionDropped(const ConnectionPtr &conn, Connection::DropReason reason)
uint64_t messages_received_