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)

TimerBase constructor.

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

  • period – The interval at which the timer fires

  • context – node context

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 bool 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:

true if the callback should be executed, false if the timer was canceled.

virtual void execute_callback() = 0

Call the callback function when the timer signal is emitted.

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.

Protected Attributes

Clock::SharedPtr clock_
std::shared_ptr<rcl_timer_t> timer_handle_
std::atomic<bool> in_use_by_wait_set_ = {false}