managed_resource.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement (BSD License)
4  *
5  * Copyright (c) 2018, University of Luxembourg
6  * All rights reserved.
7  *
8  * Redistribution and use in source and binary forms, with or without
9  * modification, are permitted provided that the following conditions
10  * are met:
11  *
12  * * Redistributions of source code must retain the above copyright
13  * notice, this list of conditions and the following disclaimer.
14  * * Redistributions in binary form must reproduce the above
15  * copyright notice, this list of conditions and the following
16  * disclaimer in the documentation and/or other materials provided
17  * with the distribution.
18  * * Neither the name of University of Luxembourg nor the names of its
19  * contributors may be used to endorse or promote products derived
20  * from this software without specific prior written permission.
21  *
22  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
23  * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
24  * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
25  * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
26  * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
27  * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
28  * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
29  * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
30  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
31  * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
32  * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
33  * POSSIBILITY OF SUCH DAMAGE.
34  *
35  * Author: Maciej Zurad
36  *********************************************************************/
46 #ifndef ROBOT_ACTIVITY_RESOURCE_MANAGED_RESOURCE_H
47 #define ROBOT_ACTIVITY_RESOURCE_MANAGED_RESOURCE_H
48 
49 #include <atomic>
50 
51 #include <ros/ros.h>
52 #include <ros/console.h>
53 
54 namespace robot_activity
55 {
56 namespace resource
57 {
58 
59 class ManagedSubscriber;
61 
76 template <class Derived, class Resource>
77 class Managed
78 {
79 public:
84  Managed() = delete;
85 
89  ~Managed();
90 
106  template<typename... Args>
107  explicit Managed(Args&& ...args)
108  : acquired_(false), paused_(true), resource_(), lazy_acquirer_()
109  {
110  ROS_DEBUG("Managed::ctor");
111  lazy_acquirer_ = makeLazyAcquirer(std::forward<Args>(args)...);
112  }
113 
119  void acquire(const ros::NodeHandlePtr& node_handle);
120 
125  void release();
126 
132  void pause();
133 
138  void resume();
139 
140  typedef std::shared_ptr<Managed<Derived, Resource>> SharedPtr;
141 
142 protected:
143  typedef std::function<Resource(const ros::NodeHandlePtr&)> LazyAcquirer;
144 
153  template<typename... Args>
154  LazyAcquirer makeLazyAcquirer(Args&& ...args) const
155  {
156  return static_cast<const Derived*>(this)
157  ->makeLazyAcquirer(std::forward<Args>(args)...);
158  }
159 
163  std::atomic<bool> acquired_;
164 
168  std::atomic<bool> paused_;
169 
170 
174  Resource resource_;
175 
179  LazyAcquirer lazy_acquirer_;
180 };
181 
182 } // namespace resource
183 } // namespace robot_activity
184 
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&#39;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&#39;s not already acquired.
Resource resource_
The actual resource controlled by this class.
#define ROS_DEBUG(...)
std::atomic< bool > acquired_
Atomic flag specifing whether the resource is acquired or not.


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