Public Member Functions | Private Member Functions | Private Attributes | List of all members
swri::TypedServiceServerImpl< MReq, MRes, T > Class Template Reference

#include <service_server_impl.h>

Inheritance diagram for swri::TypedServiceServerImpl< MReq, MRes, T >:
Inheritance graph
[legend]

Public Member Functions

 TypedServiceServerImpl ()
 
 TypedServiceServerImpl (ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj)
 
 TypedServiceServerImpl (ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj)
 
 TypedServiceServerImpl (ros::NodeHandle &nh, const std::string &service, bool(T::*srv_func)(const std::string &, const MReq &, MRes &), T *obj)
 
- Public Member Functions inherited from swri::ServiceServerImpl
std::vector< std::string > clientNames () const
 
ServiceServerStatistics clientStatistics (const std::string &name) const
 
bool instrumentPerClient () const
 
bool logCalls () const
 
const std::string & mappedService () const
 
void resetStatistics ()
 
 ServiceServerImpl ()
 
void setInstrumentPerClient (bool enable)
 
void setLogCalls (bool enable)
 
const ServiceServerStatisticstotalStats () const
 
const std::string & unmappedService () const
 

Private Member Functions

bool handleService (ros::ServiceEvent< MReq, MRes > &event)
 
void initialize (ros::NodeHandle &nh, const std::string &service)
 

Private Attributes

bool(T::* callback_plain_ )(MReq &, MRes &)
 
bool(T::* callback_with_event_ )(ros::ServiceEvent< MReq, MRes > &)
 
bool(T::* callback_with_name_ )(const std::string &, const MReq &, MRes &)
 
T * obj_
 

Additional Inherited Members

- Protected Member Functions inherited from swri::ServiceServerImpl
void processServing (const std::string caller_name, bool success, const ros::WallDuration &runtime)
 
- Protected Attributes inherited from swri::ServiceServerImpl
std::map< std::string, ServiceServerStatisticsclient_stats_
 
bool instrument_per_client_
 
bool log_calls_
 
std::string mapped_service_
 
ros::ServiceServer server_
 
ServiceServerStatistics total_stats_
 
std::string unmapped_service_
 

Detailed Description

template<class MReq, class MRes, class T>
class swri::TypedServiceServerImpl< MReq, MRes, T >

Definition at line 124 of file service_server_impl.h.

Constructor & Destructor Documentation

template<class MReq , class MRes , class T >
swri::TypedServiceServerImpl< MReq, MRes, T >::TypedServiceServerImpl ( )
inline

Definition at line 181 of file service_server_impl.h.

template<class MReq , class MRes , class T >
swri::TypedServiceServerImpl< MReq, MRes, T >::TypedServiceServerImpl ( ros::NodeHandle nh,
const std::string &  service,
bool(T::*)(MReq &, MRes &)  srv_func,
T *  obj 
)
inline

Definition at line 190 of file service_server_impl.h.

template<class MReq , class MRes , class T >
swri::TypedServiceServerImpl< MReq, MRes, T >::TypedServiceServerImpl ( ros::NodeHandle nh,
const std::string &  service,
bool(T::*)(ros::ServiceEvent< MReq, MRes > &)  srv_func,
T *  obj 
)
inline

Definition at line 202 of file service_server_impl.h.

template<class MReq , class MRes , class T >
swri::TypedServiceServerImpl< MReq, MRes, T >::TypedServiceServerImpl ( ros::NodeHandle nh,
const std::string &  service,
bool(T::*)(const std::string &, const MReq &, MRes &)  srv_func,
T *  obj 
)
inline

Definition at line 214 of file service_server_impl.h.

Member Function Documentation

template<class MReq , class MRes , class T >
bool swri::TypedServiceServerImpl< MReq, MRes, T >::handleService ( ros::ServiceEvent< MReq, MRes > &  event)
inlineprivate

Definition at line 150 of file service_server_impl.h.

template<class MReq , class MRes , class T >
void swri::TypedServiceServerImpl< MReq, MRes, T >::initialize ( ros::NodeHandle nh,
const std::string &  service 
)
inlineprivate

Definition at line 131 of file service_server_impl.h.

Member Data Documentation

template<class MReq , class MRes , class T >
bool(T::* swri::TypedServiceServerImpl< MReq, MRes, T >::callback_plain_) (MReq &, MRes &)
private

Definition at line 127 of file service_server_impl.h.

template<class MReq , class MRes , class T >
bool(T::* swri::TypedServiceServerImpl< MReq, MRes, T >::callback_with_event_) (ros::ServiceEvent< MReq, MRes > &)
private

Definition at line 128 of file service_server_impl.h.

template<class MReq , class MRes , class T >
bool(T::* swri::TypedServiceServerImpl< MReq, MRes, T >::callback_with_name_) (const std::string &, const MReq &, MRes &)
private

Definition at line 129 of file service_server_impl.h.

template<class MReq , class MRes , class T >
T* swri::TypedServiceServerImpl< MReq, MRes, T >::obj_
private

Definition at line 126 of file service_server_impl.h.


The documentation for this class was generated from the following file:


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