Class AsyncBufferInterface

Inheritance Relationships

Derived Type

Class Documentation

class AsyncBufferInterface

Abstract interface for asynchronous operations on a tf2::BufferCoreInterface. Implementations include tf2_ros::Buffer.

Subclassed by tf2_ros::Buffer

Public Functions

virtual TF2_ROS_PUBLIC ~AsyncBufferInterface() = default
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)=0

Wait for a transform between two frames to become available.

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.

virtual void cancel(const TransformStampedFuture &ts_future) = 0

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

Parameters:

ts_future – The future to the requested transform.