service_server_impl.h
Go to the documentation of this file.
1 // *****************************************************************************
2 //
3 // Copyright (c) 2015, 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_SERVICE_SERVER_IMPL_H_
30 #define SWRI_ROSCPP_SERVICE_SERVER_IMPL_H_
31 
33 
34 namespace swri
35 {
36 class ServiceServer;
38 {
39  protected:
41  std::string unmapped_service_;
42  std::string mapped_service_;
43 
46  std::map<std::string, ServiceServerStatistics> client_stats_;
47 
48  bool log_calls_;
49 
50  void processServing(const std::string caller_name,
51  bool success,
52  const ros::WallDuration &runtime)
53  {
54  total_stats_.merge(success, runtime);
55  if (instrument_per_client_) {
56  client_stats_[caller_name].merge(success, runtime);
57  }
58  }
59 
60  public:
62  :
63  unmapped_service_("uninitialized"),
64  mapped_service_("initialized"),
65  instrument_per_client_(false),
66  log_calls_(false)
67  {
68  }
69 
71  {
72  total_stats_.reset();
73  client_stats_.clear();
74  }
75 
76  const std::string& unmappedService() const { return unmapped_service_; }
77  const std::string& mappedService() const { return mapped_service_; }
78 
79  const ServiceServerStatistics& totalStats() const { return total_stats_; }
80 
81  void setInstrumentPerClient(bool enable)
82  {
83  instrument_per_client_ = enable;
84  if (!instrument_per_client_) {
85  client_stats_.clear();
86  }
87  }
88 
90 
91  std::vector<std::string> clientNames() const
92  {
93  std::vector<std::string> names;
94  names.reserve(client_stats_.size());
95 
96  std::map<std::string, ServiceServerStatistics>::const_iterator it;
97  for (it = client_stats_.begin(); it != client_stats_.end(); it++) {
98  names.push_back(it->first);
99  }
100  return names;
101  }
102 
104  const std::string &name) const
105  {
106  std::map<std::string, ServiceServerStatistics>::const_iterator it;
107  it = client_stats_.find(name);
108  if (it == client_stats_.end()) {
109  return ServiceServerStatistics();
110  } else {
111  return it->second;
112  }
113  }
114 
115  void setLogCalls(bool enable)
116  {
117  log_calls_ = enable;
118  }
119 
120  bool logCalls() const { return log_calls_; }
121 };
122 
123 template<class MReq, class MRes, class T>
125 {
126  T *obj_;
127  bool (T::*callback_plain_)(MReq &, MRes &);
128  bool (T::*callback_with_event_)(ros::ServiceEvent< MReq, MRes > &);
129  bool (T::*callback_with_name_)(const std::string &, const MReq &, MRes &);
130 
132  const std::string &service)
133  {
134  unmapped_service_ = service;
135  mapped_service_ = nh.resolveName(service);
136 
138  ROS_INFO("Serving to '%s'.", mapped_service_.c_str());
139  } else {
140  ROS_INFO("Serving to '%s' at '%s'.",
141  unmapped_service_.c_str(),
142  mapped_service_.c_str());
143  }
144 
147  this);
148  }
149 
151  {
152  if (logCalls()) {
153  ROS_INFO("Service '%s' called by '%s'",
154  mapped_service_.c_str(),
155  event.getCallerName().c_str());
156  }
157 
158  bool result;
160 
161  try {
162  if (callback_plain_) {
163  result = (obj_->*callback_plain_)(
164  const_cast<MReq&>(event.getRequest()), event.getResponse());
165  } else if (callback_with_name_) {
166  result = (obj_->*callback_with_name_)(
167  event.getCallerName(), event.getRequest(), event.getResponse());
168  } else {
169  result = (obj_->*callback_with_event_)(event);
170  }
171  } catch (...) {
172  result = false;
173  }
175 
176  processServing(event.getCallerName(), result, finish-start);
177  return result;
178  }
179 
180  public:
182  :
183  obj_(NULL),
184  callback_plain_(NULL),
185  callback_with_event_(NULL),
186  callback_with_name_(NULL)
187  {
188  }
189 
191  const std::string &service,
192  bool(T::*srv_func)(MReq &, MRes &),
193  T *obj)
194  {
195  obj_ = obj;
196  callback_plain_ = srv_func;
197  callback_with_event_ = NULL;
198  callback_with_name_ = NULL;
199  initialize(nh, service);
200  }
201 
203  const std::string &service,
204  bool(T::*srv_func)(ros::ServiceEvent<MReq, MRes> &),
205  T *obj)
206  {
207  obj_ = obj;
208  callback_plain_ = NULL;
209  callback_with_event_ = srv_func;
210  callback_with_name_ = NULL;
211  initialize(nh, service);
212  }
213 
215  const std::string &service,
216  bool(T::*srv_func)(const std::string &, const MReq &, MRes &),
217  T *obj)
218  {
219  obj_ = obj;
220  callback_plain_ = NULL;
221  callback_with_event_ = NULL;
222  callback_with_name_ = srv_func;
223  initialize(nh, service);
224  }
225 }; // class TypedServiceServerImpl
226 } // namespace swri
227 #endif // SWRI_ROSCPP_SERVICE_SERVER_IMPL_H_
228 
ServiceServerStatistics total_stats_
std::vector< std::string > clientNames() const
const std::string & getCallerName() const
ResponseType & getResponse() const
void setLogCalls(bool enable)
ROSCPP_DECL void start()
ROSCONSOLE_DECL void initialize()
std::string resolveName(const std::string &name, bool remap=true) const
void setInstrumentPerClient(bool enable)
TypedServiceServerImpl(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ServiceServer advertiseService(const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
ServiceServerStatistics clientStatistics(const std::string &name) const
ros::ServiceServer server_
void processServing(const std::string caller_name, bool success, const ros::WallDuration &runtime)
std::map< std::string, ServiceServerStatistics > client_stats_
void initialize(ros::NodeHandle &nh, const std::string &service)
const RequestType & getRequest() const
#define ROS_INFO(...)
TypedServiceServerImpl(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj)
const ServiceServerStatistics & totalStats() const
void merge(bool success, const ros::WallDuration &runtime)
TypedServiceServerImpl(ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const std::string &, const MReq &, MRes &), T *obj)
static WallTime now()
bool handleService(ros::ServiceEvent< MReq, MRes > &event)
const std::string & unmappedService() const
const std::string & mappedService() const


swri_roscpp
Author(s):
autogenerated on Tue Apr 6 2021 02:50:35