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  ServiceClient& operator=(const ServiceClient& other) = default;
50 
55  template<class MReq, class MRes>
56  bool call(MReq& req, MRes& res)
57  {
58  namespace st = service_traits;
59 
60  if (!isValid())
61  {
62  return false;
63  }
64 
65  if (strcmp(st::md5sum(req), st::md5sum(res)))
66  {
67  ROS_ERROR("The request and response parameters to the service "
68  "call must be autogenerated from the same "
69  "server definition file (.srv). your service call "
70  "for %s appeared to use request/response types "
71  "from different .srv files. (%s vs. %s)", impl_->name_.c_str(), st::md5sum(req), st::md5sum(res));
72  return false;
73  }
74 
75  return call(req, res, st::md5sum(req));
76  }
77 
81  template<class Service>
82  bool call(Service& service)
83  {
84  namespace st = service_traits;
85 
86  if (!isValid())
87  {
88  return false;
89  }
90 
91  return call(service.request, service.response, st::md5sum(service));
92  }
93 
97  template<typename MReq, typename MRes>
98  bool call(const MReq& req, MRes& resp, const std::string& service_md5sum)
99  {
100  namespace ser = serialization;
101  SerializedMessage ser_req = ser::serializeMessage(req);
102  SerializedMessage ser_resp;
103  bool ok = call(ser_req, ser_resp, service_md5sum);
104  if (!ok)
105  {
106  return false;
107  }
108 
109  try
110  {
111  ser::deserializeMessage(ser_resp, resp);
112  }
113  catch (std::exception& e)
114  {
115  deserializeFailed(e);
116  return false;
117  }
118 
119  return true;
120  }
121 
122  bool call(const SerializedMessage& req, SerializedMessage& resp, const std::string& service_md5sum);
123 
128  bool isValid() const;
129 
133  bool isPersistent() const;
134 
143  void shutdown();
144 
151  bool waitForExistence(ros::Duration timeout = ros::Duration(-1));
152 
157  bool exists();
158 
162  std::string getService();
163 
164  operator void*() const { return isValid() ? (void*)1 : (void*)0; }
165  bool operator<(const ServiceClient& rhs) const
166  {
167  return impl_ < rhs.impl_;
168  }
169 
170  bool operator==(const ServiceClient& rhs) const
171  {
172  return impl_ == rhs.impl_;
173  }
174 
175  bool operator!=(const ServiceClient& rhs) const
176  {
177  return impl_ != rhs.impl_;
178  }
179 
180 private:
181  // This works around a problem with the OSX linker that causes the static variable declared by
182  // ROS_ERROR to error with missing symbols when it's used directly in the templated call() method above
183  // This for some reason only showed up in the rxtools package
184  void deserializeFailed(const std::exception& e)
185  {
186  ROS_ERROR("Exception thrown while while deserializing service call: %s", e.what());
187  }
188 
189  struct Impl
190  {
191  Impl();
192  ~Impl();
193 
194  void shutdown();
195  bool isValid() const;
196 
198  std::string name_;
201  std::string service_md5sum_;
203  };
205  typedef boost::weak_ptr<Impl> ImplWPtr;
206 
207  ImplPtr impl_;
208 
209  friend class NodeHandle;
211 };
213 
214 }
215 
216 #endif
bool call(const std::string &service_name, MReq &req, MRes &res)
Invoke an RPC service.
Definition: service.h:65
bool operator==(const ServiceClient &rhs) const
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
bool operator!=(const ServiceClient &rhs) const
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:589
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:594
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
#define ROS_ERROR(...)
bool operator<(const ServiceClient &rhs) const
boost::shared_ptr< ServiceClient > ServiceClientPtr


roscpp
Author(s): Morgan Quigley, Josh Faust, Brian Gerkey, Troy Straszheim, Dirk Thomas
autogenerated on Mon Feb 28 2022 23:33:27