28 #ifndef ROSCPP_SERVICE_CLIENT_LINK_H 29 #define ROSCPP_SERVICE_CLIENT_LINK_H 31 #include "ros/common.h" 33 #include <boost/thread/mutex.hpp> 34 #include <boost/shared_array.hpp> 35 #include <boost/enable_shared_from_this.hpp> 36 #include <boost/signals2/connection.hpp> 52 class ROSCPP_DECL
ServiceClientLink :
public boost::enable_shared_from_this<ServiceClientLink>
59 bool initialize(
const ConnectionPtr& connection);
72 void onConnectionDropped(
const ConnectionPtr& conn);
74 void onHeaderWritten(
const ConnectionPtr& conn);
77 void onResponseWritten(
const ConnectionPtr& conn);
88 #endif // ROSCPP_PUBLISHER_DATA_HANDLER_H ROSCONSOLE_DECL void initialize()
const ConnectionPtr & getConnection()
boost::shared_ptr< Connection > ConnectionPtr
Encapsulates a connection to a remote host, independent of the transport type.
std_msgs::Header * header(M &m)
Handles a connection to a single incoming service client.
ConnectionPtr connection_
ServicePublicationWPtr parent_
Manages an advertised service.
ROSCPP_DECL bool ok()
Check whether it's time to exit.
boost::signals2::connection dropped_conn_
boost::weak_ptr< ServicePublication > ServicePublicationWPtr
boost::shared_ptr< ServicePublication > ServicePublicationPtr
boost::shared_ptr< ServiceClientLink > ServiceClientLinkPtr