service_client.h
Go to the documentation of this file.
1 //=================================================================================================
2 // Copyright (c) 2013, Johannes Meyer, TU Darmstadt
3 // All rights reserved.
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
8 // notice, 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 name of the Flight Systems and Automatic Control group,
13 // TU Darmstadt, nor the names of its contributors may be used to
14 // endorse or promote products derived from this software without
15 // specific prior written permission.
16 
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND
18 // ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED
19 // WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
20 // DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER BE LIABLE FOR ANY
21 // DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES
22 // (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
23 // LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND
24 // ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT
25 // (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS
26 // SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
27 //=================================================================================================
28 
29 #ifndef TOPIC_PROXY_SERVICE_CLIENT_H
30 #define TOPIC_PROXY_SERVICE_CLIENT_H
31 
32 #include <ros/forwards.h>
33 #include <ros/common.h>
34 #include <ros/service_traits.h>
35 #include <ros/serialization.h>
36 
37 namespace topic_proxy
38 {
39 
41 public:
42  ServiceClient();
43  ServiceClient(const ServiceClient& rhs);
45 
46  template <typename Service>
47  ServiceClient(const std::string& service_name, const std::string& host = std::string(), uint32_t port = 0, const ros::M_string& header_values = ros::M_string())
48  {
49  init<Service>(service_name, host, port, header_values);
50  }
51 
52  template <typename Service>
53  bool init(const std::string& service_name, std::string host = std::string(), uint32_t port = 0, const ros::M_string& header_values = ros::M_string())
54  {
55  return init(service_name, std::string(ros::service_traits::md5sum<Service>()), host, port, header_values);
56  }
57 
58  bool init(const std::string& service_name, const std::string& service_md5sum, std::string host = std::string(), uint32_t port = 0, const ros::M_string& header_values = ros::M_string());
59 
64  template<class MReq, class MRes>
65  bool call(MReq& req, MRes& res)
66  {
67  namespace st = ros::service_traits;
68 
69  if (!isValid())
70  {
71  return false;
72  }
73 
74  if (strcmp(st::md5sum(req), st::md5sum(res)))
75  {
76  ROS_ERROR("The request and response parameters to the service "
77  "call must be autogenerated from the same "
78  "server definition file (.srv). your service call "
79  "for %s appeared to use request/response types "
80  "from different .srv files. (%s vs. %s)", impl_->name_.c_str(), st::md5sum(req), st::md5sum(res));
81  return false;
82  }
83 
84  return call(req, res, st::md5sum(req));
85  }
86 
90  template<class Service>
91  bool call(Service& service)
92  {
93  namespace st = ros::service_traits;
94 
95  if (!isValid())
96  {
97  return false;
98  }
99 
100  return call(service.request, service.response, st::md5sum(service));
101  }
102 
106  template<typename MReq, typename MRes>
107  bool call(const MReq& req, MRes& resp, const std::string& service_md5sum)
108  {
109  namespace ser = ros::serialization;
110  ros::SerializedMessage ser_req = ser::serializeMessage(req);
111  ros::SerializedMessage ser_resp;
112  bool ok = call(ser_req, ser_resp, service_md5sum);
113  if (!ok)
114  {
115  return false;
116  }
117 
118  try
119  {
120  ser::deserializeMessage(ser_resp, resp);
121  }
122  catch (std::exception& e)
123  {
125  return false;
126  }
127 
128  return true;
129  }
130 
131  bool call(const ros::SerializedMessage& req, ros::SerializedMessage& resp, const std::string& service_md5sum);
132 
137  bool isValid() const;
138 
147  void shutdown();
148 
152  std::string getService();
153 
154 private:
155  // This works around a problem with the OSX linker that causes the static variable declared by
156  // ROS_ERROR to error with missing symbols when it's used directly in the templated call() method above
157  // This for some reason only showed up in the rxtools package
158  void deserializeFailed(const std::exception& e)
159  {
160  ROS_ERROR("Exception thrown while while deserializing service call: %s", e.what());
161  }
162 
163  struct Impl
164  {
165  Impl();
166  ~Impl();
167 
168  void shutdown();
169  bool isValid() const;
170 
172  std::string name_;
175  };
177  typedef boost::weak_ptr<Impl> ImplWPtr;
178 
179  ImplPtr impl_;
180 };
181 
182 } // namespace topic_proxy
183 
184 #endif // TOPIC_PROXY_SERVICE_CLIENT_H
boost::shared_ptr< Impl > ImplPtr
bool call(Service &service)
Call the service aliased by this handle with the specified service request/response.
boost::weak_ptr< Impl > ImplWPtr
bool call(MReq &req, MRes &res)
std::map< std::string, std::string > M_string
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...
void deserializeFailed(const std::exception &e)
ros::ServiceServerLinkPtr server_link_
bool call(MReq &req, MRes &res)
Call the service aliased by this handle with the specified request/response messages.
ROSCPP_DECL bool ok()
ServiceClient(const std::string &service_name, const std::string &host=std::string(), uint32_t port=0, const ros::M_string &header_values=ros::M_string())
bool init(const std::string &service_name, std::string host=std::string(), uint32_t port=0, const ros::M_string &header_values=ros::M_string())
bool isValid() const
std::string getService()
void deserializeFailed(const std::exception &e)
#define ROS_ERROR(...)


topic_proxy
Author(s): Johannes Meyer
autogenerated on Sat Jul 27 2019 03:35:25