Class TimerBase

Inheritance Relationships

Derived Type

Class Documentation

class TimerBase

Subclassed by rclcpp::GenericTimer< FunctorT, >

Public Functions

explicit TimerBase(Clock::SharedPtr clock, std::chrono::nanoseconds period, rclcpp::Context::SharedPtr context, bool autostart = true)

TimerBase constructor.

In order to activate a timer that is not started on initialization, user should call the reset() method.

Parameters:
  • clock – A clock to use for time and sleeping

  • period – The interval at which the timer fires

  • context – node context

  • autostart – timer state on initialization

virtual ~TimerBase()

TimerBase destructor.

void cancel()

Cancel the timer.

Throws:

std::runtime_error – if the rcl_timer_cancel returns a failure

bool is_canceled()

Return the timer cancellation state.

Throws:
  • std::runtime_error – if the rcl_get_error_state returns 0

  • rclcpp::exceptions::RCLError – some child class exception based on ret

Returns:

true if the timer has been cancelled, false otherwise

void reset()

Reset the timer.

Throws:

std::runtime_error – if the rcl_timer_reset returns a failure

virtual std::shared_ptr<void> call() = 0

Indicate that we’re about to execute the callback.

The multithreaded executor takes advantage of this to avoid scheduling the callback multiple times.

Returns:

a valid shared_ptr if the callback should be executed, an invalid shared_ptr (nullptr) if the timer was canceled.

virtual void execute_callback(const std::shared_ptr<void> &data) = 0

Call the callback function when the timer signal is emitted.

Parameters:

data[in] the pointer returned by the call function

std::shared_ptr<const rcl_timer_t> get_timer_handle()
std::chrono::nanoseconds time_until_trigger()

Check how long the timer has until its next scheduled callback.

Throws:

std::runtime_error – if the rcl_timer_get_time_until_next_call returns a failure

Returns:

A std::chrono::duration representing the relative time until the next callback or std::chrono::nanoseconds::max() if the timer is canceled.

virtual bool is_steady() = 0

Is the clock steady (i.e. is the time between ticks constant?)

Returns:

True if the clock used by this timer is steady.

bool is_ready()

Check if the timer is ready to trigger the callback.

This function expects its caller to immediately trigger the callback after this function, since it maintains the last time the callback was triggered.

Throws:

std::runtime_error – if it failed to check timer

Returns:

True if the timer needs to trigger.

bool exchange_in_use_by_wait_set_state(bool in_use_state)

Exchange the “in use by wait set” state for this timer.

This is used to ensure this timer is not used by multiple wait sets at the same time.

Parameters:

in_use_state[in] the new state to exchange into the state, true indicates it is now in use by a wait set, and false is that it is no longer in use by a wait set.

Returns:

the previous state.

void set_on_reset_callback(std::function<void(size_t)> callback)

Set a callback to be called when the timer is reset.

You should aim to make this callback fast and not blocking. If you need to do a lot of work or wait for some other event, you should spin it off to another thread.

Calling it again will override any previously set callback. An exception will be thrown if the callback is not callable.

This function is thread-safe.

If you want more information available in the callback, you may use a lambda with captures or std::bind.

Parameters:

callback[in] functor to be called whenever timer is reset

void clear_on_reset_callback()

Unset the callback registered for reset timer.

Protected Functions

void set_on_reset_callback(rcl_event_callback_t callback, const void *user_data)

Protected Attributes

std::recursive_mutex callback_mutex_
std::function<void(size_t)> on_reset_callback_ = {nullptr}
Clock::SharedPtr clock_
std::shared_ptr<rcl_timer_t> timer_handle_
std::atomic<bool> in_use_by_wait_set_ = {false}