Class Buffer

Inheritance Relationships

Base Types

Class Documentation

class Buffer : public tf2_ros::BufferInterface, public tf2_ros::AsyncBufferInterface, public tf2::BufferCore

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.

Public Types

using SharedPtr = std::shared_ptr<tf2_ros::Buffer>

Public Functions

template<typename NodeT = rclcpp::Node::SharedPtr>
inline Buffer(rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), NodeT &&node = NodeT(), const rclcpp::QoS &qos = rclcpp::ServicesQoS())

Constructor for a Buffer object.

Parameters:
  • clock – A clock to use for time and sleeping

  • cache_time – How long to keep a history of transforms

  • node – If passed advertise the view_frames service that exposes debugging information from the buffer

  • qos – If passed change the quality of service of the frames_server_ service

virtual 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.

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

Parameters:
  • target_frame – The frame to which data should be transformed

  • source_frame – The frame where the data originated

  • time – The time at which the value of the transform is desired. (0 will get the latest)

  • timeout – How long to block before failing

Returns:

The transform between the frames

inline 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.

See also

lookupTransform(const std::string&, const std::string&, const tf2::TimePoint&,

const tf2::Duration)

virtual 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.

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

Parameters:
  • target_frame – The frame to which data should be transformed

  • target_time – The time to which the data should be transformed. (0 will get the latest)

  • source_frame – The frame where the data originated

  • source_time – The time at which the source_frame should be evaluated. (0 will get the latest)

  • fixed_frame – The frame in which to assume the transform is constant in time.

  • timeout – How long to block before failing

Returns:

The transform between the frames

inline 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.

See also

lookupTransform(const std::string&, const tf2::TimePoint&,

const std::string&, const tf2::TimePoint&,

const std::string&, const tf2::Duration)

virtual 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.

Parameters:
  • target_frame – The frame into which to transform

  • source_frame – The frame from which to transform

  • target_time – The time at which to transform

  • timeout – How long to block before failing

  • errstr – A 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

inline 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.

See also

canTransform(const std::string&, const std::string&,

const tf2::TimePoint&, const tf2::Duration, std::string*)

virtual 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.

Parameters:
  • target_frame – The frame into which to transform

  • target_time – The time into which to transform

  • source_frame – The frame from which to transform

  • source_time – The time from which to transform

  • fixed_frame – The frame in which to treat the transform as constant in time

  • timeout – How long to block before failing

  • errstr – A 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

inline 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.

See also

canTransform(const std::string&, const tf2::TimePoint&,

const std::string&, const tf2::TimePoint&,

const std::string&, const tf2::Duration, std::string*)

virtual 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.

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_frame – The frame into which to transform.

  • source_frame – The frame from which to tranform.

  • time – The time at which to transform.

  • timeout – Duration after which waiting will be stopped.

  • callback – The 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.

inline 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.

virtual TF2_ROS_PUBLIC void cancel (const TransformStampedFuture &ts_future) override

Cancel the future to make sure the callback of requested transform is clean.

Parameters:

ts_future – The future to the requested transform.

inline TF2_ROS_PUBLIC void setCreateTimerInterface (CreateTimerInterface::SharedPtr create_timer_interface)