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::Buffer Class Reference

Standard implementation of the tf2_ros::BufferInterface abstract data type. More...

#include <buffer.h>

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

Public Member Functions

TF2_ROS_PUBLIC Buffer (rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time=tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), rclcpp::Node::SharedPtr node=rclcpp::Node::SharedPtr())
 Constructor for a Buffer object. More...
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration timeout) const override
 Get the transform between two frames by frame ID. More...
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration timeout=rclcpp::Duration::from_nanoseconds(0)) const
 Get the transform between two frames by frame ID. More...
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame, const tf2::Duration timeout) const override
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped lookupTransform (const std::string &target_frame, const rclcpp::Time &target_time, const std::string &source_frame, const rclcpp::Time &source_time, const std::string &fixed_frame, const rclcpp::Duration timeout=rclcpp::Duration::from_nanoseconds(0)) const
 Get the transform between two frames by frame ID assuming fixed frame. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &target_time, const tf2::Duration timeout, std::string *errstr=NULL) const override
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration timeout=rclcpp::Duration::from_nanoseconds(0), std::string *errstr=NULL) const
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &source_frame, const tf2::TimePoint &source_time, const std::string &fixed_frame, const tf2::Duration timeout, std::string *errstr=NULL) const override
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC bool canTransform (const std::string &target_frame, const rclcpp::Time &target_time, const std::string &source_frame, const rclcpp::Time &source_time, const std::string &fixed_frame, const rclcpp::Duration timeout=rclcpp::Duration::from_nanoseconds(0), std::string *errstr=NULL) const
 Test if a transform is possible. More...
 
TF2_ROS_PUBLIC TransformStampedFuture waitForTransform (const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &time, const tf2::Duration &timeout, TransformReadyCallback callback) override
 Wait for a transform between two frames to become available. More...
 
TF2_ROS_PUBLIC TransformStampedFuture waitForTransform (const std::string &target_frame, const std::string &source_frame, const rclcpp::Time &time, const rclcpp::Duration &timeout, TransformReadyCallback callback)
 Wait for a transform between two frames to become available. More...
 
TF2_ROS_PUBLIC void setCreateTimerInterface (CreateTimerInterface::SharedPtr create_timer_interface)
 
- Public Member Functions inherited from tf2_ros::BufferInterface
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
template<class T >
transform (const T &in, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame. This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). More...
 
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame and convert to a specified output type. It is templated on two types: the type of the input object and the type of the transformed output. For example, the template types could be Transform, Pose, Vector, or Quaternion messages type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. More...
 
