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(
60 std::is_same_v<mutex_type, std::mutex> || std::is_same_v<mutex_type, std::recursive_mutex>);
61 static_assert(std::is_copy_constructible_v<T>, "Passed type must be copy constructible");
62
63public:
64 using mutex_t = mutex_type;
65 using type = T;
66 // Provide various constructors
67 constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {}
68 constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {}
69
70 // Only enabled for types that can be constructed from an initializer list
71 template <typename U = T>
72 constexpr RealtimeBoxBestEffort(
73 const std::initializer_list<U> & init,
74 std::enable_if_t<std::is_constructible_v<U, std::initializer_list<U>>>)
75 : value_(init)
76 {
77 }
78
84 template <typename U = T>
85 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, bool> trySet(const T & value)
86 {
87 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
88 if (!guard.try_lock()) {
89 return false;
90 }
91 value_ = value;
92 return true;
93 }
99 bool trySet(const std::function<void(T &)> & func)
100 {
101 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
102 if (!guard.try_lock()) {
103 return false;
104 }
105
106 func(value_);
107 return true;
108 }
113 template <typename U = T>
114 [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, std::optional<U>> tryGet() const
115 {
116 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
117 if (!guard.try_lock()) {
118 return std::nullopt;
119 }
120 return value_;
121 }
127 bool tryGet(const std::function<void(const T &)> & func)
128 {
129 std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
130 if (!guard.try_lock()) {
131 return false;
132 }
133
134 func(value_);
135 return true;
136 }
137
142 template <typename U = T>
143 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> set(const T & value)
144 {
145 std::lock_guard<mutex_t> guard(lock_);
146 // cppcheck-suppress missingReturn
147 value_ = value;
148 }
152 void set(const std::function<void(T &)> & func)
153 {
154 std::lock_guard<mutex_t> guard(lock_);
155 func(value_);
156 }
157
162 template <typename U = T>
163 [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, U> get() const
164 {
165 std::lock_guard<mutex_t> guard(lock_);
166 return value_;
167 }
172 template <typename U = T>
173 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> get(T & in) const
174 {
175 std::lock_guard<mutex_t> guard(lock_);
176 // cppcheck-suppress missingReturn
177 in = value_;
178 }
184 void get(const std::function<void(const T &)> & func)
185 {
186 std::lock_guard<mutex_t> guard(lock_);
187 func(value_);
188 }
189
194 template <typename U = T>
195 typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> operator=(const T & value)
196 {
197 set(value);
198 }
199
204 template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
205 [[nodiscard]] operator T() const
206 {
207 // Only makes sense with the getNonRT method otherwise we would return an std::optional
208 return get();
209 }
214 template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
215 [[nodiscard]] operator std::optional<T>() const
216 {
217 return tryGet();
218 }
219
220 // In case one wants to actually use a pointer
221 // in this implementation we allow accessing the lock directly.
222 // Note: Be careful with lock.unlock().
223 // It may only be called from the thread that locked the mutex!
224 [[nodiscard]] const mutex_t & getMutex() const { return lock_; }
225 [[nodiscard]] mutex_t & getMutex() { return lock_; }
226
227private:
228 T value_;
229 mutable mutex_t lock_;
230};
231} // namespace realtime_tools
232
233#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:85
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:163
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:184
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:173
bool tryGet(const std::function< void(const T &)> &func)
access the content (r) with best effort
Definition realtime_box_best_effort.hpp:127
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:114
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:152
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:195
bool trySet(const std::function< void(T &)> &func)
access the content readable with best effort
Definition realtime_box_best_effort.hpp:99
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:143
A pthread mutex wrapper that provides a mutex with the priority inheritance protocol and a priority c...
Definition async_function_handler.hpp:38