35 #ifndef ROSCPP_SERVICE_SERVER_LINK_H 36 #define ROSCPP_SERVICE_SERVER_LINK_H 38 #include "ros/common.h" 41 #include <boost/thread/mutex.hpp> 42 #include <boost/shared_array.hpp> 43 #include <boost/enable_shared_from_this.hpp> 44 #include <boost/thread.hpp> 59 class ROSCPP_DECL
ServiceServerLink :
public boost::enable_shared_from_this<ServiceServerLink>
81 typedef std::map<std::string, std::string>
M_string;
82 ServiceServerLink(
const std::string& service_name,
bool persistent,
const std::string& request_md5sum,
const std::string& response_md5sum,
const M_string& header_values);
86 bool initialize(
const ConnectionPtr& connection);
112 void onConnectionDropped(
const ConnectionPtr& conn);
113 bool onHeaderReceived(
const ConnectionPtr& conn,
const Header&
header);
124 void processNextCall();
132 void cancelCall(
const CallInfoPtr& info);
134 void onHeaderWritten(
const ConnectionPtr& conn);
135 void onRequestWritten(
const ConnectionPtr& conn);
160 #endif // ROSCPP_SERVICE_SERVER_LINK_H ros::internal::condition_variable_monotonic finished_condition_
boost::mutex finished_mutex_
const ConnectionPtr & getConnection() const
ROSCONSOLE_DECL void initialize()
boost::thread::id caller_thread_id_
bool call(const std::string &service_name, MReq &req, MRes &res)
Invoke an RPC service.
SerializedMessage * resp_
boost::shared_ptr< Connection > ConnectionPtr
ConnectionPtr connection_
std_msgs::Header * header(M &m)
std::map< std::string, std::string > M_string
const std::string & getServiceName() const
std::queue< CallInfoPtr > Q_CallInfo
CallInfoPtr current_call_
std::string exception_string_
boost::shared_ptr< CallInfo > CallInfoPtr
std::string service_name_
std::string request_md5sum_
boost::mutex call_queue_mutex_
bool isPersistent() const
Returns whether this is a persistent connection.
boost::condition_variable condition_variable_monotonic
M_string extra_outgoing_header_values_
Handles a connection to a service. If it's a non-persistent client, automatically disconnects when it...
const std::string & getRequestMD5Sum() const
std::string response_md5sum_
boost::shared_ptr< ServiceServerLink > ServiceServerLinkPtr
const std::string & getResponseMD5Sum() const