template<class T >
T & transform (const T &in, T &out, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class T >
transform (const T &in, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame (advanced). This function is templated and can take as input any valid mathematical object that tf knows how to apply a transform to, by way of the templated math conversions interface. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
template<class A , class B >
B & transform (const A &in, B &out, const std::string &target_frame, const tf2::TimePoint &target_time, const std::string &fixed_frame, tf2::Duration timeout=tf2::durationFromSec(0.0)) const
 Transform an input into the target frame and convert to a specified output type (advanced). It is templated on two types: the type of the input object and the type of the transformed output. For example, the template type could be a Transform, Pose, Vector, or Quaternion message type (as defined in geometry_msgs). The function will calculate the transformation and then convert the result into the specified output type. Compilation will fail if a known conversion does not exist bewteen the two template parameters. This function follows the advanced API, which allows transforming between different time points, and specifying a fixed frame that does not varying in time. More...
 
virtual ~BufferInterface ()
 
- Public Member Functions inherited from tf2_ros::AsyncBufferInterface
virtual TF2_ROS_PUBLIC ~AsyncBufferInterface ()=default
 

Detailed Description

Standard implementation of the tf2_ros::BufferInterface abstract data type.

Inherits tf2_ros::BufferInterface and tf2::BufferCore. Stores known frames and offers a ROS service, "tf_frames", which responds to client requests with a response containing a tf2_msgs::FrameGraph representing the relationship of known frames.

Constructor & Destructor Documentation

◆ Buffer()

TF2_ROS_PUBLIC tf2_ros::Buffer::Buffer ( rclcpp::Clock::SharedPtr  clock,
tf2::Duration  cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME),
rclcpp::Node::SharedPtr  node = rclcpp::Node::SharedPtr() 
)

Constructor for a Buffer object.

Parameters
clockA clock to use for time and sleeping
cache_timeHow long to keep a history of transforms
nodeIf passed advertise the view_frames service that exposes debugging information from the buffer

Member Function Documentation

◆ lookupTransform() [1/4]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::Buffer::lookupTransform ( const std::string target_frame,
const std::string source_frame,
const tf2::TimePoint &  time,
const tf2::Duration  timeout 
) const
overridevirtual

Get the transform between two frames by frame ID.

Parameters
target_frameThe frame to which data should be transformed
source_frameThe frame where the data originated
timeThe time at which the value of the transform is desired. (0 will get the latest)
timeoutHow long to block before failing
Returns
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Implements tf2_ros::BufferInterface.

◆ lookupTransform() [2/4]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::Buffer::lookupTransform ( const std::string target_frame,
const std::string source_frame,
const rclcpp::Time &  time,
const rclcpp::Duration  timeout = rclcpp::Duration::from_nanoseconds(0) 
) const
inline

Get the transform between two frames by frame ID.

See also
lookupTransform(const std::string&, const std::string&, const tf2::TimePoint&, const tf2::Duration)

◆ lookupTransform() [3/4]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::Buffer::lookupTransform ( const std::string target_frame,
const tf2::TimePoint &  target_time,
const std::string source_frame,
const tf2::TimePoint &  source_time,
const std::string fixed_frame,
const tf2::Duration  timeout 
) const
overridevirtual

Get the transform between two frames by frame ID assuming fixed frame.

Parameters
target_frameThe frame to which data should be transformed
target_timeThe time to which the data should be transformed. (0 will get the latest)
source_frameThe frame where the data originated
source_timeThe time at which the source_frame should be evaluated. (0 will get the latest)
fixed_frameThe frame in which to assume the transform is constant in time.
timeoutHow long to block before failing
Returns
The transform between the frames

Possible exceptions tf2::LookupException, tf2::ConnectivityException, tf2::ExtrapolationException, tf2::InvalidArgumentException

Implements tf2_ros::BufferInterface.

◆ lookupTransform() [4/4]

TF2_ROS_PUBLIC geometry_msgs::msg::TransformStamped tf2_ros::Buffer::lookupTransform ( const std::string target_frame,
const rclcpp::Time &  target_time,
const std::string source_frame,
const rclcpp::Time &  source_time,
const std::string fixed_frame,
const rclcpp::Duration  timeout = rclcpp::Duration::from_nanoseconds(0) 
) const
inline

Get the transform between two frames by frame ID assuming fixed frame.

See also
lookupTransform(const std::string&, const tf2::TimePoint&, const std::string&, const tf2::TimePoint&, const std::string&, const tf2::Duration)

◆ canTransform() [1/4]

TF2_ROS_PUBLIC bool tf2_ros::Buffer::canTransform ( const std::string target_frame,
const std::string source_frame,
const tf2::TimePoint &  target_time,
const tf2::Duration  timeout,
std::string errstr = NULL 
) const
overridevirtual

Test if a transform is possible.

Parameters
target_frameThe frame into which to transform
source_frameThe frame from which to transform
target_timeThe time at which to transform
timeoutHow long to block before failing
errstrA pointer to a string which will be filled with why the transform failed, if not NULL
Returns
True if the transform is possible, false otherwise

Implements tf2_ros::BufferInterface.

◆ canTransform() [2/4]

TF2_ROS_PUBLIC bool tf2_ros::Buffer::canTransform ( const std::string target_frame,
const std::string source_frame,
const rclcpp::Time &  time,
const rclcpp::Duration  timeout = rclcpp::Duration::from_nanoseconds(0),
std::string errstr = NULL 
) const
inline

Test if a transform is possible.

See also
canTransform(const std::string&, const std::string&, const tf2::TimePoint&, const tf2::Duration, std::string*)

◆ canTransform() [3/4]

TF2_ROS_PUBLIC bool tf2_ros::Buffer::canTransform ( const std::string target_frame,
const tf2::TimePoint &  target_time,
const std::string source_frame,
const tf2::TimePoint &  source_time,
const std::string fixed_frame,
const tf2::Duration  timeout,
std::string errstr = NULL 
) const
overridevirtual

Test if a transform is possible.

Parameters
target_frameThe frame into which to transform
target_timeThe time into which to transform
source_frameThe frame from which to transform
source_timeThe time from which to transform
fixed_frameThe frame in which to treat the transform as constant in time
timeoutHow long to block before failing
errstrA pointer to a string which will be filled with why the transform failed, if not NULL
Returns
True if the transform is possible, false otherwise

Implements tf2_ros::BufferInterface.

◆ canTransform() [4/4]

TF2_ROS_PUBLIC bool tf2_ros::Buffer::canTransform ( const std::string target_frame,
const rclcpp::Time &  target_time,
const std::string source_frame,
const rclcpp::Time &  source_time,
const std::string fixed_frame,
const rclcpp::Duration  timeout = rclcpp::Duration::from_nanoseconds(0),
std::string errstr = NULL 
) const
inline

Test if a transform is possible.

See also
canTransform(const std::string&, const tf2::TimePoint&, const std::string&, const tf2::TimePoint&, const std::string&, const tf2::Duration, std::string*)

◆ waitForTransform() [1/2]

TF2_ROS_PUBLIC TransformStampedFuture tf2_ros::Buffer::waitForTransform ( const std::string target_frame,
const std::string source_frame,
const tf2::TimePoint &  time,
const tf2::Duration &  timeout,
TransformReadyCallback  callback 
)
overridevirtual

Wait for a transform between two frames to become available.

Before this method can be called, a tf2_ros::CreateTimerInterface must be registered by first calling setCreateTimerInterface. If no tf2_ros::CreateTimerInterface is set, then a tf2_ros::CreateTimerInterfaceException is thrown.

Parameters
target_frameThe frame into which to transform.
source_frameThe frame from which to tranform.
timeThe time at which to transform.
timeoutDuration after which waiting will be stopped.
callbackThe function to be called when the transform becomes available or a timeout occurs. In the case of timeout, an exception will be set on the future.
Returns
A future to the requested transform. If a timeout occurs a tf2::LookupException will be set on the future.

Implements tf2_ros::AsyncBufferInterface.

◆ waitForTransform() [2/2]

TF2_ROS_PUBLIC TransformStampedFuture tf2_ros::Buffer::waitForTransform ( const std::string target_frame,
const std::string source_frame,
const rclcpp::Time &  time,
const rclcpp::Duration &  timeout,
TransformReadyCallback  callback 
)
inline

Wait for a transform between two frames to become available.

See also
waitForTransform(const std::string &, const std::string &, const tf2::TimePoint &, const tf2::Duration &, TransformReadyCallback);

◆ setCreateTimerInterface()

TF2_ROS_PUBLIC void tf2_ros::Buffer::setCreateTimerInterface ( CreateTimerInterface::SharedPtr  create_timer_interface)
inline

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