Wrapper around ROS Timer. More...
#include <isolated_async_timer.h>
Public Types | |
typedef std::function< void(void)> | LambdaCallback |
Public Member Functions | |
IsolatedAsyncTimer () | |
Default destructor is deleted. | |
IsolatedAsyncTimer (const ros::NodeHandle &node_handle, const IsolatedAsyncTimer::LambdaCallback &callback, const float &frequency, bool stoppable=true, bool autostart=true, bool oneshot=false) | |
Constructor. | |
IsolatedAsyncTimer (const ros::NodeHandle &node_handle, const ros::TimerCallback &callback, const float &frequency, bool stoppable=true, bool autostart=true, bool oneshot=false) | |
Constructor. | |
bool | isValid () |
Returns true if timer is valid. | |
void | pause () |
Pauses the timer. | |
void | resume () |
Resumes the timer. | |
void | setRate (const float &frequency, bool reset=true) |
Sets a new rate to the timer. | |
void | start () |
Starts the timer. | |
void | stop () |
Stops the timer if set to stoppable. | |
~IsolatedAsyncTimer () | |
Default destructor. | |
Static Public Member Functions | |
static ros::TimerCallback | to_timer_callback (const IsolatedAsyncTimer::LambdaCallback &callback) |
Converts a Lambda callback to valid ros::TimerCallback. | |
Private Member Functions | |
ros::TimerCallback | wrapTimerCallback (const ros::TimerCallback &callback) const |
Wraps a ros::TimerCallback with additional functionality. | |
Private Attributes | |
ros::TimerCallback | callback_ |
Actual ros::TimerCallback used in the timer. | |
ros::CallbackQueue | callback_queue_ |
Seperate callback queue for the timer. | |
float | frequency_ |
Frequency in Hz of the timer. | |
ros::NodeHandle | node_handle_ |
Node handle used to create the actual ros::Timer. | |
std::atomic< bool > | paused_ |
Atomic bool that determines whether timer is paused or not. | |
ros::Duration | period_ |
Duration between consecutive callback executions. | |
std::shared_ptr < ros::AsyncSpinner > | spinner_ |
Shared pointer to the actual ros::AsyncSpiner that serves the callback queue in the background. | |
std::atomic< bool > | stoppable_ |
Atomic bool that determines whether timer is stoppable or not. | |
std::shared_ptr< ros::Timer > | timer_ |
Shared pointer to the actual ros::Timer object. | |
ros::TimerOptions | timer_ops_ |
Timer options needed for. |
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.
typedef std::function<void(void)> robot_activity::IsolatedAsyncTimer::LambdaCallback |
Definition at line 65 of file isolated_async_timer.h.
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
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
node_handle | [description] |
callback | [description] |
frequency | [description] |
stoppable | [description] |
autostart | [description] |
oneshot | [description] |
Definition at line 117 of file isolated_async_timer.h.
Default destructor.
Definition at line 150 of file isolated_async_timer.h.
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)
frequency | New timer frequency in Hz |
reset | Whether 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 | ) | [inline, static] |
Converts a Lambda callback to valid ros::TimerCallback.
callback | Lambda callback i.e. an std::function<void(void)> |
Definition at line 219 of file isolated_async_timer.h.
ros::TimerCallback robot_activity::IsolatedAsyncTimer::wrapTimerCallback | ( | const ros::TimerCallback & | callback | ) | const [inline, private] |
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.
callback | ros::TimerCallback to be wrapped |
Definition at line 237 of file isolated_async_timer.h.
Actual ros::TimerCallback used in the timer.
Definition at line 280 of file isolated_async_timer.h.
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.
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.
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.
Timer options needed for.
Definition at line 275 of file isolated_async_timer.h.