Class TimersManager

Nested Relationships

Nested Types

Class Documentation

class TimersManager

This class provides a way for storing and executing timer objects. It provides APIs to suit the needs of different applications and execution models. All public APIs provided by this class are thread-safe.

Timers management This class provides APIs to add/remove timers to/from an internal storage. It keeps a list of weak pointers from added timers, and locks them only when they need to be executed or modified. Timers are kept ordered in a binary-heap priority queue. Calls to add/remove APIs will temporarily block the execution of the timers and will require to reorder the internal priority queue. Because of this, they have a not-negligible impact on the performance.

Timers execution The most efficient use of this class consists in letting a TimersManager object to spawn a thread where timers are monitored and optionally executed. This can be controlled via the start and stop methods. Ready timers can either be executed or an on_ready_callback can be used to notify other entities that they are ready and need to be executed. Other APIs allow to directly execute a given timer.

This class assumes that the execute_callback() API of the stored timers is never called by other entities, but it can only be called from here. If this assumption is not respected, the heap property may be invalidated, so timers may be executed out of order, without this object noticing it.

Public Functions

TimersManager(std::shared_ptr<rclcpp::Context> context, std::function<void(const rclcpp::TimerBase*, const std::shared_ptr<void>&)> on_ready_callback = nullptr)

Construct a new TimersManager object.

Parameters:
  • context – custom context to be used. Shared ownership of the context is held until destruction.

  • on_ready_callback – The timers on ready callback. The presence of this function indicates what to do when the TimersManager is running and a timer becomes ready. The TimersManager is considered “running” when the start method has been called. If it’s callable, it will be invoked instead of the timer callback. If it’s not callable, then the TimersManager will directly execute timers when they are ready. All the methods that execute a given timer (e.g. execute_head_timer or execute_ready_timer) without the TimersManager being running, i.e. without actually explicitly waiting for the timer to become ready, will ignore this callback.

~TimersManager()

Destruct the TimersManager object making sure to stop thread and release memory.

void add_timer(rclcpp::TimerBase::SharedPtr timer)

Adds a new timer to the storage, maintaining weak ownership of it. Function is thread safe and it can be called regardless of the state of the timers thread.

Parameters:

timer – the timer to add.

Throws:

std::invalid_argument – if timer is a nullptr.

void remove_timer(rclcpp::TimerBase::SharedPtr timer)

Remove a single timer from the object storage. Will do nothing if the timer was not being stored here. Function is thread safe and it can be called regardless of the state of the timers thread.

Parameters:

timer – the timer to remove.

void clear()

Remove all the timers stored in the object. Function is thread safe and it can be called regardless of the state of the timers thread.

void start()

Starts a thread that takes care of executing the timers stored in this object. Function will throw an error if the timers thread was already running.

void stop()

Stops the timers thread. Will do nothing if the timer thread was not running.

size_t get_number_ready_timers()

Get the number of timers that are currently ready. This function is thread safe.

Throws:

std::runtime_error – if the timers thread was already running.

Returns:

size_t number of ready timers.

bool execute_head_timer()

Executes head timer if ready. This function is thread safe. This function will try to execute the timer callback regardless of whether the TimersManager on_ready_callback was passed during construction.

Throws:

std::runtime_error – if the timers thread was already running.

Returns:

true if head timer was ready.

void execute_ready_timer(const rclcpp::TimerBase *timer_id, const std::shared_ptr<void> &data)

Executes timer identified by its ID. This function is thread safe. This function will try to execute the timer callback regardless of whether the TimersManager on_ready_callback was passed during construction.

Parameters:
  • timer_id – the timer ID of the timer to execute

  • data – internal data of the timer

std::optional<std::chrono::nanoseconds> get_head_timeout()

Get the amount of time before the next timer triggers. This function is thread safe.

Throws:

std::runtime_error – if the timers thread was already running.

Returns:

std::optional<std::chrono::nanoseconds> to wait, the returned value could be negative if the timer is already expired or std::chrono::nanoseconds::max() if there are no timers stored in the object. If the head timer was cancelled, then this will return a nullopt.