Class Buffer

Inheritance Relationships

Base Types

  • public tf2::BufferCore

  • public tf2_ros::BufferInterface

Class Documentation

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

Warning

This is NOT a drop-in replacement for tf2_ros::Buffer. The following tf2_ros::Buffer features are intentionally omitted:

  • AsyncBufferInterface (waitForTransform, cancel, setCreateTimerInterface)

  • The “tf2_frames” debug service (getFrames)

Public Types

using SharedPtr = std::shared_ptr<Buffer>

Public Functions

template<typename NodeT = std::shared_ptr<agnocast::Node>>
inline Buffer(rclcpp::Clock::SharedPtr clock, tf2::Duration cache_time = tf2::Duration(tf2::BUFFER_CORE_DEFAULT_CACHE_TIME), NodeT &&node = NodeT())

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, the buffer will use this node’s logger instead of the default

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 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)

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 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)

bool canTransform(const std::string &target_frame, const std::string &source_frame, const tf2::TimePoint &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 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*)

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 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*)

inline rclcpp::Clock::SharedPtr getClock() const

Get the clock used by this buffer.