Wrapper around ROS resources, such as ros::Subscriber and ros::ServiceServer. More...
#include <managed_resource.h>
Public Types | |
typedef std::shared_ptr < Managed< Derived, Resource > > | SharedPtr |
Public Member Functions | |
void | acquire (const ros::NodeHandlePtr &node_handle) |
Acquires the resource if it's not already acquired. | |
Managed () | |
Default empty constructor is deleted. | |
template<typename... Args> | |
Managed (Args &&...args) | |
Variadic constructor. | |
void | pause () |
Pauses the resource. | |
void | release () |
Releases the resource if it's already acquired. shutdown() method in case of ros::Subscriber and ros::ServiceServer. | |
void | resume () |
Resumes the resource. | |
~Managed () | |
Destructor. | |
Protected Types | |
typedef std::function < Resource(const ros::NodeHandlePtr &)> | LazyAcquirer |
Protected Member Functions | |
template<typename... Args> | |
LazyAcquirer | makeLazyAcquirer (Args &&...args) const |
Lazily acquires a resource. | |
Protected Attributes | |
std::atomic< bool > | acquired_ |
Atomic flag specifing whether the resource is acquired or not. | |
LazyAcquirer | lazy_acquirer_ |
Function that will acquire the resource upon calling with a node handle. | |
std::atomic< bool > | paused_ |
Atomic flag specifing whether the resource is paused or not. | |
Resource | resource_ |
The actual resource controlled by this class. |
Wrapper around ROS resources, such as ros::Subscriber and ros::ServiceServer.
This class adds additional functionality to ROS resources such as pausing, resuming and re-acquiring it. It also implements lazy acquisition of a resource due to the fact that the resource is not acquired upon instantiation, but when *acquire* is called. The class is the base wrapper class and has to be sub-classed by a specific resource. We use CRTP idiom, hence the templated class, in order to achieve static-time (compile-time) polymorphism.
Derived | CRTP derived class |
Resource | ROS resource, such as ros::Subscriber or ros::ServiceServer |
Definition at line 77 of file managed_resource.h.
typedef std::function<Resource(const ros::NodeHandlePtr&)> robot_activity::resource::Managed< Derived, Resource >::LazyAcquirer [protected] |
Definition at line 143 of file managed_resource.h.
typedef std::shared_ptr<Managed<Derived, Resource> > robot_activity::resource::Managed< Derived, Resource >::SharedPtr |
Definition at line 140 of file managed_resource.h.
robot_activity::resource::Managed< Derived, Resource >::Managed | ( | ) |
Default empty constructor is deleted.
Resource has to be fully described upon instantiation
robot_activity::resource::Managed< Specialization, Resource >::~Managed | ( | ) |
Destructor.
Definition at line 45 of file managed_resource.cpp.
robot_activity::resource::Managed< Derived, Resource >::Managed | ( | Args &&... | args | ) | [inline, explicit] |
Variadic constructor.
Main constructor, where args should fully specify the resource and correspond to one of the original function signatures from ROS resources (eg. ros::Subscriber). Args are forwarded to the makeLazyAcquirer function, which is bound at compile-time to the deriving class, which HAS to implement ALL function signatures available in ROS for creating that particular resource via a node handle.
Args | Types have to match ROS resource creation function signature (e.g node_handle.subscribe(...)) |
args | Specify the resource, e.g. topic, queue_size and a callback in the case of a ros::Subscriber |
Definition at line 107 of file managed_resource.h.
void robot_activity::resource::Managed< Specialization, Resource >::acquire | ( | const ros::NodeHandlePtr & | node_handle | ) |
Acquires the resource if it's not already acquired.
node_handle | NodeHandle is needed for acquisition, same as in ROS |
Definition at line 51 of file managed_resource.cpp.
LazyAcquirer robot_activity::resource::Managed< Derived, Resource >::makeLazyAcquirer | ( | Args &&... | args | ) | const [inline, protected] |
Lazily acquires a resource.
Creates a function such that, when called with a ROS node handle will acquire the specific resource
args | Specifies the resource |
Definition at line 154 of file managed_resource.h.
void robot_activity::resource::Managed< Specialization, Resource >::pause | ( | ) |
Pauses the resource.
Depending on the deriving concrete resource, it usually means that the callback is returned before actually executing
Definition at line 82 of file managed_resource.cpp.
void robot_activity::resource::Managed< Specialization, Resource >::release | ( | ) |
Releases the resource if it's already acquired. shutdown() method in case of ros::Subscriber and ros::ServiceServer.
Definition at line 66 of file managed_resource.cpp.
void robot_activity::resource::Managed< Specialization, Resource >::resume | ( | ) |
Resumes the resource.
Undoes the pause operation
Definition at line 89 of file managed_resource.cpp.
std::atomic<bool> robot_activity::resource::Managed< Derived, Resource >::acquired_ [protected] |
Atomic flag specifing whether the resource is acquired or not.
Definition at line 163 of file managed_resource.h.
LazyAcquirer robot_activity::resource::Managed< Derived, Resource >::lazy_acquirer_ [protected] |
Function that will acquire the resource upon calling with a node handle.
Definition at line 179 of file managed_resource.h.
std::atomic<bool> robot_activity::resource::Managed< Derived, Resource >::paused_ [protected] |
Atomic flag specifing whether the resource is paused or not.
Definition at line 168 of file managed_resource.h.
Resource robot_activity::resource::Managed< Derived, Resource >::resource_ [protected] |
The actual resource controlled by this class.
Definition at line 174 of file managed_resource.h.