ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization method.
More...
#include <timer.h>
|
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 |
|
ROSTimer & | operator= (const ROSTimer &)=delete |
|
ROSTimer & | operator= (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) |
|
| MRSTimer (const MRSTimer &)=default |
|
| MRSTimer (MRSTimer &&)=default |
|
MRSTimer & | operator= (const MRSTimer &)=default |
|
MRSTimer & | operator= (MRSTimer &&)=default |
|
|
using | callback_t = std::function< void(const ros::TimerEvent &)> |
|
ros::Timer wrapper. The interface is the same as with ros::Timer, except for the initialization method.
◆ 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
-
- Parameters
-
nh | ROS node handle to be used for creating the underlying ros::Timer object. |
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. |
◆ 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
-
- Parameters
-
nh | ROS node handle to be used for creating the underlying ros::Timer object. |
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. |
◆ 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
-
callback | callback method to be called. |
Implements mrs_lib::MRSTimer.
◆ setPeriod()
void mrs_lib::ROSTimer::setPeriod |
( |
const ros::Duration & |
duration, |
|
|
const bool |
reset = true |
|
) |
| |
|
overridevirtual |
The documentation for this class was generated from the following files: