3737
3838from geometry_msgs .msg import TransformStamped
3939import rclpy
40+ from rclpy .callback_groups import MutuallyExclusiveCallbackGroup
4041from rclpy .clock import JumpThreshold , TimeJump
4142from rclpy .duration import Duration
4243from rclpy .node import Node
@@ -89,6 +90,8 @@ def __init__(
8990 else :
9091 self .clock = rclpy .clock .Clock ()
9192
93+ self .node = node
94+
9295 # create a jump callback to clear the buffer if use_sim_true is true and there is a
9396 # jump in time
9497 threshold = JumpThreshold (min_forward = None ,
@@ -154,14 +157,17 @@ async def lookup_transform_async(
154157 self ,
155158 target_frame : str ,
156159 source_frame : str ,
157- time : Time
160+ time : Time ,
161+ timeout : Duration | None = None
158162 ) -> TransformStamped :
159163 """
160164 Get the transform from the source frame to the target frame asyncronously.
161165
162166 :param target_frame: Name of the frame to transform into.
163167 :param source_frame: Name of the input frame.
164168 :param time: The time at which to get the transform (0 will get the latest).
169+ :param timeout: Time to wait for the target frame to become available. Needs a Node instance
170+ to be set on the Buffer to work.
165171 :return: The transform between the frames.
166172 """
167173 return await self .wait_for_transform_async (target_frame , source_frame , time , timeout )
@@ -197,7 +203,8 @@ async def lookup_transform_full_async(
197203 target_time : Time ,
198204 source_frame : str ,
199205 source_time : Time ,
200- fixed_frame : str
206+ fixed_frame : str ,
207+ timeout : Duration | None = None
201208 ) -> TransformStamped :
202209 """
203210 Get transform from source frame to target frame using the advanced API asyncronously.
@@ -207,6 +214,8 @@ async def lookup_transform_full_async(
207214 :param source_frame: Name of the input frame.
208215 :param source_time: The time at which source_frame will be evaluated (0 gets the latest).
209216 :param fixed_frame: Name of the frame to consider constant in time.
217+ :param timeout: Time to wait for the target frame to become available. Needs a Node instance
218+ to be set on the Buffer to work.
210219 :return: The transform between the frames.
211220 """
212221 return await self .wait_for_transform_full_async (
@@ -295,22 +304,53 @@ def wait_for_transform_async(
295304 self ,
296305 target_frame : str ,
297306 source_frame : str ,
298- time : Time
307+ time : Time ,
308+ timeout : Duration | None = None
299309 ) -> Future :
300310 """
301311 Wait for a transform from the source frame to the target frame to become possible.
302312
303313 :param target_frame: Name of the frame to transform into.
304314 :param source_frame: Name of the input frame.
305315 :param time: The time at which to get the transform (0 will get the latest).
306- :return: A future that becomes true when the transform is available.
316+ :param timeout: Time to wait for the target frame to become available. Needs a Node instance
317+ to be set on the Buffer to work.
318+ :return: A future that contains the transform when it becomes available.
307319 """
308320 fut = rclpy .task .Future ()
309321 if self .can_transform_core (target_frame , source_frame , time )[0 ]:
310322 # Short cut, the transform is available
311323 fut .set_result (self .lookup_transform (target_frame , source_frame , time ))
312324 return fut
313325
326+ timeout_timer = None
327+
328+ def _on_timeout ():
329+ # Deactivate the callback to avoid memory leaks
330+ # Cancel the timer after it has triggered once
331+ timeout_timer .cancel ()
332+ # This is needed, as this function otherwise leaks resources.
333+ # timer.destroy() is not sufficient!
334+ self .node .destroy_timer (timeout_timer )
335+
336+ # The transform could be available now, so we check if the future is still pending
337+ if not fut .done ():
338+ fut .set_exception (
339+ tf2 .LookupException (
340+ f"Failed to find transform from '{ source_frame } ' to '{ target_frame } '"
341+ )
342+ )
343+
344+ # Check if a timeout is specified
345+ if timeout is not None :
346+ if self .node is None :
347+ raise RuntimeError ("Async timeouts require a Node instance to be set." )
348+
349+ timeout_timer = self .node .create_timer (
350+ timeout .nanoseconds / 1e9 , _on_timeout , clock = self .node .get_clock (),
351+ callback_group = MutuallyExclusiveCallbackGroup ()
352+ )
353+
314354 def _on_new_data ():
315355 try :
316356 if self .can_transform_core (target_frame , source_frame , time )[0 ]:
@@ -329,7 +369,8 @@ def wait_for_transform_full_async(
329369 target_time : Time ,
330370 source_frame : str ,
331371 source_time : Time ,
332- fixed_frame : str
372+ fixed_frame : str ,
373+ timeout : Duration | None = None
333374 ) -> Future :
334375 """
335376 Wait for a transform from the source frame to the target frame to become possible.
@@ -339,6 +380,8 @@ def wait_for_transform_full_async(
339380 :param source_frame: Name of the input frame.
340381 :param source_time: The time at which source_frame will be evaluated (0 gets the latest).
341382 :param fixed_frame: Name of the frame to consider constant in time.
383+ :param timeout: Time to wait for the target frame to become available. Needs a Node instance
384+ to be set on the Buffer to work.
342385 :return: A future that becomes true when the transform is available.
343386 """
344387 fut = rclpy .task .Future ()
@@ -350,6 +393,34 @@ def wait_for_transform_full_async(
350393 target_frame , target_time , source_frame , source_time , fixed_frame ))
351394 return fut
352395
396+ timeout_timer = None
397+
398+ def _on_timeout ():
399+ # Deactivate the callback to avoid memory leaks
400+ # Cancel the timer after it has triggered once
401+ timeout_timer .cancel ()
402+ # This is needed, as this function otherwise leaks resources.
403+ # timer.destroy() is not sufficient!
404+ self .node .destroy_timer (timeout_timer )
405+
406+ # The transform could be available now, so we check if the future is still pending
407+ if not fut .done ():
408+ fut .set_exception (
409+ tf2 .LookupException (
410+ f"Failed to find transform from '{ source_frame } ' to '{ target_frame } '"
411+ )
412+ )
413+
414+ # Check if a timeout is specified
415+ if timeout is not None :
416+ if self .node is None :
417+ raise RuntimeError ("Async timeouts require a Node instance to be set." )
418+
419+ timeout_timer = self .node .create_timer (
420+ timeout .nanoseconds / 1e9 , _on_timeout , clock = self .node .get_clock (),
421+ callback_group = MutuallyExclusiveCallbackGroup ()
422+ )
423+
353424 def _on_new_data ():
354425 try :
355426 if self .can_transform_full_core (
0 commit comments