Skip to content

Commit 2c15d17

Browse files
committed
Remove unnecessary double computation of transform
Signed-off-by: Florian Vahl <[email protected]>
1 parent bbc69c7 commit 2c15d17

File tree

1 file changed

+3
-6
lines changed

1 file changed

+3
-6
lines changed

tf2_ros_py/tf2_ros/buffer.py

Lines changed: 3 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -164,8 +164,7 @@ async def lookup_transform_async(
164164
:param time: The time at which to get the transform (0 will get the latest).
165165
:return: The transform between the frames.
166166
"""
167-
await self.wait_for_transform_async(target_frame, source_frame, time)
168-
return self.lookup_transform_core(target_frame, source_frame, time)
167+
return await self.wait_for_transform_async(target_frame, source_frame, time, timeout)
169168

170169
def lookup_transform_full(
171170
self,
@@ -210,10 +209,8 @@ async def lookup_transform_full_async(
210209
:param fixed_frame: Name of the frame to consider constant in time.
211210
:return: The transform between the frames.
212211
"""
213-
await self.wait_for_transform_full_async(
214-
target_frame, target_time, source_frame, source_time, fixed_frame)
215-
return self.lookup_transform_full_core(
216-
target_frame, target_time, source_frame, source_time, fixed_frame)
212+
return await self.wait_for_transform_full_async(
213+
target_frame, target_time, source_frame, source_time, fixed_frame, timeout)
217214

218215
def can_transform(
219216
self,

0 commit comments

Comments
 (0)