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.h>
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 | |
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(const ros::TimerEvent &)> |
Custom thread-based Timers with the same interface as mrs_lib::ROSTimer.
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.
ObjectType |
nh | ignored (used just for consistency with ROSTimer) |
rate | rate at which the callback should be called. |
ObjectType::*const | callback callback method to be called. |
obj | object for the method. |
oneshot | whether the callback should only be called once after starting. |
autostart | whether the timer should immediately start after construction. |
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.
ObjectType |
nh | ignored (used just for consistency with ROSTimer) |
duration | desired callback period. |
ObjectType::*const | callback callback method to be called. |
obj | object for the method. |
oneshot | whether the callback should only be called once after starting. |
autostart | whether the timer should immediately start after construction. |
|
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. |
reset | ignored in this implementation. |
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.