mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
Loading...
Searching...
No Matches
mrs_lib::ThreadTimer Class Reference

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
 
ThreadTimeroperator= (const ThreadTimer &)=delete
 
ThreadTimeroperator= (ThreadTimer &&)=delete
 
- Public Member Functions inherited from mrs_lib::MRSTimer
 MRSTimer (const MRSTimer &)=default
 
 MRSTimer (MRSTimer &&)=default
 
MRSTimeroperator= (const MRSTimer &)=default
 
MRSTimeroperator= (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_
 

Detailed Description

Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.

Constructor & Destructor Documentation

◆ ~ThreadTimer()

virtual mrs_lib::ThreadTimer::~ThreadTimer ( )
inlineoverridevirtual

stops the timer and then destroys the object

No more callbacks will be called when the destructor is started.

Member Function Documentation

◆ running()

bool mrs_lib::ThreadTimer::running ( )
overridevirtual

returns true if callbacks should be called

Returns
true if timer is running

Implements mrs_lib::MRSTimer.

◆ setCallback()

void mrs_lib::ThreadTimer::setCallback ( const std::function< void()> &  callback)
overridevirtual

change the callback method

Usable e.g. for running thread with a specific parameter if you bind it using std::bind

Parameters
callbackcallback method to be called.

Implements mrs_lib::MRSTimer.

◆ setPeriod()

void mrs_lib::ThreadTimer::setPeriod ( const rclcpp::Duration &  duration)
overridevirtual

set the timer period/duration

The new period will be applied after the next callback.

Parameters
durationthe new desired callback period.

Implements mrs_lib::MRSTimer.

◆ start()

void mrs_lib::ThreadTimer::start ( )
overridevirtual

start the timer

The first callback will be called in now + period.

Note
If the timer is already started, nothing will change.

Implements mrs_lib::MRSTimer.

◆ stop()

void mrs_lib::ThreadTimer::stop ( )
overridevirtual

stop the timer

No more callbacks will be called after this method returns.

Implements mrs_lib::MRSTimer.


The documentation for this class was generated from the following files: