Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017
00018
00019
00020
00021
00022
00023
00024
00025
00026
00027
00028
00029
00030
00031
00032
00033
00034
00035
00036
00037 #include <robot_activity/resource/managed_resource.h>
00038
00039 namespace robot_activity
00040 {
00041 namespace resource
00042 {
00043
00044 template<class Specialization, class Resource>
00045 Managed<Specialization, Resource>::~Managed()
00046 {
00047 ROS_DEBUG("Managed::dtor");
00048 }
00049
00050 template<class Specialization, class Resource>
00051 void Managed<Specialization, Resource>::acquire(const ros::NodeHandlePtr& node_handle)
00052 {
00053 ROS_DEBUG("Managed::acquire executed!");
00054 if (acquired_)
00055 {
00056 ROS_DEBUG("Already acquired!");
00057 return;
00058 }
00059
00060 ROS_DEBUG("Subscribing...");
00061 resource_ = lazy_acquirer_(node_handle);
00062 acquired_ = true;
00063 }
00064
00065 template<class Specialization, class Resource>
00066 void Managed<Specialization, Resource>::release()
00067 {
00068 ROS_DEBUG("Managed::release executed!");
00069 if (acquired_)
00070 {
00071 ROS_DEBUG("Releasing...");
00072 resource_.shutdown();
00073 acquired_ = false;
00074 }
00075 else
00076 {
00077 ROS_DEBUG("Cannot release ");
00078 }
00079 }
00080
00081 template<class Specialization, class Resource>
00082 void Managed<Specialization, Resource>::pause()
00083 {
00084 ROS_DEBUG("Managed::pause executed!");
00085 paused_ = true;
00086 }
00087
00088 template<class Specialization, class Resource>
00089 void Managed<Specialization, Resource>::resume()
00090 {
00091 ROS_DEBUG("Managed::resume executed!");
00092 paused_ = false;
00093 }
00094
00095 template class Managed<ManagedSubscriber, ros::Subscriber>;
00096 template class Managed<ManagedServiceServer, ros::ServiceServer>;
00097
00098 }
00099 }