mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
timer_handler.h
1#ifndef MRS_TIMER_H
2#define MRS_TIMER_H
3
4#include <rclcpp/rclcpp.hpp>
5#include <mutex>
6
7#include <mrs_lib/coro/runners.hpp>
8#include <mrs_lib/coro/task.hpp>
9#include <mrs_lib/internal/coroutine_callback_helpers.hpp>
10#include <mrs_lib/utils.h>
11
12namespace mrs_lib
13{
14
16 {
17 TimerHandlerOptions(const rclcpp::Node::SharedPtr node) : node(node)
18 {
19 }
20
21 TimerHandlerOptions() = default;
22
23 rclcpp::Node::SharedPtr node;
24
25 bool oneshot = false;
26
27 bool autostart = true;
28
29 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
30 };
31
42 {
43 public:
44 using callback_t = std::function<void()>;
45
49 virtual void stop() = 0;
50
54 virtual void start() = 0;
55
62 virtual void setPeriod(const rclcpp::Duration& duration) = 0;
63
71 virtual void setCallback(const std::function<void()>& callback) = 0;
72
78 virtual bool running() = 0;
79
80 virtual ~MRSTimer() = default;
81 MRSTimer(const MRSTimer&) = default;
82 MRSTimer(MRSTimer&&) = default;
83 MRSTimer& operator=(const MRSTimer&) = default;
84 MRSTimer& operator=(MRSTimer&&) = default;
85
86 protected:
87 MRSTimer() = default;
88
97 template <typename C>
98 static std::function<void()> createNonReentrantCallback(Task<> (C::*method)(), C* instance)
99 {
100 auto is_running = std::make_shared<std::atomic<bool>>(false);
101 return [is_running, method, instance]() -> void {
102 bool was_running = is_running->exchange(true);
103
104 if (!was_running)
105 {
106 // The callback was not running and we have set it as running, we start it here.
107 internal::start_task(
108 // Capturing lambdas should not be used as coroutines.
109 // Pass the values as arguments instead.
110 [](std::shared_ptr<std::atomic<bool>> is_running, Task<> (C::*method)(), C* instance) -> mrs_lib::Task<> {
111 // Run the user specified callback.
112 co_await std::invoke(method, instance);
113 // The task finished so we store false to allow another callback to start.
114 is_running->store(false);
115 co_return;
116 },
117 is_running, method, instance);
118 }
119 };
120 }
121
122 rclcpp::Node::SharedPtr node_;
123 };
124
125 // | ------------------------ ROSTimer ------------------------ |
126
127 /* class ROSTimer //{ */
128
132 class ROSTimer : public MRSTimer
133 {
134 public:
135 ROSTimer();
136
137 ROSTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
138
139 ROSTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
140
150 template <typename C>
151 ROSTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, Task<> (C::*method)(), C* instance)
152 : ROSTimer(opts, rate, createNonReentrantCallback(method, instance))
153 {
154 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(nullptr));
155 }
156
166 template <typename C>
167 ROSTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, Task<> (C::*method)(), std::shared_ptr<C> instance)
168 : ROSTimer(opts, rate, createNonReentrantCallback(method, instance))
169 {
170 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(nullptr));
171 }
172
176 virtual void stop() override;
177
181 virtual void start() override;
182
189 virtual void setPeriod(const rclcpp::Duration& duration) override;
190
198 virtual void setCallback(const std::function<void()>& callback) override;
199
205 virtual bool running() override;
206
207 virtual ~ROSTimer() override
208 {
209 stop();
210 };
211
212 // to keep rule of five since we have a custom destructor
213 ROSTimer(const ROSTimer&) = delete;
214 ROSTimer(ROSTimer&&) = delete;
215 ROSTimer& operator=(const ROSTimer&) = delete;
216 ROSTimer& operator=(ROSTimer&&) = delete;
217
218 private:
219 std::mutex mutex_timer_;
220
221 std::function<void()> callback;
222
223 bool oneshot;
224
225 rclcpp::TimerBase::SharedPtr timer_;
226
227 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
228 };
229
230 //}
231
232 // | ----------------------- ThreadTimer ---------------------- |
233
234 /* class ThreadTimer //{ */
235
239 class ThreadTimer : public MRSTimer
240 {
241
242 public:
243 ThreadTimer();
244
245 ThreadTimer(const rclcpp::Node::SharedPtr& node, const rclcpp::Rate& rate, const std::function<void()>& callback);
246
247 ThreadTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, const std::function<void()>& callback);
248
258 template <typename C>
259 ThreadTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, Task<> (C::*method)(), C* instance)
260 : ThreadTimer(opts, rate, createNonReentrantCallback(method, instance))
261 {
262 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(nullptr));
263 }
264
274 template <typename C>
275 ThreadTimer(const mrs_lib::TimerHandlerOptions& opts, const rclcpp::Rate& rate, Task<> (C::*method)(), std::shared_ptr<C> instance)
276 : ThreadTimer(opts, rate, createNonReentrantCallback(method, instance))
277 {
278 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(nullptr));
279 }
280
286 virtual void stop() override;
287
295 virtual void start() override;
296
304 virtual void setPeriod(const rclcpp::Duration& duration) override;
305
313 virtual void setCallback(const std::function<void()>& callback) override;
314
320 virtual bool running() override;
321
327 virtual ~ThreadTimer() override
328 {
329 stop();
330 };
331 // to keep rule of five since we have a custom destructor
332 ThreadTimer(const ThreadTimer&) = delete;
333 ThreadTimer(ThreadTimer&&) = delete;
334 ThreadTimer& operator=(const ThreadTimer&) = delete;
335 ThreadTimer& operator=(ThreadTimer&&) = delete;
336
337 private:
338 class Impl;
339
340 std::unique_ptr<Impl> impl_;
341
342 }; // namespace mrs_lib
343
344 //}
345
346} // namespace mrs_lib
347
348#ifndef MRS_TIMER_HPP
349#include <mrs_lib/impl/timer_handler.hpp>
350#endif
351
352#endif // MRS_TIMER_H
Common wrapper representing the functionality of the rclcpp::Timer.
Definition timer_handler.h:42
static std::function< void()> createNonReentrantCallback(Task<>(C::*method)(), C *instance)
Create a callback for coroutine that should only run once at a time.
Definition timer_handler.h:98
virtual void setCallback(const std::function< void()> &callback)=0
change the callback method
virtual bool running()=0
returns true if callbacks should be called
virtual void setPeriod(const rclcpp::Duration &duration)=0
set the timer period/duration
virtual void stop()=0
stop the timer
virtual void start()=0
start the timer
rclcpp::Timer wrapper. The interface is the same as with rclcpp::Timer, except for the initialization...
Definition timer_handler.h:133
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:98
virtual void stop() override
stop the timer
Definition timer_handler.cpp:38
ROSTimer(const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), std::shared_ptr< C > instance)
Create Ros timer with coroutine callback.
Definition timer_handler.h:167
ROSTimer(const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), C *instance)
Create Ros timer with coroutine callback.
Definition timer_handler.h:151
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:74
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:107
virtual void start() override
start the timer
Definition timer_handler.cpp:59
Task type for creating coroutines.
Definition task.hpp:294
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition timer_handler.h:240
virtual void start() override
start the timer
Definition timer_handler.cpp:149
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition timer_handler.h:327
virtual void stop() override
stop the timer
Definition timer_handler.cpp:162
ThreadTimer(const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), std::shared_ptr< C > instance)
Create thread timer with coroutine callback.
Definition timer_handler.h:275
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:188
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:175
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:201
ThreadTimer(const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), C *instance)
Create thread timer with coroutine callback.
Definition timer_handler.h:259
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition timer_handler.h:16
Defines various general utility functions.