Class CreateTimerROS
Defined in File create_timer_ros.h
Inheritance Relationships
Base Type
public tf2_ros::CreateTimerInterface
(Class CreateTimerInterface)
Class Documentation
-
class CreateTimerROS : public tf2_ros::CreateTimerInterface
Create and manage ROS timers.
This class is thread safe.
Public Functions
-
virtual ~CreateTimerROS() = default
- virtual TF2_ROS_PUBLIC TimerHandle createTimer (rclcpp::Clock::SharedPtr clock, const tf2::Duration &period, TimerCallbackType callback) override
Create a new timer.
After creation, the timer will periodically execute the user-provided callback.
- Parameters:
clock – The clock providing the current time
period – The interval at which the timer fires
callback – The callback function to execute every interval
- virtual TF2_ROS_PUBLIC void cancel (const TimerHandle &timer_handle) override
Cancel a timer.
The timer will stop executing user callbacks.
- Parameters:
timer_handle – Handle to the timer to cancel \raises tf2_ros::InvalidTimerHandleException if the timer does not exist
- virtual TF2_ROS_PUBLIC void reset (const TimerHandle &timer_handle) override
Reset the timer.
The timer will reset and continue to execute user callbacks periodically.
- Parameters:
timer_handle – Handle to the timer to reset \raises tf2_ros::InvalidTimerHandleException if the timer does not exist
- virtual TF2_ROS_PUBLIC void remove (const TimerHandle &timer_handle) override
Remove a timer.
The timer will be canceled and removed from internal storage.
- Parameters:
timer_handle – Handle to the timer to reset. \raises tf2_ros::InvalidTimerHandleException if the timer does not exist
-
virtual ~CreateTimerROS() = default