tf2_ros.buffer_client module

class tf2_ros.buffer_client.BufferClient[source]

Bases: BufferInterface

Action client-based implementation of BufferInterface.

__init__(node: rclpy.node.Node, ns: str, check_frequency: float = 10.0, timeout_padding: rclpy.duration.Duration = rclpy.duration.Duration) None[source]

Construct a BufferClient.

Parameters:
  • node – The ROS 2 node.

  • ns – The namespace in which to look for a BufferServer.

  • check_frequency – How frequently to check for updates to known transforms.

  • timeout_padding – A constant timeout to add to blocking calls.

can_transform(target_frame: str, source_frame: str, time: rclpy.time.Time, timeout: rclpy.duration.Duration = rclpy.duration.Duration) bool[source]

Check if a transform from the source frame to the target frame is possible.

Parameters:
  • target_frame – Name of the frame to transform into.

  • source_frame – Name of the input frame.

  • time – The time at which to get the transform. (0 will get the latest)

  • timeout – Time to wait for the target frame to become available.

  • return_debug_type – If true, return a tuple representing debug information.

Returns:

True if the transform is possible, false otherwise.

can_transform_full(target_frame: str, target_time: rclpy.time.Time, source_frame: str, source_time: rclpy.time.Time, fixed_frame: str, timeout: rclpy.duration.Duration = rclpy.duration.Duration) bool[source]

Check if a transform from the source frame to the target frame is possible (advanced API).

Must be implemented by a subclass of BufferInterface.

Parameters:
  • target_frame – Name of the frame to transform into.

  • target_time – The time to transform to. (0 will get the latest)

  • source_frame – Name of the input frame.

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

  • fixed_frame – Name of the frame to consider constant in time.

  • timeout – Time to wait for the target frame to become available.

  • return_debug_type – If true, return a tuple representing debug information.

Returns:

True if the transform is possible, false otherwise.

destroy() None[source]

Cleanup resources associated with this BufferClient.

lookup_transform(target_frame: str, source_frame: str, time: rclpy.time.Time, timeout: rclpy.duration.Duration = rclpy.duration.Duration) geometry_msgs.msg.TransformStamped[source]

Get the transform from the source frame to the target frame.

Parameters:
  • target_frame – Name of the frame to transform into.

  • source_frame – Name of the input frame.

  • time – The time at which to get the transform (0 will get the latest).

  • timeout – Time to wait for the target frame to become available.

Returns:

The transform between the frames.

lookup_transform_full(target_frame: str, target_time: rclpy.time.Time, source_frame: str, source_time: rclpy.time.Time, fixed_frame: str, timeout: rclpy.duration.Duration = rclpy.duration.Duration) geometry_msgs.msg.TransformStamped[source]

Get the transform from the source frame to the target frame using the advanced API.

Parameters:
  • target_frame – Name of the frame to transform into.

  • target_time – The time to transform to. (0 will get the latest)

  • source_frame – Name of the input frame.

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

  • fixed_frame – Name of the frame to consider constant in time.

  • timeout – Time to wait for the target frame to become available.

Returns:

The transform between the frames.