From 0ea2ad3ee99d2e3ffcb1f04286d22edfeffb2e1c Mon Sep 17 00:00:00 2001 From: Lucas Wendland <82680922+CursedRock17@users.noreply.github.com> Date: Thu, 4 Apr 2024 03:55:51 -0400 Subject: [PATCH] Transform Data Callback Python (#664) Signed-off-by: CursedRock17 --- tf2_ros_py/tf2_ros/buffer.py | 18 ++++++++++-------- 1 file changed, 10 insertions(+), 8 deletions(-) diff --git a/tf2_ros_py/tf2_ros/buffer.py b/tf2_ros_py/tf2_ros/buffer.py index e3893f0ea..f40463fcd 100644 --- a/tf2_ros_py/tf2_ros/buffer.py +++ b/tf2_ros_py/tf2_ros/buffer.py @@ -187,7 +187,8 @@ def lookup_transform_full( :return: The transform between the frames. """ self.can_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout) - return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame) + return self.lookup_transform_full_core( + target_frame, target_time, source_frame, source_time, fixed_frame) async def lookup_transform_full_async( self, @@ -208,7 +209,8 @@ async def lookup_transform_full_async( :return: The transform between the frames. """ await self.wait_for_transform_full_async(target_frame, target_time, source_frame, source_time, fixed_frame) - return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame) + return self.lookup_transform_full_core( + target_frame, target_time, source_frame, source_time, fixed_frame) def can_transform( self, @@ -226,7 +228,7 @@ def can_transform( :param time: The time at which to get the transform (0 will get the latest). :param timeout: Time to wait for the target frame to become available. :param return_debug_type: If true, return a tuple representing debug information. - :return: True if the transform is possible, false otherwise. + :return: The information of the transform being waited on. """ clock = rclpy.clock.Clock() if timeout != Duration(): @@ -267,7 +269,7 @@ def can_transform_full( :param fixed_frame: Name of the frame to consider constant in time. :param timeout: Time to wait for the target frame to become available. :param return_debug_type: If true, return a tuple representing debug information. - :return: True if the transform is possible, false otherwise. + :return: The information of the transform being waited on. """ clock = rclpy.clock.Clock() if timeout != Duration(): @@ -302,13 +304,13 @@ def wait_for_transform_async( fut = rclpy.task.Future() if self.can_transform_core(target_frame, source_frame, time)[0]: # Short cut, the transform is available - fut.set_result(True) + fut.set_result(self.lookup_transform(target_frame, source_frame, time)) return fut def _on_new_data(): try: if self.can_transform_core(target_frame, source_frame, time)[0]: - fut.set_result(True) + fut.set_result(self.lookup_transform(target_frame, source_frame, time)) except BaseException as e: fut.set_exception(e) @@ -338,13 +340,13 @@ def wait_for_transform_full_async( fut = rclpy.task.Future() if self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0]: # Short cut, the transform is available - fut.set_result(True) + fut.set_result(self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)) return fut def _on_new_data(): try: if self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0]: - fut.set_result(True) + fut.set_result(self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)) except BaseException as e: fut.set_exception(e)