4#include <rclcpp/rclcpp.hpp>
19 rclcpp::Node::SharedPtr node;
23 bool autostart =
true;
25 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
39 using callback_t = std::function<void()>;
57 virtual void setPeriod(
const rclcpp::Duration& duration) = 0;
66 virtual void setCallback(
const std::function<
void()>& callback) = 0;
84 rclcpp::Node::SharedPtr node_;
98 ROSTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
105 virtual void stop()
override;
110 virtual void start()
override;
118 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
127 virtual void setCallback(
const std::function<
void()>& callback)
override;
134 virtual bool running()
override;
147 std::mutex mutex_timer_;
149 std::function<void()> callback;
153 rclcpp::TimerBase::SharedPtr timer_;
155 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
172 ThreadTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
181 virtual void stop()
override;
190 virtual void start()
override;
199 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
208 virtual void setCallback(
const std::function<
void()>& callback)
override;
215 virtual bool running()
override;
234 std::unique_ptr<Impl> impl_;
243#include <mrs_lib/impl/timer_handler.hpp>
Common wrapper representing the functionality of the rclcpp::Timer.
Definition timer_handler.h:37
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:94
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:94
virtual void stop() override
stop the timer
Definition timer_handler.cpp:43
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:102
virtual void start() override
start the timer
Definition timer_handler.cpp:61
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition timer_handler.h:167
virtual void start() override
start the timer
Definition timer_handler.cpp:138
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition timer_handler.h:222
virtual void stop() override
stop the timer
Definition timer_handler.cpp:149
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:171
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:160
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:182
All mrs_lib functions, classes, variables and definitions are contained in this namespace.
Definition attitude_converter.h:24
Definition timer_handler.h:13
Defines various general utility functions.