ros2_control - humble
realtime_box_best_effort.h
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_H_
32 #define REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_
33 
34 #include <initializer_list>
35 #include <mutex>
36 #include <optional>
37 #include <utility>
38 
39 #include <rcpputils/pointer_traits.hpp>
40 
41 namespace realtime_tools
42 {
43 
44 template <typename T>
45 constexpr auto is_ptr_or_smart_ptr = rcpputils::is_pointer<T>::value;
46 
55 template <class T, typename mutex_type = std::mutex>
57 {
58  static_assert(
59  std::is_same_v<mutex_type, std::mutex> || std::is_same_v<mutex_type, std::recursive_mutex>);
60  static_assert(std::is_copy_constructible_v<T>, "Passed type must be copy constructible");
61 
62 public:
63  using mutex_t = mutex_type;
64  using type = T;
65  // Provide various constructors
66  constexpr explicit RealtimeBoxBestEffort(const T & init = T{}) : value_(init) {}
67  constexpr explicit RealtimeBoxBestEffort(const T && init) : value_(std::move(init)) {}
68 
69  // Only enabled for types that can be constructed from an initializer list
70  template <typename U = T>
71  constexpr RealtimeBoxBestEffort(
72  const std::initializer_list<U> & init,
73  std::enable_if_t<std::is_constructible_v<U, std::initializer_list>>)
74  : value_(init)
75  {
76  }
77 
83  template <typename U = T>
84  typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, bool> trySet(const T & value)
85  {
86  std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
87  if (!guard.try_lock()) {
88  return false;
89  }
90  value_ = value;
91  return true;
92  }
98  bool trySet(const std::function<void(T &)> & func)
99  {
100  std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
101  if (!guard.try_lock()) {
102  return false;
103  }
104 
105  func(value_);
106  return true;
107  }
112  template <typename U = T>
113  [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, std::optional<U>> tryGet() const
114  {
115  std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
116  if (!guard.try_lock()) {
117  return std::nullopt;
118  }
119  return value_;
120  }
126  bool tryGet(const std::function<void(const T &)> & func)
127  {
128  std::unique_lock<mutex_t> guard(lock_, std::defer_lock);
129  if (!guard.try_lock()) {
130  return false;
131  }
132 
133  func(value_);
134  return true;
135  }
136 
141  template <typename U = T>
142  typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> set(const T & value)
143  {
144  std::lock_guard<mutex_t> guard(lock_);
145  // cppcheck-suppress missingReturn
146  value_ = value;
147  }
151  void set(const std::function<void(T &)> & func)
152  {
153  std::lock_guard<mutex_t> guard(lock_);
154  func(value_);
155  }
156 
161  template <typename U = T>
162  [[nodiscard]] typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, U> get() const
163  {
164  std::lock_guard<mutex_t> guard(lock_);
165  return value_;
166  }
171  template <typename U = T>
172  typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> get(T & in) const
173  {
174  std::lock_guard<mutex_t> guard(lock_);
175  // cppcheck-suppress missingReturn
176  in = value_;
177  }
183  void get(const std::function<void(const T &)> & func)
184  {
185  std::lock_guard<mutex_t> guard(lock_);
186  func(value_);
187  }
188 
193  template <typename U = T>
194  typename std::enable_if_t<!is_ptr_or_smart_ptr<U>, void> operator=(const T & value)
195  {
196  set(value);
197  }
198 
203  template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
204  [[nodiscard]] operator T() const
205  {
206  // Only makes sense with the getNonRT method otherwise we would return an std::optional
207  return get();
208  }
213  template <typename U = T, typename = typename std::enable_if_t<!is_ptr_or_smart_ptr<U>>>
214  [[nodiscard]] operator std::optional<T>() const
215  {
216  return tryGet();
217  }
218 
219  // In case one wants to actually use a pointer
220  // in this implementation we allow accessing the lock directly.
221  // Note: Be careful with lock.unlock().
222  // It may only be called from the thread that locked the mutex!
223  [[nodiscard]] const mutex_t & getMutex() const { return lock_; }
224  [[nodiscard]] mutex_t & getMutex() { return lock_; }
225 
226 private:
227  T value_;
228  mutable mutex_t lock_;
229 };
230 } // namespace realtime_tools
231 
232 #endif // REALTIME_TOOLS__REALTIME_BOX_BEST_EFFORT_H_
Definition: realtime_box_best_effort.h:57
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.h:172
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.h:183
bool tryGet(const std::function< void(const T &)> &func)
access the content (r) with best effort
Definition: realtime_box_best_effort.h:126
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.h:162
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.h:113
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.h:142
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.h:84
void set(const std::function< void(T &)> &func)
access the content (rw) and wait until the mutex could locked
Definition: realtime_box_best_effort.h:151
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.h:194
bool trySet(const std::function< void(T &)> &func)
access the content readable with best effort
Definition: realtime_box_best_effort.h:98
Definition: async_function_handler.hpp:38