4#include <rclcpp/rclcpp.hpp>
20 rclcpp::Node::SharedPtr node;
24 bool autostart =
true;
26 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group;
41 using callback_t = std::function<void()>;
59 virtual void setPeriod(
const rclcpp::Duration& duration) = 0;
68 virtual void setCallback(
const std::function<
void()>& callback) = 0;
86 rclcpp::Node::SharedPtr node_;
101 ROSTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
108 virtual void stop()
override;
113 virtual void start()
override;
121 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
130 virtual void setCallback(
const std::function<
void()>& callback)
override;
137 virtual bool running()
override;
151 std::mutex mutex_timer_;
153 std::function<void()> callback;
157 rclcpp::TimerBase::SharedPtr timer_;
159 std::optional<rclcpp::CallbackGroup::SharedPtr> callback_group_;
177 ThreadTimer(
const rclcpp::Node::SharedPtr& node,
const rclcpp::Rate& rate,
const std::function<
void()>& callback);
186 virtual void stop()
override;
195 virtual void start()
override;
204 virtual void setPeriod(
const rclcpp::Duration& duration)
override;
213 virtual void setCallback(
const std::function<
void()>& callback)
override;
220 virtual bool running()
override;
240 std::unique_ptr<Impl> impl_;
249#include <mrs_lib/impl/timer_handler.hpp>
Common wrapper representing the functionality of the rclcpp::Timer.
Definition timer_handler.h:39
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:97
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:108
virtual void stop() override
stop the timer
Definition timer_handler.cpp:48
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:84
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:117
virtual void start() override
start the timer
Definition timer_handler.cpp:69
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
Definition timer_handler.h:172
virtual void start() override
start the timer
Definition timer_handler.cpp:159
virtual ~ThreadTimer() override
stops the timer and then destroys the object
Definition timer_handler.h:227
virtual void stop() override
stop the timer
Definition timer_handler.cpp:172
virtual void setCallback(const std::function< void()> &callback) override
change the callback method
Definition timer_handler.cpp:198
virtual void setPeriod(const rclcpp::Duration &duration) override
set the timer period/duration
Definition timer_handler.cpp:185
virtual bool running() override
returns true if callbacks should be called
Definition timer_handler.cpp:211
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.