tf2_ros.buffer module
- class tf2_ros.buffer.Buffer[source]
Bases:
BufferCore
,BufferInterface
Standard implementation of the
tf2_ros.BufferInterface
abstract data type.Inherits from
tf2_ros.buffer_interface.BufferInterface
andtf2.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.- __init__(cache_time: rclpy.duration.Duration | None = None, node: rclpy.node.Node | None = None) None [source]
Constructor.
- Parameters:
cache_time – Duration object describing how long to retain past information in BufferCore.
node – Create a tf2_frames service that returns all frames as a yaml document.
- can_transform(target_frame: str, source_frame: str, time: rclpy.time.Time, timeout: rclpy.duration.Duration = rclpy.duration.Duration, return_debug_tuple: bool = False) 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:
The information of the transform being waited on.
- 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, return_debug_tuple: bool = False) 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 will get 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:
The information of the transform being waited on.
- 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.
- async lookup_transform_async(target_frame: str, source_frame: str, time: rclpy.time.Time) geometry_msgs.msg.TransformStamped [source]
Get the transform from the source frame to the target frame asyncronously.
- 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).
- 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 will get 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.
- async lookup_transform_full_async(target_frame: str, target_time: rclpy.time.Time, source_frame: str, source_time: rclpy.time.Time, fixed_frame: str) geometry_msgs.msg.TransformStamped [source]
Get the transform from the source frame to the target frame using the advanced API asyncronously.
- 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 will get the latest).
fixed_frame – Name of the frame to consider constant in time.
- Returns:
The transform between the frames.
- wait_for_transform_async(target_frame: str, source_frame: str, time: rclpy.time.Time) rclpy.task.Future [source]
Wait for a transform from the source frame to the target frame to become 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).
- Returns:
A future that becomes true when the transform is available.
- wait_for_transform_full_async(target_frame: str, target_time: rclpy.time.Time, source_frame: str, source_time: rclpy.time.Time, fixed_frame: str) rclpy.task.Future [source]
Wait for a transform from the source frame to the target frame to become possible.
- 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 will get the latest).
fixed_frame – Name of the frame to consider constant in time.
- Returns:
A future that becomes true when the transform is available.