service_server.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_H_
30 #define SWRI_ROSCPP_SERVICE_SERVER_H_
31 
32 #include <ros/node_handle.h>
36 
37 namespace swri
38 {
40 {
41  private:
43 
44  public:
45  ServiceServer();
46 
47  template<class MReq, class MRes, class T>
49  const std::string &service,
50  bool(T::*srv_func)(MReq &, MRes &),
51  T *obj);
52 
53  template<class MReq, class MRes, class T>
55  const std::string &service,
56  bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &),
57  T *obj);
58 
59  template<class MReq, class MRes, class T>
61  const std::string &service,
62  bool(T::*srv_func)(const std::string &, const MReq &, MRes &),
63  T *obj);
64 
65  ServiceServer& operator=(const ServiceServer &other);
66 
67  // Reset all statistics, including message and timeout counts.
68  void resetStatistics();
69 
70  // Returns the unmapped service name that was provided when the
71  // service was created.
72  const std::string& unmappedService() const;
73  // Returns the fully mapped service name that the server is
74  // listening on.
75  const std::string& mappedService() const;
76 
77  // Retrieve the statitics for all service calls handled by the
78  // server.
79  const ServiceServerStatistics& statistics() const;
80 
81  // The service statistics can be broken down to individual clients
82  // if desired.
83  void setInstrumentPerClient(bool enable);
84  bool instrumentPerClient() const;
85  std::vector<std::string> clientNames() const;
86  ServiceServerStatistics clientStatistics(const std::string &name) const;
87 
88  // The service server can output a console log message when the
89  // service is called if desired.
90  void setLogCalls(bool enable);
91  bool logCalls() const;
92 
93  // These flags determine which values are added to a diagnostic
94  // status by the appendDiagnostics method.
96  DIAG_CONNECTION = 1 << 0, // Include service names
97  DIAG_SERVINGS = 1 << 1, // Servings counts/success rates
98  DIAG_TIMING = 1 << 2, // Include service time
99  DIAG_CLIENTS = 1 << 3, // Include client list, if applicable.
100 
101  DIAG_ALL = ~0, // Abbreviation to include all information
103  // Abbreviation to include everything except connection info.
104  };
105 
106  // This is a convenience method to add information about this
107  // server to a diagnostic status in a standard way.
108  //
109  // The status is merged with a warning if service calls have failed.
110  // The status is merged with an error if the most recent service
111  // call failed.
112  //
113  // The flags parameter determines which values are added to the
114  // status' key/value pairs. This should be a bitwise combination of
115  // the values defined in DIAGNOSTIC_FLAGS.
117  const std::string &name,
118  const int flags);
119 }; // class ServiceServer
120 
121 inline
123 {
124  // Setup an empty implementation so that we can assume impl_ is
125  // non-null and avoid a lot of unnecessary NULL checks.
126  impl_ = boost::make_shared<ServiceServerImpl>();
127 }
128 
129 template<class MReq, class MRes, class T>
130 inline
132  const std::string &service,
133  bool(T::*srv_func)(MReq &, MRes &),
134  T *obj)
135 {
138  nh, service, srv_func, obj));
139 }
140 
141 template<class MReq, class MRes, class T>
142 inline
144  const std::string &service,
145  bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &),
146  T *obj)
147 {
150  nh, service, srv_func, obj));
151 }
152 
153 template<class MReq, class MRes, class T>
154 inline
156  const std::string &service,
157  bool(T::*srv_func)(const std::string &, const MReq &, MRes &),
158  T *obj)
159 {
162  nh, service, srv_func, obj));
163 }
164 
165 inline
167 {
168  bool instrument_per_client = impl_->instrumentPerClient();
169  bool log_calls = impl_->logCalls();
170  impl_ = other.impl_;
171  impl_->setInstrumentPerClient(instrument_per_client);
172  impl_->setLogCalls(log_calls);
173  return *this;
174 }
175 
176 inline
178 {
179  impl_->resetStatistics();
180 }
181 
182 inline
183 const std::string& ServiceServer::unmappedService() const
184 {
185  return impl_->unmappedService();
186 }
187 
188 inline
189 const std::string& ServiceServer::mappedService() const
190 {
191  return impl_->mappedService();
192 }
193 
194 inline
196 {
197  return impl_->totalStats();
198 }
199 
200 inline
202 {
203  impl_->setInstrumentPerClient(enable);
204 }
205 
206 inline
208 {
209  return impl_->instrumentPerClient();
210 }
211 
212 inline
213 std::vector<std::string> ServiceServer::clientNames() const
214 {
215  return impl_->clientNames();
216 }
217 
218 inline
220  const std::string &name) const
221 {
222  return impl_->clientStatistics(name);
223 }
224 
225 inline
226 void ServiceServer::setLogCalls(bool enable)
227 {
228  impl_->setLogCalls(enable);
229 }
230 
231 inline
233 {
234  return impl_->logCalls();
235 }
236 
237 inline
240  const std::string &name,
241  const int flags)
242 {
243  const ServiceServerStatistics& stats = statistics();
244 
245  // Alias a type for easier access to DiagnosticStatus enumerations.
246  typedef diagnostic_msgs::DiagnosticStatus DS;
247 
248  if (stats.lastFailed()) {
249  status.mergeSummaryf(DS::ERROR, "Last %s service called failed", name.c_str());
250  } else if (stats.failed()) {
251  status.mergeSummaryf(DS::ERROR, "%s service calls have failed.", name.c_str());
252  }
253 
254  if (flags & DIAG_CONNECTION) {
255  if (mappedService() == unmappedService()) {
256  status.addf(name + "service name", "%s", mappedService().c_str());
257  } else {
258  status.addf(name + "service name", "%s -> %s",
259  unmappedService().c_str(),
260  mappedService().c_str());
261  }
262  }
263 
264  if (flags & DIAG_SERVINGS) {
265  status.addf(name + "service calls", "%d failed / %d calls",
266  stats.failed(), stats.servings());
267  }
268 
269  if (flags & DIAG_TIMING) {
270  status.addf(name + "service call time", "%.2f [s] (%.2f [s] - %.2f [s])",
271  stats.meanTime().toSec(),
272  stats.minTime().toSec(),
273  stats.maxTime().toSec());
274  }
275 
276  if (flags & DIAG_CLIENTS) {
277  std::vector<std::string> names = clientNames();
278 
279  for (size_t i = 0; i < names.size(); i++) {
280  ServiceServerStatistics client_stats = clientStatistics(names[i]);
281 
282  if (flags & DIAG_SERVINGS) {
283  status.addf(name + " calls from " + names[i], "%d failed / %d calls",
284  client_stats.failed(),
285  client_stats.servings());
286  }
287 
288  if (flags & DIAG_TIMING) {
289  status.addf(name + " calls from " + names[i] + " time", "%.2f [s] (%.2f [s] - %.2f [s])",
290  client_stats.meanTime().toSec(),
291  client_stats.minTime().toSec(),
292  client_stats.maxTime().toSec());
293  }
294  }
295  }
296 }
297 } // namespace swri
298 #endif // SWRI_ROSCPP_SERVICE_SERVER_H_
const ServiceServerStatistics & statistics() const
bool logCalls() const
void appendDiagnostics(diagnostic_updater::DiagnosticStatusWrapper &status, const std::string &name, const int flags)
ServiceServerStatistics clientStatistics(const std::string &name) const
bool instrumentPerClient() const
void setLogCalls(bool enable)
void addf(const std::string &key, const char *format,...)
ros::WallDuration minTime() const
std::vector< std::string > clientNames() const
ServiceServer & operator=(const ServiceServer &other)
void setInstrumentPerClient(bool enable)
const std::string & unmappedService() const
boost::shared_ptr< ServiceServerImpl > impl_
const std::string & mappedService() const
void mergeSummaryf(unsigned char lvl, const char *format,...)
ros::WallDuration maxTime() const
diagnostic_msgs::DiagnosticStatus DS
ros::WallDuration meanTime() const


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