topic_service_client.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2018, Southwest Research Institute® (SwRI®)
4 // All rights reserved.
5 //
6 // Redistribution and use in source and binary forms, with or without
7 // modification, are permitted provided that the following conditions are met:
8 // * Redistributions of source code must retain the above copyright
9 // notice, this list of conditions and the following disclaimer.
10 // * Redistributions in binary form must reproduce the above copyright
11 // notice, this list of conditions and the following disclaimer in the
12 // documentation and/or other materials provided with the distribution.
13 // * Neither the name of Southwest Research Institute® (SwRI®) nor the
14 // names of its contributors may be used to endorse or promote products
15 // derived from this software without specific prior written permission.
16 //
17 // THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18 // AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19 // IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20 // ARE DISCLAIMED. IN NO EVENT SHALL SOUTHWEST RESEARCH INSTITUTE 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 SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_
30 #define SWRI_ROSCPP_TOPIC_SERVICE_CLIENT_H_
31 
32 #include <ros/node_handle.h>
33 
34 #include <boost/thread/mutex.hpp>
35 
36 #include <map>
37 
38 namespace swri
39 {
40 
41 template<class MReq, class MRes>
43 {
44 private:
45  typedef
46  boost::mutex request_lock_;
50 
52  std::string name_;
53  std::string service_name_;
54 
55  int sequence_;
56 
57 public:
58  TopicServiceClientRaw() : sequence_(0), timeout_(ros::Duration(4.0))
59  {
60 
61  }
62 
64  const std::string &service,
65  const std::string &client_name = "")
66  {
67  name_ = client_name.length() ? client_name : ros::this_node::getName();
68  std::string rservice = nh.resolveName(service);
69  service_name_ = rservice;
70 
71  request_pub_ = nh.advertise<MReq>(rservice + "/request", 10);
72  response_sub_ = nh.subscribe(rservice + "/response", 10, &TopicServiceClientRaw<MReq, MRes>::response_callback, this);
73  }
74 
75  bool call(MReq& request, MRes& response)
76  {
77  boost::mutex::scoped_lock scoped_lock(request_lock_);
78 
79  // block for response
80  request.srv_header.stamp = ros::Time::now();
81  request.srv_header.sequence = sequence_;
82  request.srv_header.sender = name_;
83 
84  // Wait until we get a subscriber and publisher
85  while (request_pub_.getNumSubscribers() == 0 || response_sub_.getNumPublishers() == 0)
86  {
87  ros::Duration(0.002).sleep();
88  ros::spinOnce();
89 
90  if (ros::Time::now() - request.srv_header.stamp > timeout_)
91  {
92  return false;
93  }
94  }
95  request_pub_.publish(request);
96 
97  // Wait until we get a response
98  while (!response_ && ros::Time::now() - request.srv_header.stamp < timeout_)
99  {
100  ros::Duration(0.002).sleep();
101  ros::spinOnce();
102  }
103 
104  sequence_++;
105  if (response_)
106  {
107  response = *response_;
108  response_.reset();
109  return response.srv_header.result;
110  }
111  return false;
112  }
113 
114  std::string getService()
115  {
116  return service_name_;
117  }
118 
119  bool exists()
120  {
121  return request_pub_.getNumSubscribers() > 0 && response_sub_.getNumPublishers() > 0;
122  }
123 
124  // The service server can output a console log message when the
125  // service is called if desired.
126  void setLogCalls(bool enable);
127  bool logCalls() const;
128 private:
129 
131  {
132  ROS_DEBUG("Got response for %s with sequence %i",
133  message->srv_header.sender.c_str(), message->srv_header.sequence);
134 
135  if (message->srv_header.sender != name_)
136  {
137  ROS_DEBUG("Got response from another client, ignoring..");
138  return;
139  }
140 
141  if (message->srv_header.sequence != sequence_)
142  {
143  ROS_WARN("Got wrong sequence number, ignoring..");
144  return;
145  }
146 
147  response_ = message;
148  }
149 }; // class TopicServiceClientRaw
150 
151 template<class MReq>
152 class TopicServiceClient: public TopicServiceClientRaw<typename MReq:: Request, typename MReq:: Response>
153 {
154 public:
155  bool call(MReq& req)
156  {
158  }
159 
160 }; // class TopicServiceClient
161 
162 
163 } // namespace swri
164 #endif // SWRI_ROSCPP_TOPIC_SERVICE_SERVER_H_
void publish(const boost::shared_ptr< M > &message) const
void response_callback(const boost::shared_ptr< MRes > &message)
Subscriber subscribe(const std::string &topic, uint32_t queue_size, void(T::*fp)(M), T *obj, const TransportHints &transport_hints=TransportHints())
bool call(MReq &request, MRes &response)
std::string resolveName(const std::string &name, bool remap=true) const
bool sleep() const
ROSCPP_DECL const std::string & getName()
#define ROS_WARN(...)
boost::shared_ptr< MRes > response_
void initialize(ros::NodeHandle &nh, const std::string &service, const std::string &client_name="")
uint32_t getNumPublishers() const
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
uint32_t getNumSubscribers() const
void setLogCalls(bool enable)
static Time now()
ROSCPP_DECL void spinOnce()
#define ROS_DEBUG(...)


swri_roscpp
Author(s):
autogenerated on Fri Jun 7 2019 22:05:50