tf2_ros  master
This package contains the ROS bindings for the tf2 library, for both Python and C++.
Public Member Functions | List of all members
tf2_ros::CreateTimerROS Class Reference

Create and manage ROS timers. More...

#include <create_timer_ros.h>

Inheritance diagram for tf2_ros::CreateTimerROS:
Inheritance graph
[legend]
Collaboration diagram for tf2_ros::CreateTimerROS:
Collaboration graph
[legend]

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 >
 

Detailed Description

Create and manage ROS timers.

This class is thread safe.

Constructor & Destructor Documentation

◆ CreateTimerROS()

TF2_ROS_PUBLIC tf2_ros::CreateTimerROS::CreateTimerROS ( rclcpp::node_interfaces::NodeBaseInterface::SharedPtr  node_base,
rclcpp::node_interfaces::NodeTimersInterface::SharedPtr  node_timers 
)

◆ ~CreateTimerROS()

virtual tf2_ros::CreateTimerROS::~CreateTimerROS ( )
virtualdefault

Member Function Documentation

◆ createTimer()

virtual TF2_ROS_PUBLIC TimerHandle tf2_ros::CreateTimerROS::createTimer ( rclcpp::Clock::SharedPtr  clock,
const tf2::Duration &  period,
TimerCallbackType  callback 
)
overridevirtual

Create a new timer.

After creation, the timer will periodically execute the user-provided callback.

Parameters
clockThe clock providing the current time
periodThe interval at which the timer fires
callbackThe callback function to execute every interval

Implements tf2_ros::CreateTimerInterface.

◆ cancel()

virtual TF2_ROS_PUBLIC void tf2_ros::CreateTimerROS::cancel ( const TimerHandle timer_handle)
overridevirtual

Cancel a timer.

The timer will stop executing user callbacks.

Parameters
timer_handleHandle to the timer to cancel \raises tf2_ros::InvalidTimerHandleException if the timer does not exist

Implements tf2_ros::CreateTimerInterface.

◆ reset()

virtual TF2_ROS_PUBLIC void tf2_ros::CreateTimerROS::reset ( const TimerHandle timer_handle)
overridevirtual

Reset the timer.

The timer will reset and continue to execute user callbacks periodically.

Parameters
timer_handleHandle to the timer to reset \raises tf2_ros::InvalidTimerHandleException if the timer does not exist

Implements tf2_ros::CreateTimerInterface.

◆ remove()

virtual TF2_ROS_PUBLIC void tf2_ros::CreateTimerROS::remove ( const TimerHandle timer_handle)
overridevirtual

Remove a timer.

The timer will be canceled and removed from internal storage.

Parameters
timer_handleHandle to the timer to reset. \raises tf2_ros::InvalidTimerHandleException if the timer does not exist

Implements tf2_ros::CreateTimerInterface.


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