Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028 #ifndef ROSCPP_SERVICE_H
00029 #define ROSCPP_SERVICE_H
00030
00031 #include <string>
00032 #include "ros/common.h"
00033 #include "ros/message.h"
00034 #include "ros/forwards.h"
00035 #include "ros/node_handle.h"
00036 #include "ros/service_traits.h"
00037 #include "ros/names.h"
00038
00039 #include <boost/shared_ptr.hpp>
00040
00041 namespace ros
00042 {
00043
00044 class ServiceServerLink;
00045 typedef boost::shared_ptr<ServiceServerLink> ServiceServerLinkPtr;
00046
00050 namespace service
00051 {
00052
00064 template<class MReq, class MRes>
00065 bool call(const std::string& service_name, MReq& req, MRes& res)
00066 {
00067 namespace st = service_traits;
00068 NodeHandle nh;
00069 ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(req), false, M_string());
00070 ServiceClient client = nh.serviceClient(ops);
00071 return client.call(req, res);
00072 }
00073
00084 template<class Service>
00085 bool call(const std::string& service_name, Service& service)
00086 {
00087 namespace st = service_traits;
00088
00089 NodeHandle nh;
00090 ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(service), false, M_string());
00091 ServiceClient client = nh.serviceClient(ops);
00092 return client.call(service.request, service.response);
00093 }
00094
00102 ROSCPP_DECL bool waitForService(const std::string& service_name, int32_t timeout);
00103
00111 ROSCPP_DECL bool waitForService(const std::string& service_name, ros::Duration timeout = ros::Duration(-1));
00112
00120 ROSCPP_DECL bool exists(const std::string& service_name, bool print_failure_reason);
00121
00132 template<class MReq, class MRes>
00133 ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
00134 {
00135 NodeHandle nh;
00136 ServiceClient client = nh.template serviceClient<MReq, MRes>(ros::names::resolve(service_name), persistent, header_values);
00137 return client;
00138 }
00139
00150 template<class Service>
00151 ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
00152 {
00153 NodeHandle nh;
00154 ServiceClient client = nh.template serviceClient<Service>(ros::names::resolve(service_name), persistent, header_values);
00155 return client;
00156 }
00157
00158 }
00159
00160 }
00161
00162 #endif // ROSCPP_SERVICE_H
00163
roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Mon Oct 6 2014 11:46:44