![]() |
mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
|
rclcpp::Timer wrapper. The interface is the same as with rclcpp::Timer, except for the initialization method. More...
#include <timer_handler.h>
Inheritance diagram for mrs_lib::ROSTimer:
Collaboration diagram for mrs_lib::ROSTimer:Public Member Functions | |
| ROSTimer (const rclcpp::Node::SharedPtr &node, const rclcpp::Rate &rate, const std::function< void()> &callback) | |
| ROSTimer (const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, const std::function< void()> &callback) | |
| template<typename C > | |
| ROSTimer (const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), C *instance) | |
| Create Ros timer with coroutine callback. | |
| template<typename C > | |
| ROSTimer (const mrs_lib::TimerHandlerOptions &opts, const rclcpp::Rate &rate, Task<>(C::*method)(), std::shared_ptr< C > instance) | |
| Create Ros timer with coroutine 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 | |
| ROSTimer (const ROSTimer &)=delete | |
| ROSTimer (ROSTimer &&)=delete | |
| ROSTimer & | operator= (const ROSTimer &)=delete |
| ROSTimer & | operator= (ROSTimer &&)=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()> |
Static Protected Member Functions inherited from mrs_lib::MRSTimer | |
| template<typename C > | |
| static std::function< void()> | createNonReentrantCallback (Task<>(C::*method)(), C *instance) |
| Create a callback for coroutine that should only run once at a time. | |
Protected Attributes inherited from mrs_lib::MRSTimer | |
| rclcpp::Node::SharedPtr | node_ |
rclcpp::Timer wrapper. The interface is the same as with rclcpp::Timer, except for the initialization method.
|
inline |
Create Ros timer with coroutine callback.
Using coroutine callbacks is only allowed with reentrant callback group. If the specified callback group is not reentrant, this throws an exception.
To make the callback design simpler, the coroutine itself will not run again until the previous one completely finished.
|
inline |
Create Ros timer with coroutine callback.
Using coroutine callbacks is only allowed with reentrant callback group. If the specified callback group is not reentrant, this throws an exception.
To make the callback design simpler, the coroutine itself will not run again until the previous one completely finished.
|
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 |
|
overridevirtual |
start the timer
Implements mrs_lib::MRSTimer.
|
overridevirtual |
stop the timer
Implements mrs_lib::MRSTimer.