Public Types | Public Member Functions | Private Member Functions | List of all members
robot_activity::resource::ManagedServiceServer Class Reference

Implementation of Managed class for ros::ServiceServer. More...

#include <managed_serviceserver.h>

Inheritance diagram for robot_activity::resource::ManagedServiceServer:
Inheritance graph
[legend]

Public Types

template<typename... Args>
using ServiceCallback = boost::function< bool(Args...)>
 Typedef for ROS service callbacks. More...
 
- Public Types inherited from robot_activity::resource::Managed< ManagedServiceServer, ros::ServiceServer >
typedef std::shared_ptr< Managed< ManagedServiceServer, ros::ServiceServer > > SharedPtr
 

Public Member Functions

void advertiseService (const ros::NodeHandlePtr &node_handle)
 Advertises the ROS service given a node handle. More...
 
template<class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, const ServiceCallback< MReq &, MRes & > &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr()) const
 Creates a function that advertises a ROS service when called. More...
 
template<class ServiceEvent >
LazyAcquirer makeLazyAcquirer (const std::string &service, const ServiceCallback< ServiceEvent & > &callback, const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr()) const
 Creates a function that advertises a ROS service when called. More...
 
template<class T , class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), T *obj) const
 Creates a function that advertises a ROS service when called. More...
 
template<class T , class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), T *obj) const
 Creates a function that advertises a ROS service when called. More...
 
template<class T , class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(T::*srv_func)(MReq &, MRes &), const boost::shared_ptr< T > &obj) const
 Creates a function that advertises a ROS service when called. More...
 
template<class T , class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(T::*srv_func)(ros::ServiceEvent< MReq, MRes > &), const boost::shared_ptr< T > &obj) const
 Creates a function that advertises a ROS service when called. More...
 
template<class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(*srv_func)(MReq &, MRes &)) const
 Creates a function that advertises a ROS service when called. More...
 
template<class MReq , class MRes >
LazyAcquirer makeLazyAcquirer (const std::string &service, bool(*srv_func)(ros::ServiceEvent< MReq, MRes > &)) const
 Creates a function that advertises a ROS service when called. More...
 
void shutdown ()
 Shutdowns the ROS service. More...
 
- Public Member Functions inherited from robot_activity::resource::Managed< ManagedServiceServer, ros::ServiceServer >
void acquire (const ros::NodeHandlePtr &node_handle)
 Acquires the resource if it's not already acquired. More...
 
 Managed ()=delete
 Default empty constructor is deleted. More...
 
 Managed (Args &&...args)
 Variadic constructor. More...
 
void pause ()
 Pauses the resource. More...
 
void release ()
 Releases the resource if it's already acquired. shutdown() method in case of ros::Subscriber and ros::ServiceServer. More...
 
void resume ()
 Resumes the resource. More...
 
 ~Managed ()
 Destructor. More...
 

Private Member Functions

template<typename... Args>
ServiceCallback< Args... > wrapServiceCallback (const ServiceCallback< Args... > &callback) const
 Wraps the service callback. More...
 

Additional Inherited Members

- Protected Types inherited from robot_activity::resource::Managed< ManagedServiceServer, ros::ServiceServer >
typedef std::function< ros::ServiceServer(const ros::NodeHandlePtr &)> LazyAcquirer
 
- Protected Member Functions inherited from robot_activity::resource::Managed< ManagedServiceServer, ros::ServiceServer >
LazyAcquirer makeLazyAcquirer (Args &&...args) const
 Lazily acquires a resource. More...
 
- Protected Attributes inherited from robot_activity::resource::Managed< ManagedServiceServer, ros::ServiceServer >
std::atomic< bool > acquired_
 Atomic flag specifing whether the resource is acquired or not. More...
 
LazyAcquirer lazy_acquirer_
 Function that will acquire the resource upon calling with a node handle. More...
 
std::atomic< bool > paused_
 Atomic flag specifing whether the resource is paused or not. More...
 
ros::ServiceServer resource_
 The actual resource controlled by this class. More...
 

Detailed Description

Implementation of Managed class for ros::ServiceServer.

Adds additional functionality to ros::ServiceServer resource by wrapping it. The service server can be shutdowned, advertised and paused. Shutting down has the same effect as in ROS, while advertising does not require any arguments, since they are passed in the inherited constructor. Pausing the service, will cause the callback to return false immediately.

Definition at line 71 of file managed_serviceserver.h.

Member Typedef Documentation

template<typename... Args>
using robot_activity::resource::ManagedServiceServer::ServiceCallback = boost::function<bool(Args...)>

Typedef for ROS service callbacks.

