29 #ifndef SWRI_ROSCPP_SERVICE_SERVER_H_ 30 #define SWRI_ROSCPP_SERVICE_SERVER_H_ 47 template<
class MReq,
class MRes,
class T>
49 const std::string &service,
50 bool(T::*srv_func)(MReq &, MRes &),
53 template<
class MReq,
class MRes,
class T>
55 const std::string &service,
59 template<
class MReq,
class MRes,
class T>
61 const std::string &service,
62 bool(T::*srv_func)(
const std::string &,
const MReq &, MRes &),
117 const std::string &
name,
126 impl_ = boost::make_shared<ServiceServerImpl>();
129 template<
class MReq,
class MRes,
class T>
132 const std::string &service,
133 bool(T::*srv_func)(MReq &, MRes &),
138 nh, service, srv_func, obj));
141 template<
class MReq,
class MRes,
class T>
144 const std::string &service,
150 nh, service, srv_func, obj));
153 template<
class MReq,
class MRes,
class T>
156 const std::string &service,
157 bool(T::*srv_func)(
const std::string &,
const MReq &, MRes &),
162 nh, service, srv_func, obj));
168 bool instrument_per_client = impl_->instrumentPerClient();
169 bool log_calls = impl_->logCalls();
171 impl_->setInstrumentPerClient(instrument_per_client);
172 impl_->setLogCalls(log_calls);
179 impl_->resetStatistics();
185 return impl_->unmappedService();
191 return impl_->mappedService();
197 return impl_->totalStats();
203 impl_->setInstrumentPerClient(enable);
209 return impl_->instrumentPerClient();
215 return impl_->clientNames();
220 const std::string &
name)
const 222 return impl_->clientStatistics(name);
228 impl_->setLogCalls(enable);
234 return impl_->logCalls();
240 const std::string &
name,
246 typedef diagnostic_msgs::DiagnosticStatus
DS;
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());
258 status.
addf(name +
"service name",
"%s -> %s",
265 status.
addf(name +
"service calls",
"%d failed / %d calls",
270 status.
addf(name +
"service call time",
"%.2f [s] (%.2f [s] - %.2f [s])",
279 for (
size_t i = 0; i < names.size(); i++) {
282 if (flags & DIAG_SERVINGS) {
283 status.
addf(name +
" calls from " + names[i],
"%d failed / %d calls",
288 if (flags & DIAG_TIMING) {
289 status.
addf(name +
" calls from " + names[i] +
" time",
"%.2f [s] (%.2f [s] - %.2f [s])",
298 #endif // SWRI_ROSCPP_SERVICE_SERVER_H_
const ServiceServerStatistics & statistics() 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