service.h
Go to the documentation of this file.
1 #include "sick_scan/sick_scan_base.h" /* Base definitions included in all header files, added by add_sick_scan_base_header.py. Do not edit this line. */
2 /*
3  * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  * * Redistributions of source code must retain the above copyright notice,
8  * this list of conditions and the following disclaimer.
9  * * Redistributions in binary form must reproduce the above copyright
10  * notice, this list of conditions and the following disclaimer in the
11  * documentation and/or other materials provided with the distribution.
12  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
13  * contributors may be used to endorse or promote products derived from
14  * this software without specific prior written permission.
15  *
16  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
17  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
18  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
19  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
20  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
21  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
22  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
23  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
24  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
25  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
26  * POSSIBILITY OF SUCH DAMAGE.
27  */
28 
29 #ifndef ROSCPP_SERVICE_H
30 #define ROSCPP_SERVICE_H
31 
32 #include <string>
33 #include "ros/common.h"
34 #include "ros/message.h"
35 #include "ros/forwards.h"
36 #include "ros/node_handle.h"
37 #include "ros/service_traits.h"
38 #include "ros/names.h"
39 
40 #include <memory>
41 
42 namespace roswrap
43 {
44 
45 class ServiceServerLink;
46 typedef std::shared_ptr<ServiceServerLink> ServiceServerLinkPtr;
47 
51 namespace service
52 {
53 
65 template<class MReq, class MRes>
66 bool call(const std::string& service_name, MReq& req, MRes& res)
67 {
68  namespace st = service_traits;
69  NodeHandle nh;
70  ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(req), false, M_string());
71  ServiceClient client = nh.serviceClient(ops);
72  return client.call(req, res);
73 }
74 
85 template<class Service>
86 bool call(const std::string& service_name, Service& service)
87 {
88  namespace st = service_traits;
89 
90  NodeHandle nh;
91  ServiceClientOptions ops(ros::names::resolve(service_name), st::md5sum(service), false, M_string());
92  ServiceClient client = nh.serviceClient(ops);
93  return client.call(service.request, service.response);
94 }
95 
103 ROSCPP_DECL bool waitForService(const std::string& service_name, int32_t timeout);
104 
112 ROSCPP_DECL bool waitForService(const std::string& service_name, ros::Duration timeout = ros::Duration(-1));
113 
121 ROSCPP_DECL bool exists(const std::string& service_name, bool print_failure_reason);
122 
133 template<class MReq, class MRes>
134 ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
135 {
136  NodeHandle nh;
137  ServiceClient client = nh.template serviceClient<MReq, MRes>(ros::names::resolve(service_name), persistent, header_values);
138  return client;
139 }
140 
151 template<class Service>
152 ServiceClient createClient(const std::string& service_name, bool persistent = false, const M_string& header_values = M_string())
153 {
154  NodeHandle nh;
155  ServiceClient client = nh.template serviceClient<Service>(ros::names::resolve(service_name), persistent, header_values);
156  return client;
157 }
158 
159 }
160 
161 }
162 
163 #endif // ROSCPP_SERVICE_H
164 
roswrap::message_traits::md5sum
const char * md5sum()
returns MD5Sum<M>::value();
Definition: message_traits.h:227
roswrap::ServiceClientOptions
Encapsulates all options available for creating a ServiceClient.
Definition: service_client_options.h:42
roswrap::ServiceClient::call
bool call(MReq &req, MRes &res)
Call the service aliased by this handle with the specified request/response messages.
Definition: service_client.h:56
roswrap::M_string
std::map< std::string, std::string > M_string
Definition: datatypes.h:46
roswrap::service::waitForService
ROSCPP_DECL bool waitForService(const std::string &service_name, int32_t timeout)
Wait for a service to be advertised and available. Blocks until it is.
roswrap::service::createClient
ServiceClient createClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Create a client for a service.
Definition: service.h:134
ros::names::resolve
ROSCPP_DECL std::string resolve(const std::string &name, bool remap=true)
Resolve a graph resource name into a fully qualified graph resource name.
roswrap::NodeHandle::serviceClient
ServiceClient serviceClient(const std::string &service_name, bool persistent=false, const M_string &header_values=M_string())
Create a client for a service, version templated on two message types.
Definition: node_handle.h:1240
roswrap::ServiceClient
Provides a handle-based interface to service client connections.
Definition: service_client.h:43
roswrap
Definition: param_modi.cpp:41
roswrap::NodeHandle
roscpp's interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
roswrap::ServiceServerLinkPtr
std::shared_ptr< ServiceServerLink > ServiceServerLinkPtr
Definition: forwards.h:87
sick_scan_base.h
sick_generic_device_finder.timeout
timeout
Definition: sick_generic_device_finder.py:113
roswrap::service::exists
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
Checks if a service is both advertised and available.
ROSCPP_DECL
#define ROSCPP_DECL
Definition: roswrap/src/cfgsimu/sick_scan/ros/common.h:63
roswrap::service::call
bool call(const std::string &service_name, MReq &req, MRes &res)
Invoke an RPC service.
Definition: service.h:66
ros::Duration


sick_scan_xd
Author(s): Michael Lehning , Jochen Sprickerhof , Martin Günther
autogenerated on Fri Oct 25 2024 02:47:10