Skip to content

Commit 0ea2ad3

Browse files
authored
Transform Data Callback Python (#664)
Signed-off-by: CursedRock17 <[email protected]>
1 parent 4fd450d commit 0ea2ad3

File tree

1 file changed

+10
-8
lines changed

1 file changed

+10
-8
lines changed

tf2_ros_py/tf2_ros/buffer.py

Lines changed: 10 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -187,7 +187,8 @@ def lookup_transform_full(
187187
:return: The transform between the frames.
188188
"""
189189
self.can_transform_full(target_frame, target_time, source_frame, source_time, fixed_frame, timeout)
190-
return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)
190+
return self.lookup_transform_full_core(
191+
target_frame, target_time, source_frame, source_time, fixed_frame)
191192

192193
async def lookup_transform_full_async(
193194
self,
@@ -208,7 +209,8 @@ async def lookup_transform_full_async(
208209
:return: The transform between the frames.
209210
"""
210211
await self.wait_for_transform_full_async(target_frame, target_time, source_frame, source_time, fixed_frame)
211-
return self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)
212+
return self.lookup_transform_full_core(
213+
target_frame, target_time, source_frame, source_time, fixed_frame)
212214

213215
def can_transform(
214216
self,
@@ -226,7 +228,7 @@ def can_transform(
226228
:param time: The time at which to get the transform (0 will get the latest).
227229
:param timeout: Time to wait for the target frame to become available.
228230
:param return_debug_type: If true, return a tuple representing debug information.
229-
:return: True if the transform is possible, false otherwise.
231+
:return: The information of the transform being waited on.
230232
"""
231233
clock = rclpy.clock.Clock()
232234
if timeout != Duration():
@@ -267,7 +269,7 @@ def can_transform_full(
267269
:param fixed_frame: Name of the frame to consider constant in time.
268270
:param timeout: Time to wait for the target frame to become available.
269271
:param return_debug_type: If true, return a tuple representing debug information.
270-
:return: True if the transform is possible, false otherwise.
272+
:return: The information of the transform being waited on.
271273
"""
272274
clock = rclpy.clock.Clock()
273275
if timeout != Duration():
@@ -302,13 +304,13 @@ def wait_for_transform_async(
302304
fut = rclpy.task.Future()
303305
if self.can_transform_core(target_frame, source_frame, time)[0]:
304306
# Short cut, the transform is available
305-
fut.set_result(True)
307+
fut.set_result(self.lookup_transform(target_frame, source_frame, time))
306308
return fut
307309

308310
def _on_new_data():
309311
try:
310312
if self.can_transform_core(target_frame, source_frame, time)[0]:
311-
fut.set_result(True)
313+
fut.set_result(self.lookup_transform(target_frame, source_frame, time))
312314
except BaseException as e:
313315
fut.set_exception(e)
314316

@@ -338,13 +340,13 @@ def wait_for_transform_full_async(
338340
fut = rclpy.task.Future()
339341
if self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0]:
340342
# Short cut, the transform is available
341-
fut.set_result(True)
343+
fut.set_result(self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame))
342344
return fut
343345

344346
def _on_new_data():
345347
try:
346348
if self.can_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame)[0]:
347-
fut.set_result(True)
349+
fut.set_result(self.lookup_transform_full_core(target_frame, target_time, source_frame, source_time, fixed_frame))
348350
except BaseException as e:
349351
fut.set_exception(e)
350352

0 commit comments

Comments
 (0)