4#include <rclcpp/rclcpp.hpp>
7#include <mrs_lib/coro/runners.hpp>
8#include <mrs_lib/coro/task.hpp>
9#include <mrs_lib/internal/coroutine_callback_helpers.hpp>
23 rclcpp::Node::SharedPtr node;
27 bool autostart =
true;
29 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
44 using callback_t = std::function<void()>;
62 virtual void setPeriod(
const rclcpp::Duration& duration) = 0;
71 virtual void setCallback(
const std::function<
void()>& callback) = 0;
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);
107 internal::start_task(
110 [](std::shared_ptr<std::atomic<bool>> is_running,
Task<> (C::*method)(), C* instance) ->
mrs_lib::Task<> {
112 co_await std::invoke(method, instance);
114 is_running->store(
false);
117 is_running, method, instance);
122 rclcpp::Node::SharedPtr node_;
137 ROSTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
150 template <
typename C>
154 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(
nullptr));
166 template <
typename C>
170 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(
nullptr));
176 virtual void stop()
override;
181 virtual void start()
override;
189 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
198 virtual void setCallback(
const std::function<
void()>& callback)
override;
205 virtual bool running()
override;
213 ROSTimer(
const ROSTimer&) =
delete;
214 ROSTimer(ROSTimer&&) =
delete;
215 ROSTimer& operator=(
const ROSTimer&) =
delete;
216 ROSTimer& operator=(ROSTimer&&) =
delete;
219 std::mutex mutex_timer_;
221 std::function<void()> callback;
225 rclcpp::TimerBase::SharedPtr timer_;
227 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
245 ThreadTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
258 template <
typename C>
262 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(
nullptr));
274 template <
typename C>
278 internal::require_callback_group_coro_compatible(opts.callback_group.value_or(
nullptr));
286 virtual void stop()
override;
295 virtual void start()
override;
304 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
313 virtual void setCallback(
const std::function<
void()>& callback)
override;
320 virtual bool running()
override;
340 std::unique_ptr<Impl> impl_;
349#include <mrs_lib/impl/timer_handler.hpp>
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.