tf2_ros.buffer_interface module
- class tf2_ros.buffer_interface.BufferInterface[source]
Bases:
object
Abstract interface for wrapping the Python tf2 library in a ROS convenience API.
Implementations include :class:tf2_ros.buffer.Buffer and :class:tf2_ros.buffer_client.BufferClient.
- 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.
Must be implemented by a subclass of BufferInterface.
- 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:
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.
- Returns:
True if the transform is possible, false otherwise.
- 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.
Must be implemented by a subclass of BufferInterface.
- 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.
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.
- Returns:
The transform between the frames.
- transform(object_stamped: geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, target_frame: str, timeout: rclpy.duration.Duration = rclpy.duration.Duration, new_type: TransformableObjectType | None = None) geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType [source]
Transform an input into the target frame.
The input must be a known transformable type (by way of the tf2 data type conversion interface).
If new_type is not None, the type specified must have a valid conversion from the input type, else the function will raise an exception.
- Parameters:
object_stamped – The timestamped object to transform.
target_frame – Name of the frame to transform the input into.
timeout – Time to wait for the target frame to become available.
new_type – Type to convert the object to.
- Returns:
The transformed, timestamped output, possibly converted to a new type.
- transform_full(object_stamped: geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, target_frame: str, target_time: rclpy.time.Time, fixed_frame: str, timeout: rclpy.duration.Duration = rclpy.duration.Duration, new_type: TransformableObjectType | None = None) geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType [source]
Transform an input into the target frame (advanced API).
The input must be a known transformable type (by way of the tf2 data type conversion interface).
If new_type is not None, the type specified must have a valid conversion from the input type, else the function will raise an exception.
This function follows the advanced API, which allows tranforming between different time points, as well as specifying a frame to be considered fixed in time.
- Parameters:
object_stamped – The timestamped object to transform.
target_frame – Name of the frame to transform the input into.
target_time – Time to transform the input into.
fixed_frame – Name of the frame to consider constant in time.
timeout – Time to wait for the target frame to become available.
new_type – Type to convert the object to.
- Returns:
The transformed, timestamped output, possibly converted to a new type.
- class tf2_ros.buffer_interface.ConvertRegistration[source]
Bases:
object
- add_convert(key: Tuple[TransformableObjectType, TransformableObjectType], callback: Callable[[Any], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType]) None [source]
- add_from_msg(key: TransformableObjectType, callback: Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType]) None [source]
- add_to_msg(key: TransformableObjectType, callback: Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2]) None [source]
- get_convert(key: Tuple[TransformableObjectType, TransformableObjectType]) Callable[[Any], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType] [source]
- get_from_msg(key: TransformableObjectType) Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType] [source]
- get_to_msg(key: TransformableObjectType) Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2] [source]
- exception tf2_ros.buffer_interface.NotImplementedException[source]
Bases:
Exception
The NotImplementedException class.
Raised when can_transform or lookup_transform is not implemented in a subclass of
tf2_ros.buffer_interface.BufferInterface
.
- tf2_ros.buffer_interface.Stamped(obj: geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, stamp: rclpy.time.Time, frame_id: str) geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType [source]
- class tf2_ros.buffer_interface.TransformRegistration[source]
Bases:
object
- add(key: TransformableObjectType, callback: Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, geometry_msgs.msg.TransformStamped], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType]) None [source]
- get(key: TransformableObjectType) Callable[[geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, geometry_msgs.msg.TransformStamped], geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType] [source]
- exception tf2_ros.buffer_interface.TypeException[source]
Bases:
Exception
The TypeException class.
Raised when an unexpected type is received while registering a transform in
tf2_ros.buffer_interface.BufferInterface
.
- tf2_ros.buffer_interface.convert(a: geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType, b_type: TransformableObjectType) geometry_msgs.msg.PointStamped | geometry_msgs.msg.PoseStamped | geometry_msgs.msg.PoseWithCovarianceStamped | geometry_msgs.msg.Vector3Stamped | sensor_msgs.msg.PointCloud2 | PyKDLType [source]