46 #ifndef ROBOT_ACTIVITY_RESOURCE_MANAGED_RESOURCE_H 47 #define ROBOT_ACTIVITY_RESOURCE_MANAGED_RESOURCE_H 76 template <
class Derived,
class Resource>
106 template<
typename... Args>
140 typedef std::shared_ptr<Managed<Derived, Resource>>
SharedPtr;
143 typedef std::function<Resource(const ros::NodeHandlePtr&)>
LazyAcquirer;
153 template<
typename... Args>
156 return static_cast<const Derived*
>(
this)
185 #endif // ROBOT_ACTIVITY_RESOURCE_MANAGED_RESOURCE_H void resume()
Resumes the resource.
std::atomic< bool > paused_
Atomic flag specifing whether the resource is paused or not.
Implementation of Managed class for ros::ServiceServer.
Managed()=delete
Default empty constructor is deleted.
Managed(Args &&...args)
Variadic constructor.
LazyAcquirer lazy_acquirer_
Function that will acquire the resource upon calling with a node handle.
std::function< Resource(const ros::NodeHandlePtr &)> LazyAcquirer
LazyAcquirer makeLazyAcquirer(Args &&...args) const
Lazily acquires a resource.
Wrapper around ROS resources, such as ros::Subscriber and ros::ServiceServer.
void release()
Releases the resource if it's already acquired. shutdown() method in case of ros::Subscriber and ros:...
void pause()
Pauses the resource.
std::shared_ptr< Managed< Derived, Resource > > SharedPtr
Implementation of Managed class for ros::Subscriber.
void acquire(const ros::NodeHandlePtr &node_handle)
Acquires the resource if it's not already acquired.
Resource resource_
The actual resource controlled by this class.
std::atomic< bool > acquired_
Atomic flag specifing whether the resource is acquired or not.