| tf2_ros
    master
    This package contains the ROS bindings for the tf2 library, for both Python and C++. | 
Create and manage ROS timers. More...
#include <create_timer_ros.h>


| Public Member Functions | |
| TF2_ROS_PUBLIC | CreateTimerROS (rclcpp::node_interfaces::NodeBaseInterface::SharedPtr node_base, rclcpp::node_interfaces::NodeTimersInterface::SharedPtr node_timers) | 
| virtual | ~CreateTimerROS ()=default | 
| virtual TF2_ROS_PUBLIC TimerHandle | createTimer (rclcpp::Clock::SharedPtr clock, const tf2::Duration &period, TimerCallbackType callback) override | 
| Create a new timer.  More... | |
| virtual TF2_ROS_PUBLIC void | cancel (const TimerHandle &timer_handle) override | 
| Cancel a timer.  More... | |
| virtual TF2_ROS_PUBLIC void | reset (const TimerHandle &timer_handle) override | 
| Reset the timer.  More... | |
| virtual TF2_ROS_PUBLIC void | remove (const TimerHandle &timer_handle) override | 
| Remove a timer.  More... | |
|  Public Member Functions inherited from tf2_ros::CreateTimerInterface | |
| virtual TF2_ROS_PUBLIC | ~CreateTimerInterface ()=default | 
| Additional Inherited Members | |
|  Public Types inherited from tf2_ros::CreateTimerInterface | |
| using | SharedPtr = std::shared_ptr< CreateTimerInterface > | 
| using | ConstSharedPtr = std::shared_ptr< const CreateTimerInterface > | 
| using | UniquePtr = std::unique_ptr< CreateTimerInterface > | 
Create and manage ROS timers.
This class is thread safe.
| TF2_ROS_PUBLIC tf2_ros::CreateTimerROS::CreateTimerROS | ( | rclcpp::node_interfaces::NodeBaseInterface::SharedPtr | node_base, | 
| rclcpp::node_interfaces::NodeTimersInterface::SharedPtr | node_timers | ||
| ) | 
| 
 | virtualdefault | 
| 
 | overridevirtual | 
Create a new timer.
After creation, the timer will periodically execute the user-provided callback.
| clock | The clock providing the current time | 
| period | The interval at which the timer fires | 
| callback | The callback function to execute every interval | 
Implements tf2_ros::CreateTimerInterface.
| 
 | overridevirtual | 
Cancel a timer.
The timer will stop executing user callbacks.
| timer_handle | Handle to the timer to cancel \raises tf2_ros::InvalidTimerHandleException if the timer does not exist | 
Implements tf2_ros::CreateTimerInterface.
| 
 | overridevirtual | 
Reset the timer.
The timer will reset and continue to execute user callbacks periodically.
| timer_handle | Handle to the timer to reset \raises tf2_ros::InvalidTimerHandleException if the timer does not exist | 
Implements tf2_ros::CreateTimerInterface.
| 
 | overridevirtual | 
Remove a timer.
The timer will be canceled and removed from internal storage.
| timer_handle | Handle to the timer to reset. \raises tf2_ros::InvalidTimerHandleException if the timer does not exist | 
Implements tf2_ros::CreateTimerInterface.
 1.8.17
 1.8.17