Public Types | Public Member Functions | Static Public Member Functions | Private Member Functions | Private Attributes | List of all members
robot_activity::IsolatedAsyncTimer Class Reference

Wrapper around ROS Timer. More...

#include <isolated_async_timer.h>

Public Types

typedef std::function< void(void)> LambdaCallback
 

Public Member Functions

 IsolatedAsyncTimer ()=delete
 Default destructor is deleted. More...
 
 IsolatedAsyncTimer (const ros::NodeHandle &node_handle, const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=true, bool oneshot=false)
 Constructor. More...
 
 IsolatedAsyncTimer (const ros::NodeHandle &node_handle, const ros::TimerCallback &callback, const float &frequency, bool stoppable=true, bool autostart=true, bool oneshot=false)
 Constructor. More...
 
bool isValid ()
 Returns true if timer is valid. More...
 
void pause ()
 Pauses the timer. More...
 
void resume ()
 Resumes the timer. More...
 
void setRate (const float &frequency, bool reset=true)
 Sets a new rate to the timer. More...
 
void start ()
 Starts the timer. More...
 
void stop ()
 Stops the timer if set to stoppable. More...
 
 ~IsolatedAsyncTimer ()
 Default destructor. More...
 

Static Public Member Functions

static ros::TimerCallback to_timer_callback (const IsolatedAsyncTimer::LambdaCallback &callback)
 Converts a Lambda callback to valid ros::TimerCallback. More...
 

Private Member Functions

ros::TimerCallback wrapTimerCallback (const ros::TimerCallback &callback) const
 Wraps a ros::TimerCallback with additional functionality. More...
 

Private Attributes

ros::TimerCallback callback_
 Actual ros::TimerCallback used in the timer. More...
 
ros::CallbackQueue callback_queue_
 Seperate callback queue for the timer. More...
 
float frequency_
 Frequency in Hz of the timer. More...
 
ros::NodeHandle node_handle_
 Node handle used to create the actual ros::Timer. More...
 
std::atomic< bool > paused_
 Atomic bool that determines whether timer is paused or not. More...
 
ros::Duration period_
 Duration between consecutive callback executions. More...
 
std::shared_ptr< ros::AsyncSpinnerspinner_
 Shared pointer to the actual ros::AsyncSpiner that serves the callback queue in the background. More...
 
std::atomic< bool > stoppable_
 Atomic bool that determines whether timer is stoppable or not. More...
 
std::shared_ptr< ros::Timertimer_
 Shared pointer to the actual ros::Timer object. More...
 
ros::TimerOptions timer_ops_
 Timer options needed for. More...
 

Detailed Description

Wrapper around ROS Timer.

ROS Timer served by a single-threaded async spinner on a separate callback queue. Timer can also be paused, which will trigger the callback, but return immediately

Definition at line 62 of file isolated_async_timer.h.

Member Typedef Documentation

typedef std::function<void(void)> robot_activity::IsolatedAsyncTimer::LambdaCallback

Definition at line 65 of file isolated_async_timer.h.

Constructor & Destructor Documentation

robot_activity::IsolatedAsyncTimer::IsolatedAsyncTimer ( )
delete

Default destructor is deleted.

[long description]

robot_activity::IsolatedAsyncTimer::IsolatedAsyncTimer ( const ros::NodeHandle node_handle,
const IsolatedAsyncTimer::LambdaCallback callback,
const float &  frequency,
bool  stoppable = true,
bool  autostart = true,
bool  oneshot = false 
)
inline

Constructor.

Constructs IsolatedAsyncTimer given a callback in form of a boost::function, which takes and returns void. Similarly to ROS's createTimer, the timer can be autostarted and run only once. Additionally, the timer can be set to unstopabble, where pausing and stopping does not have any effect

Parameters
node_handle[description]
callback[description]
frequency[description]
stoppable[description]
autostart[description]
oneshot[description]

Definition at line 88 of file isolated_async_timer.h.

robot_activity::IsolatedAsyncTimer::IsolatedAsyncTimer ( const ros::NodeHandle node_handle,
const ros::TimerCallback callback,
const float &  frequency,
bool  stoppable = true,
bool  autostart = true,
bool  oneshot = false 
)
inline

Constructor.

Constructs IsolatedAsyncTimer given a callback in form of a ros::TimerCallback, which takes a ros::TimerEvent and returns a void. Similarly to ROS's createTimer, the timer can be autostarted and run only once. Additionally, the timer can be set to unstopabble, where pausing and stopping does not have any effect

