ros2_control - humble
Loading...
Searching...
No Matches
realtime_box_best_effort.hpp
1// Copyright (c) 2024, Lennart Nachtigall
2//
3// Redistribution and use in source and binary forms, with or without
4// modification, are permitted provided that the following conditions are met:
5//
6// * Redistributions of source code must retain the above copyright
7// notice, this list of conditions and the following disclaimer.
8//
9// * Redistributions in binary form must reproduce the above copyright
10// notice, this list of conditions and the following disclaimer in the
11// documentation and/or other materials provided with the distribution.
12//
13// * Neither the name of the Willow Garage, Inc. nor the names of its
14// contributors may be used to endorse or promote products derived from
15// this software without specific prior written permission.
16//
17// THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18// AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19// IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20// ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE
21// LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22// CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23// SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24// INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25// CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26// ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27// POSSIBILITY OF SUCH DAMAGE.
28
29// Author: Lennart Nachtigall
30
31#ifndef REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_HPP_
32#define REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_HPP_
33
34#include <functional>
35#include <initializer_list>
36#include <mutex>
37#include <optional>
38#include <utility>
39
40#include <rcpputils/pointer_traits.hpp>
41
42namespace realtime_tools
43{
44
45template <typename T>
46constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer<T>::value;
47
56template <class T, typename mutex_type = std::mutex>
58{
59 static_assert(std::is_copy_constructible_v<T>, "Passed type must be copy constructible");
60
61public:
62 using mutex_t = mutex_type;
63 using type = T;
64 // Provide various constructors
65 constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {}
66 constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {}
67
68 // Only enabled for types that can be constructed from an initializer list
69 template <typename U = T>
70 constexpr RealtimeBoxBestEffort(
71 const std::initializer_list<U> & init,
72 std::enable_if_t<std::is_constructible_v<U, std::initializer_list<U>>>)
73 : value_(init)
74 {
75 }
76
82 template <typename U = T>
83 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, bool> trySet(const T & value)
84 {
85 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
86 if (!guard.try_lock()) {
87 return false;
88 }
89 value_ = value;
90 return true;
91 }
97 bool trySet(const std::function<void(T &)> & func)
98 {
99 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
100 if (!guard.try_lock()) {
101 return false;
102 }
103
104 func(value_);
105 return true;
106 }
111 template <typename U = T>
112 [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, std::optional<U>> tryGet() const
113 {
114 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
115 if (!guard.try_lock()) {
116 return std::nullopt;
117 }
118 return value_;
119 }
125 bool tryGet(const std::function<void(const T &)> & func)
126 {
127 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
128 if (!guard.try_lock()) {
129 return false;
130 }
131
132 func(value_);
133 return true;
134 }
135
140 template <typename U = T>
141 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> set(const T & value)
142 {
143 std::lock_guard<mutex_t> guard(lock_);
144 // cppcheck-suppress missingReturn
145 value_ = value;
146 }
150 void set(const std::function<void(T &)> & func)
151 {
152 std::lock_guard<mutex_t> guard(lock_);
153 func(value_);
154 }
155
160 template <typename U = T>
161 [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, U> get() const
162 {
163 std::lock_guard<mutex_t> guard(lock_);
164 return value_;
165 }
170 template <typename U = T>
171 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> get(T & in) const
172 {
173 std::lock_guard<mutex_t> guard(lock_);
174 // cppcheck-suppress missingReturn
175 in = value_;
176 }
182 void get(const std::function<void(const T &)> & func)
183 {
184 std::lock_guard<mutex_t> guard(lock_);
185 func(value_);
186 }
187
192 template <typename U = T>
193 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> operator=(const T & value)
194 {
195 set(value);
196 }
197
202 template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
203 [[nodiscard]] operator T() const
204 {
205 // Only makes sense with the getNonRT method otherwise we would return an std::optional
206 return get();
207 }
212 template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
213 [[nodiscard]] operator std::optional<T>() const
214 {
215 return tryGet();
216 }
217
218 // In case one wants to actually use a pointer
219 // in this implementation we allow accessing the lock directly.
220 // Note: Be careful with lock.unlock().
221 // It may only be called from the thread that locked the mutex!
222 [[nodiscard]] const mutex_t & getMutex() const { return lock_; }
223 [[nodiscard]] mutex_t & getMutex() { return lock_; }
224
225private:
226 T value_;
227 mutable mutex_t lock_;
228};
229} // namespace realtime_tools
230
231#endif // REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_HPP_
Definition realtime_box_best_effort.hpp:58
std::enable_if_t<!is_ptr_or_smart_ptr< U >, bool > trySet(const T &value)
set a new content with best effort
Definition realtime_box_best_effort.hpp:83
std::enable_if_t<!is_ptr_or_smart_ptr< U >, U > get() const
get the content and wait until the mutex could be locked (RealtimeBox behaviour)
Definition realtime_box_best_effort.hpp:161
void get(const std::function< void(const T &)> &func)
access the content (r) and wait until the mutex could be locked
Definition realtime_box_best_effort.hpp:182
std::enable_if_t<!is_ptr_or_smart_ptr< U >, void > get(T &in) const
get the content and wait until the mutex could be locked
Definition realtime_box_best_effort.hpp:171
bool tryGet(const std::function< void(const T &)> &func)
access the content (r) with best effort
Definition realtime_box_best_effort.hpp:125
std::enable_if_t<!is_ptr_or_smart_ptr< U >, std::optional< U > > tryGet() const
get the content with best effort
Definition realtime_box_best_effort.hpp:112
void set(const std::function< void(T &)> &func)
access the content (rw) and wait until the mutex could locked
Definition realtime_box_best_effort.hpp:150
std::enable_if_t<!is_ptr_or_smart_ptr< U >, void > operator=(const T &value)
provide a custom assignment operator for easier usage
Definition realtime_box_best_effort.hpp:193
bool trySet(const std::function< void(T &)> &func)
access the content readable with best effort
Definition realtime_box_best_effort.hpp:97
std::enable_if_t<!is_ptr_or_smart_ptr< U >, void > set(const T &value)
set the content and wait until the mutex could be locked (RealtimeBox behavior)
Definition realtime_box_best_effort.hpp:141
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38