Template Parameters
Callbackarguments

Definition at line 124 of file managed_serviceserver.h.

Member Function Documentation

void robot_activity::resource::ManagedServiceServer::advertiseService ( const ros::NodeHandlePtr node_handle)
inline

Advertises the ROS service given a node handle.

Since the ROS service is fully desribed upon instantiation, advertising only requires a node handle. The function is idempotent and can be called multiple times without any side-effect. The service can also be re-advertised after being shutdowned without respecifying arguments describing the service.

Parameters
node_handleNode handle required for the actual call to ros::NodeHandle::advertiseService embedded inside

Definition at line 102 of file managed_serviceserver.h.

template<class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
const ServiceCallback< MReq &, MRes & > &  callback,
const ros::VoidConstPtr tracked_object = ros::VoidConstPtr() 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
callbackService callback specified as boost::function accepting two arguments
tracked_objectObject to be tracked, whose destruction will terminate the service
Template Parameters
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 142 of file managed_serviceserver.h.

template<class ServiceEvent >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
const ServiceCallback< ServiceEvent & > &  callback,
const ros::VoidConstPtr tracked_object = ros::VoidConstPtr() 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
callbackService callback specified as boost::function accepting one argument
tracked_objectObject to be tracked, whose destruction will terminate the service
Template Parameters
ServiceEventService callback's event message type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 173 of file managed_serviceserver.h.

template<class T , class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(T::*)(MReq &, MRes &)  srv_func,
T *  obj 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a member function of class T, which accepts two arguments: message request and response and returns a bool
objObject to be used when calling the pointed function
Template Parameters
TClass, where the member function is defined
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 206 of file managed_serviceserver.h.

template<class T , class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(T::*)(ros::ServiceEvent< MReq, MRes > &)  srv_func,
T *  obj 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a member function of class T, which accepts one argument: service event and returns a bool
objRaw pointer to the object to be used when calling the pointed function
Template Parameters
TClass, where the member function is defined
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 233 of file managed_serviceserver.h.

template<class T , class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(T::*)(MReq &, MRes &)  srv_func,
const boost::shared_ptr< T > &  obj 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a member function of class T, which accepts two arguments: message request and response and returns a bool
objboost::shared_ptr to the object to be used when calling the pointed function, it will also be treated as the tracked object, whose destruction will trigger a service shutdown
Template Parameters
TClass, where the the member function is defined
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 263 of file managed_serviceserver.h.

template<class T , class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(T::*)(ros::ServiceEvent< MReq, MRes > &)  srv_func,
const boost::shared_ptr< T > &  obj 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a member function of class T, which accepts one argument: a service event and returns a bool
objboost::shared_ptr to the object to be used when calling the pointed function, it will also be treated as the tracked object, whose destruction will trigger a service shutdown
Template Parameters
TClass, where the the member function is defined
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 292 of file managed_serviceserver.h.

template<class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(*)(MReq &, MRes &)  srv_func 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a function, which accepts two arguments: message request and response and returns a bool
Template Parameters
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 318 of file managed_serviceserver.h.

template<class MReq , class MRes >
LazyAcquirer robot_activity::resource::ManagedServiceServer::makeLazyAcquirer ( const std::string &  service,
bool(*)(ros::ServiceEvent< MReq, MRes > &)  srv_func 
) const
inline

Creates a function that advertises a ROS service when called.

Returns a lambda, which given a node handle will advertise the ROS service. This lambda is called during advertiseService call and the result is assigned as the managed resource, which in this case is ros::ServiceServer

Parameters
serviceName of the service to be advertised
srv_funcPointer to a function, which accepts one argument: service event and returns a bool
Template Parameters
MReqService callback's message request type
MResService callback's message response type
Returns
Lambda, which return a ros::ServiceServer

Definition at line 341 of file managed_serviceserver.h.

void robot_activity::resource::ManagedServiceServer::shutdown ( )
inline

Shutdowns the ROS service.

Has the same effect as ros::ServiceServer::shutdown function if the service was advertised, otherwise does not have any effect

Definition at line 113 of file managed_serviceserver.h.

template<typename... Args>
ServiceCallback<Args...> robot_activity::resource::ManagedServiceServer::wrapServiceCallback ( const ServiceCallback< Args... > &  callback) const
inlineprivate

Wraps the service callback.

Allows for pausing/resuming the servce by adding a check at run-time. If paused, the service will return false immediately.

Parameters
callback[description]
Returns
[description]

Definition at line 386 of file managed_serviceserver.h.


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


robot_activity
Author(s): Maciej ZURAD
autogenerated on Thu Jun 6 2019 19:32:17