mrs_lib
Various reusable classes, functions and utilities for use in MRS projects
mrs_lib::ThreadTimer Class Reference

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

#include <timer.h>

+ Inheritance diagram for mrs_lib::ThreadTimer:
+ Collaboration diagram for mrs_lib::ThreadTimer:

Public Member Functions

template<class ObjectType >
 ThreadTimer (const ros::NodeHandle &nh, const ros::Rate &rate, void(ObjectType::*const callback)(const ros::TimerEvent &), ObjectType *const obj, const bool oneshot=false, const bool autostart=true)
 Constructs the object. More...
 
template<class ObjectType >
 ThreadTimer (const ros::NodeHandle &nh, const ros::Duration &duration, void(ObjectType::*const callback)(const ros::TimerEvent &), ObjectType *const obj, bool oneshot=false, const bool autostart=true)
 Constructs the object. More...
 
virtual void stop () override
 stop the timer More...
 
virtual void start () override
 start the timer More...
 
virtual void setPeriod (const ros::Duration &duration, const bool reset=true) override
 set the timer period/duration More...
 
virtual void setCallback (const std::function< void(const ros::TimerEvent &)> &callback) override
 change the callback method More...
 
virtual bool running () override
 returns true if callbacks should be called More...
 
virtual ~ThreadTimer () override
 stops the timer and then destroys the object More...
 
 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(const ros::TimerEvent &)>
 

Detailed Description

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

Constructor & Destructor Documentation

◆ ThreadTimer() [1/2]

template<class ObjectType >
mrs_lib::ThreadTimer::ThreadTimer ( const ros::NodeHandle &  nh,
const ros::Rate &  rate,
void(ObjectType::*)(const ros::TimerEvent &)  callback,
ObjectType *const  obj,
const bool  oneshot = false,
const bool  autostart = true 
)

Constructs the object.

Template Parameters
ObjectType
Parameters
nhignored (used just for consistency with ROSTimer)
raterate at which the callback should be called.
ObjectType::*constcallback callback method to be called.
objobject for the method.
oneshotwhether the callback should only be called once after starting.
autostartwhether the timer should immediately start after construction.

◆ ThreadTimer() [2/2]

template<class ObjectType >
mrs_lib::ThreadTimer::ThreadTimer ( const ros::NodeHandle &  nh,
const ros::Duration &  duration,
void(ObjectType::*)(const ros::TimerEvent &)  callback,
ObjectType *const  obj,
bool  oneshot = false,
const bool  autostart = true 
)

Constructs the object.

Template Parameters
ObjectType
Parameters
nhignored (used just for consistency with ROSTimer)
durationdesired callback period.
ObjectType::*constcallback callback method to be called.
objobject for the method.
oneshotwhether the callback should only be called once after starting.
autostartwhether the timer should immediately start after construction.

◆ ~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(const ros::TimerEvent &)> &  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 ros::Duration &  duration,
const bool  reset = true 
)
overridevirtual

set the timer period/duration

The new period will be applied after the next callback.

Parameters
durationthe new desired callback period.
resetignored in this implementation.

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: