![]() |
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer. More...
#include <timer_handler.h>
Inheritance diagram for mrs_lib::ThreadTimer:
Collaboration diagram for mrs_lib::ThreadTimer:Public Member Functions | |
| ThreadTimer (const rclcpp::Node::SharedPtr &node, const rclcpp::Rate &rate, const std::function< void()> &callback) | |
| ThreadTimer (const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, const std::function< void()> &callback) | |
| virtual void | stop () override |
| stop the timer | |
| virtual void | start () override |
| start the timer | |
| virtual void | setPeriod (const rclcpp::Duration &duration) override |
| set the timer period/duration | |
| virtual void | setCallback (const std::function< void()> &callback) override |
| change the callback method | |
| virtual bool | running () override |
| returns true if callbacks should be called | |
| virtual | ~ThreadTimer () override |
| stops the timer and then destroys the object | |
| ThreadTimer (const ThreadTimer &)=delete | |
| ThreadTimer (ThreadTimer &&)=delete | |
| ThreadTimer & | operator= (const ThreadTimer &)=delete |
| ThreadTimer & | operator= (ThreadTimer &&)=delete |
Public Member Functions inherited from mrs_lib::MRSTimer | |
| MRSTimer (const MRSTimer &)=default | |
| MRSTimer (MRSTimer &&)=default | |
| MRSTimer & | operator= (const MRSTimer &)=default |
| MRSTimer & | operator= (MRSTimer &&)=default |
Additional Inherited Members | |
Public Types inherited from mrs_lib::MRSTimer | |
| using | callback_t = std::function< void()> |
Protected Attributes inherited from mrs_lib::MRSTimer | |
| rclcpp::Node::SharedPtr | node_ |
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
|
inlineoverridevirtual |
stops the timer and then destroys the object
No more callbacks will be called when the destructor is started.
|
overridevirtual |
returns true if callbacks should be called
Implements mrs_lib::MRSTimer.
|
overridevirtual |
change the callback method
Usable e.g. for running thread with a specific parameter if you bind it using std::bind
| callback | callback method to be called. |
Implements mrs_lib::MRSTimer.
|
overridevirtual |
set the timer period/duration
The new period will be applied after the next callback.
| duration | the new desired callback period. |
Implements mrs_lib::MRSTimer.
|
overridevirtual |
start the timer
The first callback will be called in now + period.
Implements mrs_lib::MRSTimer.
|
overridevirtual |
stop the timer
No more callbacks will be called after this method returns.
Implements mrs_lib::MRSTimer.