ROS 2 rclcpp + rcl - humble  humble
ROS 2 C++ Client Library with ROS Client Library
Public Member Functions | Protected Attributes | List of all members
rclcpp::TimerBase Class Referenceabstract
Inheritance diagram for rclcpp::TimerBase:
Inheritance graph
[legend]

Public Member Functions

RCLCPP_PUBLIC TimerBase (Clock::SharedPtr clock, std::chrono::nanoseconds period, rclcpp::Context::SharedPtr context)
 TimerBase constructor. More...
 
virtual RCLCPP_PUBLIC ~TimerBase ()
 TimerBase destructor.
 
RCLCPP_PUBLIC void cancel ()
 Cancel the timer. More...
 
RCLCPP_PUBLIC bool is_canceled ()
 Return the timer cancellation state. More...
 
RCLCPP_PUBLIC void reset ()
 Reset the timer. More...
 
virtual RCLCPP_PUBLIC bool call ()=0
 Indicate that we're about to execute the callback. More...
 
virtual RCLCPP_PUBLIC void execute_callback ()=0
 Call the callback function when the timer signal is emitted.
 
RCLCPP_PUBLIC std::shared_ptr< const rcl_timer_tget_timer_handle ()
 
RCLCPP_PUBLIC std::chrono::nanoseconds time_until_trigger ()
 Check how long the timer has until its next scheduled callback. More...
 
virtual bool is_steady ()=0
 Is the clock steady (i.e. is the time between ticks constant?) More...
 
RCLCPP_PUBLIC bool is_ready ()
 Check if the timer is ready to trigger the callback. More...
 
RCLCPP_PUBLIC bool exchange_in_use_by_wait_set_state (bool in_use_state)
 Exchange the "in use by wait set" state for this timer. More...
 

Protected Attributes

Clock::SharedPtr clock_
 
std::shared_ptr< rcl_timer_ttimer_handle_
 
std::atomic< bool > in_use_by_wait_set_ {false}
 

Detailed Description

Definition at line 46 of file timer.hpp.

Constructor & Destructor Documentation

◆ TimerBase()

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

TimerBase constructor.

Parameters
clockA clock to use for time and sleeping
periodThe interval at which the timer fires
contextnode context

Definition at line 29 of file timer.cpp.

References rcl_get_default_allocator, rcl_get_zero_initialized_timer(), RCL_RET_OK, rcl_timer_fini(), and rcl_timer_init().

Here is the call graph for this function:

Member Function Documentation

◆ call()

virtual RCLCPP_PUBLIC bool rclcpp::TimerBase::call ( )
pure virtual

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.

Implemented in rclcpp::GenericTimer< FunctorT, >.

◆ cancel()

void TimerBase::cancel ( )

Cancel the timer.

Exceptions
std::runtime_errorif the rcl_timer_cancel returns a failure

Definition at line 77 of file timer.cpp.

References RCL_RET_OK, and rcl_timer_cancel().

Referenced by rclcpp::GenericTimer< FunctorT, >::~GenericTimer().

Here is the call graph for this function:
Here is the caller graph for this function:

◆ exchange_in_use_by_wait_set_state()

bool TimerBase::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]in_use_statethe 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.

Definition at line 137 of file timer.cpp.

◆ is_canceled()

bool TimerBase::is_canceled ( )

Return the timer cancellation state.

Returns
true if the timer has been cancelled, false otherwise
Exceptions
std::runtime_errorif the rcl_get_error_state returns 0
rclcpp::exceptions::RCLErrorsome child class exception based on ret

Definition at line 86 of file timer.cpp.

References RCL_RET_OK, and rcl_timer_is_canceled().

Here is the call graph for this function:

◆ is_ready()

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

Returns
True if the timer needs to trigger.
Exceptions
std::runtime_errorif it failed to check timer

Definition at line 106 of file timer.cpp.

References RCL_RET_OK, and rcl_timer_is_ready().

Here is the call graph for this function:

◆ is_steady()

virtual bool rclcpp::TimerBase::is_steady ( )
pure virtual

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

Returns
True if the clock used by this timer is steady.

Implemented in rclcpp::GenericTimer< FunctorT, >.

◆ reset()

void TimerBase::reset ( )

Reset the timer.

Exceptions
std::runtime_errorif the rcl_timer_reset returns a failure

Definition at line 97 of file timer.cpp.

References RCL_RET_OK, and rcl_timer_reset().

Here is the call graph for this function:

◆ time_until_trigger()

std::chrono::nanoseconds TimerBase::time_until_trigger ( )

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

Returns
A std::chrono::duration representing the relative time until the next callback or std::chrono::nanoseconds::max() if the timer is canceled.
Exceptions
std::runtime_errorif the rcl_timer_get_time_until_next_call returns a failure

Definition at line 117 of file timer.cpp.

References RCL_RET_OK, RCL_RET_TIMER_CANCELED, and rcl_timer_get_time_until_next_call().

Here is the call graph for this function:

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