Parameters
node_handle[description]
callback[description]
frequency[description]
stoppable[description]
autostart[description]
oneshot[description]

Definition at line 117 of file isolated_async_timer.h.

robot_activity::IsolatedAsyncTimer::~IsolatedAsyncTimer ( )
inline

Default destructor.

Definition at line 150 of file isolated_async_timer.h.

Member Function Documentation

bool robot_activity::IsolatedAsyncTimer::isValid ( )
inline

Returns true if timer is valid.

Definition at line 191 of file isolated_async_timer.h.

void robot_activity::IsolatedAsyncTimer::pause ( )
inline

Pauses the timer.

Definition at line 175 of file isolated_async_timer.h.

void robot_activity::IsolatedAsyncTimer::resume ( )
inline

Resumes the timer.

Definition at line 183 of file isolated_async_timer.h.

void robot_activity::IsolatedAsyncTimer::setRate ( const float &  frequency,
bool  reset = true 
)
inline

Sets a new rate to the timer.

Sets a new rate to the timer and resets if asked for. Resetting will stop and start the timer, thus copying the callback. Copying the callback causes its state to be reset if the callback was passed as a closure (a lambda)

Parameters
frequencyNew timer frequency in Hz
resetWhether to reset the timer or not

Definition at line 206 of file isolated_async_timer.h.

void robot_activity::IsolatedAsyncTimer::start ( )
inline

Starts the timer.

Definition at line 158 of file isolated_async_timer.h.

void robot_activity::IsolatedAsyncTimer::stop ( )
inline

Stops the timer if set to stoppable.

Definition at line 166 of file isolated_async_timer.h.

static ros::TimerCallback robot_activity::IsolatedAsyncTimer::to_timer_callback ( const IsolatedAsyncTimer::LambdaCallback callback)
inlinestatic

Converts a Lambda callback to valid ros::TimerCallback.

Parameters
callbackLambda callback i.e. an std::function<void(void)>
Returns
ros::TimerCallback that can be used to create a ros::Timer

Definition at line 219 of file isolated_async_timer.h.

ros::TimerCallback robot_activity::IsolatedAsyncTimer::wrapTimerCallback ( const ros::TimerCallback callback) const
inlineprivate

Wraps a ros::TimerCallback with additional functionality.

The returned callback returns immediately if it's stoppable and paused. It also checks if the loop missed it's desired rate.

Parameters
callbackros::TimerCallback to be wrapped
Returns
Wrapped ros::TimerCallback

Definition at line 237 of file isolated_async_timer.h.

Member Data Documentation

ros::TimerCallback robot_activity::IsolatedAsyncTimer::callback_
private

Actual ros::TimerCallback used in the timer.

Definition at line 280 of file isolated_async_timer.h.

ros::CallbackQueue robot_activity::IsolatedAsyncTimer::callback_queue_
private

Seperate callback queue for the timer.

Definition at line 285 of file isolated_async_timer.h.

float robot_activity::IsolatedAsyncTimer::frequency_
private

Frequency in Hz of the timer.

Definition at line 265 of file isolated_async_timer.h.

ros::NodeHandle robot_activity::IsolatedAsyncTimer::node_handle_
private

Node handle used to create the actual ros::Timer.

Definition at line 260 of file isolated_async_timer.h.

std::atomic<bool> robot_activity::IsolatedAsyncTimer::paused_
private

Atomic bool that determines whether timer is paused or not.

Definition at line 307 of file isolated_async_timer.h.

ros::Duration robot_activity::IsolatedAsyncTimer::period_
private

Duration between consecutive callback executions.

Definition at line 270 of file isolated_async_timer.h.

std::shared_ptr<ros::AsyncSpinner> robot_activity::IsolatedAsyncTimer::spinner_
private

Shared pointer to the actual ros::AsyncSpiner that serves the callback queue in the background.

Definition at line 297 of file isolated_async_timer.h.

std::atomic<bool> robot_activity::IsolatedAsyncTimer::stoppable_
private

Atomic bool that determines whether timer is stoppable or not.

Definition at line 302 of file isolated_async_timer.h.

std::shared_ptr<ros::Timer> robot_activity::IsolatedAsyncTimer::timer_
private

Shared pointer to the actual ros::Timer object.

Definition at line 291 of file isolated_async_timer.h.

ros::TimerOptions robot_activity::IsolatedAsyncTimer::timer_ops_
private

Timer options needed for.

Definition at line 275 of file isolated_async_timer.h.


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


robot_activity
Author(s): Maciej ZURAD
autogenerated on Thu Jun 6 2019 19:32:17