rclcpp  master
C++ ROS Client Library API
Public Member Functions | Protected Attributes | List of all members
rclcpp::TimerBase Class Referenceabstract

#include <timer.hpp>

Inheritance diagram for rclcpp::TimerBase:
rclcpp::GenericTimer< FunctorT, Clock, std::enable_if<(rclcpp::function_traits::same_arguments< FunctorT, VoidCallbackType >::value||rclcpp::function_traits::same_arguments< FunctorT, TimerCallbackType >::value) &&Clock::is_steady >::type * >

Public Member Functions

 TimerBase (std::chrono::nanoseconds period)
 
 ~TimerBase ()
 
void cancel ()
 
void reset ()
 
virtual void execute_callback ()=0
 
const rcl_timer_tget_timer_handle ()
 
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...
 
bool is_ready ()
 Check if the timer is ready to trigger the callback. More...
 

Protected Attributes

rcl_timer_t timer_handle_ = rcl_get_zero_initialized_timer()
 

Constructor & Destructor Documentation

◆ TimerBase()

rclcpp::TimerBase::TimerBase ( std::chrono::nanoseconds  period)
explicit

◆ ~TimerBase()

rclcpp::TimerBase::~TimerBase ( )

Member Function Documentation

◆ cancel()

void rclcpp::TimerBase::cancel ( )

◆ reset()

void rclcpp::TimerBase::reset ( )

◆ execute_callback()

virtual void rclcpp::TimerBase::execute_callback ( )
pure virtual

◆ get_timer_handle()

const rcl_timer_t* rclcpp::TimerBase::get_timer_handle ( )

◆ time_until_trigger()

std::chrono::nanoseconds rclcpp::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.

◆ is_steady()

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

◆ is_ready()

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

Member Data Documentation

◆ timer_handle_

rcl_timer_t rclcpp::TimerBase::timer_handle_ = rcl_get_zero_initialized_timer()
protected

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