Skip to content

Commit

Permalink
Transform Data Callback Python (#664)
Browse files Browse the repository at this point in the history
Signed-off-by: CursedRock17 <[email protected]>
  • Loading branch information
CursedRock17 authored Apr 4, 2024
1 parent 4fd450d commit 0ea2ad3
Showing 1 changed file with 10 additions and 8 deletions.
18 changes: 10 additions & 8 deletions tf2_ros_py/tf2_ros/buffer.py
Original file line number Diff line number Diff line change
Expand Up @@ -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,
Expand All @@ -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,
Expand All @@ -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():
Expand Down Expand Up @@ -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():
Expand Down Expand Up @@ -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)

Expand Down Expand Up @@ -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)

Expand Down

0 comments on commit 0ea2ad3

Please sign in to comment.