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

ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization method. More...

#include <timer.h>

+ Inheritance diagram for mrs_lib::ROSTimer:
+ Collaboration diagram for mrs_lib::ROSTimer:

Public Member Functions

template<class ObjectType >
 ROSTimer (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 >
 ROSTimer (const ros::NodeHandle &nh, const ros::Duration &duration, void(ObjectType::*const callback)(const ros::TimerEvent &), ObjectType *const obj, const bool oneshot=false, const bool autostart=true)
 full constructor More...
 
virtual void stop () override
 stop the timer
 
virtual void start () override
 start the timer
 
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...
 
 ROSTimer (const ROSTimer &)=delete
 
 ROSTimer (ROSTimer &&)=delete
 
ROSTimeroperator= (const ROSTimer &)=delete
 
ROSTimeroperator= (ROSTimer &&)=delete
 
template<class ObjectType >
 ROSTimer (const ros::NodeHandle &nh, const ros::Duration &duration, void(ObjectType::*const callback)(const ros::TimerEvent &), ObjectType *const obj, const bool oneshot, const bool autostart)
 
template<class ObjectType >
 ROSTimer (const ros::NodeHandle &nh, const ros::Rate &rate, void(ObjectType::*const callback)(const ros::TimerEvent &), ObjectType *const obj, const bool oneshot, const bool autostart)
 
- 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

ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization method.

Constructor & Destructor Documentation

◆ ROSTimer() [1/2]

template<class ObjectType >
mrs_lib::ROSTimer::ROSTimer ( 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
nhROS node handle to be used for creating the underlying ros::Timer object.
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.

◆ ROSTimer() [2/2]

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

full constructor

Template Parameters
ObjectType
Parameters
nhROS node handle to be used for creating the underlying ros::Timer object.
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.

Member Function Documentation

◆ running()

bool mrs_lib::ROSTimer::running ( )
overridevirtual

returns true if callbacks should be called

Returns
true if timer is running

Implements mrs_lib::MRSTimer.

◆ setCallback()

void mrs_lib::ROSTimer::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::ROSTimer::setPeriod ( const ros::Duration &  duration,
const bool  reset = true 
)
overridevirtual

set the timer period/duration

Parameters
duration
reset

Implements mrs_lib::MRSTimer.


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