ros2_control - rolling
async_function_handler.hpp
1 // Copyright 2024 PAL Robotics S.L.
2 //
3 // Licensed under the Apache License, Version 2.0 (the "License");
4 // you may not use this file except in compliance with the License.
5 // You may obtain a copy of the License at
6 //
7 // http://www.apache.org/licenses/LICENSE-2.0
8 //
9 // Unless required by applicable law or agreed to in writing, software
10 // distributed under the License is distributed on an "AS IS" BASIS,
11 // WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
12 // See the License for the specific language governing permissions and
13 // limitations under the License.
14 
16 
17 #ifndef REALTIME_TOOLS__ASYNC_FUNCTION_HANDLER_HPP_
18 #define REALTIME_TOOLS__ASYNC_FUNCTION_HANDLER_HPP_
19 
20 #include <atomic>
21 #include <condition_variable>
22 #include <functional>
23 #include <limits>
24 #include <memory>
25 #include <mutex>
26 #include <stdexcept>
27 #include <string>
28 #include <thread>
29 #include <utility>
30 #include <vector>
31 
32 #include "rclcpp/duration.hpp"
33 #include "rclcpp/logging.hpp"
34 #include "rclcpp/time.hpp"
35 #include "realtime_tools/thread_priority.hpp"
36 
37 namespace realtime_tools
38 {
44 template <typename T>
46 {
47 public:
48  AsyncFunctionHandler() = default;
49 
51 
53 
59  void init(
60  std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> callback,
61  int thread_priority = 50)
62  {
63  if (callback == nullptr) {
64  throw std::runtime_error(
65  "AsyncFunctionHandler: parsed function to call asynchronously is not valid!");
66  }
67  if (thread_.joinable()) {
68  throw std::runtime_error(
69  "AsyncFunctionHandler: Cannot reinitialize while the thread is "
70  "running. Please stop the async callback first!");
71  }
72  async_function_ = callback;
73  thread_priority_ = thread_priority;
74  }
75 
77 
90  void init(
91  std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> callback,
92  std::function<bool()> trigger_predicate, int thread_priority = 50)
93  {
94  if (trigger_predicate == nullptr) {
95  throw std::runtime_error("AsyncFunctionHandler: parsed trigger predicate is not valid!");
96  }
97  init(callback, thread_priority);
98  trigger_predicate_ = trigger_predicate;
99  }
100 
102 
117  std::pair<bool, T> trigger_async_callback(
118  const rclcpp::Time & time, const rclcpp::Duration & period)
119  {
120  if (!is_initialized()) {
121  throw std::runtime_error("AsyncFunctionHandler: need to be initialized first!");
122  }
123  if (!is_running()) {
124  throw std::runtime_error(
125  "AsyncFunctionHandler: need to start the async callback thread first before triggering!");
126  }
127  std::unique_lock<std::mutex> lock(async_mtx_, std::try_to_lock);
128  bool trigger_status = false;
129  if (lock.owns_lock() && !trigger_in_progress_ && trigger_predicate_()) {
130  {
131  std::unique_lock<std::mutex> scoped_lock(std::move(lock));
132  trigger_in_progress_ = true;
133  current_callback_time_ = time;
134  current_callback_period_ = period;
135  }
136  async_callback_condition_.notify_one();
137  trigger_status = true;
138  }
139  const T return_value = async_callback_return_;
140  return std::make_pair(trigger_status, return_value);
141  }
142 
144 
148  {
149  if (is_running()) {
150  std::unique_lock<std::mutex> lock(async_mtx_);
151  cycle_end_condition_.wait(lock, [this] { return !trigger_in_progress_; });
152  }
153  }
154 
156 
159  bool is_initialized() const { return async_function_ && trigger_predicate_; }
160 
162 
167  {
168  if (is_running()) {
169  thread_.join();
170  }
171  }
172 
174 
177  bool is_running() const { return thread_.joinable(); }
178 
180 
183  bool is_stopped() const { return stop_async_callback_; }
184 
186 
189  std::thread & get_thread() { return thread_; }
190 
192 
195  bool is_trigger_cycle_in_progress() const { return trigger_in_progress_; }
196 
198 
202  void stop_thread()
203  {
204  if (is_running()) {
205  {
206  std::unique_lock<std::mutex> lock(async_mtx_);
207  stop_async_callback_ = true;
208  }
209  async_callback_condition_.notify_one();
210  thread_.join();
211  }
212  }
213 
215 
218  double get_last_execution_time() const { return last_execution_time_; }
219 
221 
227  {
228  if (!is_initialized()) {
229  throw std::runtime_error("AsyncFunctionHandler: need to be initialized first!");
230  }
231  if (!thread_.joinable()) {
232  stop_async_callback_ = false;
233  trigger_in_progress_ = false;
234  last_execution_time_ = 0.0;
235  async_callback_return_ = T();
236  thread_ = std::thread([this]() -> void {
237  if (!realtime_tools::configure_sched_fifo(thread_priority_)) {
238  RCLCPP_WARN(
239  rclcpp::get_logger("AsyncFunctionHandler"),
240  "Could not enable FIFO RT scheduling policy. Consider setting up your user to do FIFO "
241  "RT "
242  "scheduling. See "
243  "[https://control.ros.org/master/doc/ros2_control/controller_manager/doc/userdoc.html] "
244  "for details.");
245  }
246 
247  while (!stop_async_callback_.load(std::memory_order_relaxed)) {
248  {
249  std::unique_lock<std::mutex> lock(async_mtx_);
250  async_callback_condition_.wait(
251  lock, [this] { return trigger_in_progress_ || stop_async_callback_; });
252  if (!stop_async_callback_) {
253  const auto start_time = std::chrono::steady_clock::now();
254  async_callback_return_ =
255  async_function_(current_callback_time_, current_callback_period_);
256  const auto end_time = std::chrono::steady_clock::now();
257  last_execution_time_ = std::chrono::duration<double>(end_time - start_time).count();
258  }
259  trigger_in_progress_ = false;
260  }
261  cycle_end_condition_.notify_all();
262  }
263  });
264  }
265  }
266 
267 private:
268  rclcpp::Time current_callback_time_;
269  rclcpp::Duration current_callback_period_{0, 0};
270 
271  std::function<T(const rclcpp::Time &, const rclcpp::Duration &)> async_function_;
272  std::function<bool()> trigger_predicate_ = []() { return true; };
273 
274  // Async related variables
275  std::thread thread_;
276  int thread_priority_ = std::numeric_limits<int>::quiet_NaN();
277  std::atomic_bool stop_async_callback_{false};
278  std::atomic_bool trigger_in_progress_{false};
279  std::atomic<T> async_callback_return_;
280  std::condition_variable async_callback_condition_;
281  std::condition_variable cycle_end_condition_;
282  std::mutex async_mtx_;
283  std::atomic<double> last_execution_time_;
284 };
285 } // namespace realtime_tools
286 
287 #endif // REALTIME_TOOLS__ASYNC_FUNCTION_HANDLER_HPP_
Class to handle asynchronous function calls. AsyncFunctionHandler is a class that allows the user to ...
Definition: async_function_handler.hpp:46
void wait_for_trigger_cycle_to_finish()
Waits until the current async callback method trigger cycle is finished.
Definition: async_function_handler.hpp:147
bool is_trigger_cycle_in_progress() const
Check if the async callback method is in progress.
Definition: async_function_handler.hpp:195
void start_thread()
Initializes and starts the callback thread.
Definition: async_function_handler.hpp:226
void init(std::function< T(const rclcpp::Time &, const rclcpp::Duration &)> callback, std::function< bool()> trigger_predicate, int thread_priority=50)
Initialize the AsyncFunctionHandler with the callback, trigger_predicate and thread_priority.
Definition: async_function_handler.hpp:90
bool is_running() const
Check if the async worker thread is running.
Definition: async_function_handler.hpp:177
void init(std::function< T(const rclcpp::Time &, const rclcpp::Duration &)> callback, int thread_priority=50)
Initialize the AsyncFunctionHandler with the callback and thread_priority.
Definition: async_function_handler.hpp:59
std::thread & get_thread()
Get the async worker thread.
Definition: async_function_handler.hpp:189
void stop_thread()
Stops the callback thread.
Definition: async_function_handler.hpp:202
double get_last_execution_time() const
Get the last execution time of the async callback method.
Definition: async_function_handler.hpp:218
void join_async_callback_thread()
Join the async callback thread.
Definition: async_function_handler.hpp:166
bool is_stopped() const
Check if the async callback is triggered to stop the cycle.
Definition: async_function_handler.hpp:183
bool is_initialized() const
Check if the AsyncFunctionHandler is initialized.
Definition: async_function_handler.hpp:159
std::pair< bool, T > trigger_async_callback(const rclcpp::Time &time, const rclcpp::Duration &period)
Triggers the async callback method cycle.
Definition: async_function_handler.hpp:117
Definition: async_function_handler.hpp:38
bool configure_sched_fifo(int priority)
Definition: thread_priority.cpp:48