service_client.h
Go to the documentation of this file.
1 /*
2  * Copyright (C) 2009, Willow Garage, Inc.
3  *
4  * Redistribution and use in source and binary forms, with or without
5  * modification, are permitted provided that the following conditions are met:
6  * * Redistributions of source code must retain the above copyright notice,
7  * this list of conditions and the following disclaimer.
8  * * Redistributions in binary form must reproduce the above copyright
9  * notice, this list of conditions and the following disclaimer in the
10  * documentation and/or other materials provided with the distribution.
11  * * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
12  * contributors may be used to endorse or promote products derived from
13  * this software without specific prior written permission.
14  *
15  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
16  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
17  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
18  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
19  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
20  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
21  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
22  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
23  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
24  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
25  * POSSIBILITY OF SUCH DAMAGE.
26  */
27 
28 #ifndef ROSCPP_SERVICE_CLIENT_H
29 #define ROSCPP_SERVICE_CLIENT_H
30 
31 #include "ros/forwards.h"
32 #include "ros/common.h"
33 #include "ros/service_traits.h"
34 #include "ros/serialization.h"
35 
36 namespace ros
37 {
38 
42 class ROSCPP_DECL ServiceClient
43 {
44 public:
46  ServiceClient(const std::string& service_name, bool persistent, const M_string& header_values, const std::string& service_md5sum);
47  ServiceClient(const ServiceClient& rhs);
48  ~ServiceClient();
49 
54  template<class MReq, class MRes>
55  bool call(MReq& req, MRes& res)
56  {
57  namespace st = service_traits;
58 
59  if (!isValid())
60  {
61  return false;
62  }
63 
64  if (strcmp(st::md5sum(req), st::md5sum(res)))
65  {
66  ROS_ERROR("The request and response parameters to the service "
67  "call must be autogenerated from the same "
68  "server definition file (.srv). your service call "
69  "for %s appeared to use request/response types "
70  "from different .srv files. (%s vs. %s)", impl_->name_.c_str(), st::md5sum(req), st::md5sum(res));
71  return false;
72  }
73 
74  return call(req, res, st::md5sum(req));
75  }
76 
80  template<class Service>
81  bool call(Service& service)
82  {
83  namespace st = service_traits;
84 
85  if (!isValid())
86  {
87  return false;
88  }
89 
90  return call(service.request, service.response, st::md5sum(service));
91  }
92 
96  template<typename MReq, typename MRes>
97  bool call(const MReq& req, MRes& resp, const std::string& service_md5sum)
98  {
99  namespace ser = serialization;
100  SerializedMessage ser_req = ser::serializeMessage(req);
101  SerializedMessage ser_resp;
102  bool ok = call(ser_req, ser_resp, service_md5sum);
103  if (!ok)
104  {
105  return false;
106  }
107 
108  try
109  {
110  ser::deserializeMessage(ser_resp, resp);
111  }
112  catch (std::exception& e)
113  {
114  deserializeFailed(e);
115  return false;
116  }
117 
118  return true;
119  }
120 
121  bool call(const SerializedMessage& req, SerializedMessage& resp, const std::string& service_md5sum);
122 
127  bool isValid() const;
128 
132  bool isPersistent() const;
133 
142  void shutdown();
143 
150  bool waitForExistence(ros::Duration timeout = ros::Duration(-1));
151 
156  bool exists();
157 
161  std::string getService();
162 
163  operator void*() const { return isValid() ? (void*)1 : (void*)0; }
164  bool operator<(const ServiceClient& rhs) const
165  {
166  return impl_ < rhs.impl_;
167  }
168 
169  bool operator==(const ServiceClient& rhs) const
170  {
171  return impl_ == rhs.impl_;
172  }
173 
174  bool operator!=(const ServiceClient& rhs) const
175  {
176  return impl_ != rhs.impl_;
177  }
178 
179 private:
180  // This works around a problem with the OSX linker that causes the static variable declared by
181  // ROS_ERROR to error with missing symbols when it's used directly in the templated call() method above
182  // This for some reason only showed up in the rxtools package
183  void deserializeFailed(const std::exception& e)
184  {
185  ROS_ERROR("Exception thrown while while deserializing service call: %s", e.what());
186  }
187 
188  struct Impl
189  {
190  Impl();
191  ~Impl();
192 
193  void shutdown();
194  bool isValid() const;
195 
197  std::string name_;
200  std::string service_md5sum_;
202  };
204  typedef boost::weak_ptr<Impl> ImplWPtr;
205 
206  ImplPtr impl_;
207 
208  friend class NodeHandle;
210 };
212 
213 }
214 
215 #endif
bool operator!=(const ServiceClient &rhs) const
bool call(const std::string &service_name, MReq &req, MRes &res)
Invoke an RPC service.
Definition: service.h:65
bool call(MReq &req, MRes &res)
Call the service aliased by this handle with the specified request/response messages.
std::map< std::string, std::string > M_string
boost::shared_ptr< Impl > ImplPtr
ServiceServerLinkPtr server_link_
void deserializeFailed(const std::exception &e)
roscpp&#39;s interface for creating subscribers, publishers, etc.
Definition: node_handle.h:87
ROSCPP_DECL bool ok()
Check whether it&#39;s time to exit.
Definition: init.cpp:573
bool operator<(const ServiceClient &rhs) const
bool call(const MReq &req, MRes &resp, const std::string &service_md5sum)
Mostly for internal use, the other templated versions of call() just call into this one...
boost::weak_ptr< Impl > ImplWPtr
bool call(Service &service)
Call the service aliased by this handle with the specified service request/response.
Provides a handle-based interface to service client connections.
ROSCPP_DECL void shutdown()
Disconnects everything and unregisters from the master. It is generally not necessary to call this fu...
Definition: init.cpp:578
ROSCPP_DECL bool exists(const std::string &service_name, bool print_failure_reason)
Checks if a service is both advertised and available.
Definition: service.cpp:41
bool operator==(const ServiceClient &rhs) const
#define ROS_ERROR(...)
boost::shared_ptr< ServiceClient > ServiceClientPtr


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim
autogenerated on Sun Feb 3 2019 03:29:54