Skip to content

Commit 141e3cb

Browse files
Fix buffer_client.py using default timeout_padding (#437)
* Fix buffer_client.py using default timeout_padding fixes #436 Co-authored-by: Chris Lalancette <[email protected]>
1 parent c36999b commit 141e3cb

File tree

1 file changed

+7
-9
lines changed

1 file changed

+7
-9
lines changed

tf2_ros_py/tf2_ros/buffer_client.py

Lines changed: 7 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -70,14 +70,12 @@ def __init__(
7070
timeout_padding: Duration = Duration(seconds=2.0)
7171
) -> None:
7272
"""
73-
.. function:: __init__(ns, check_frequency = 10.0, timeout_padding = rospy.Duration.from_sec(2.0))
73+
Constructor.
7474
75-
Constructor.
76-
77-
:param node: The ROS2 node.
78-
:param ns: The namespace in which to look for a BufferServer.
79-
:param check_frequency: How frequently to check for updates to known transforms.
80-
:param timeout_padding: A constant timeout to add to blocking calls.
75+
:param node: The ROS2 node.
76+
:param ns: The namespace in which to look for a BufferServer.
77+
:param check_frequency: How frequently to check for updates to known transforms.
78+
:param timeout_padding: A constant timeout to add to blocking calls.
8179
"""
8280
tf2_ros.BufferInterface.__init__(self)
8381
self.node = node
@@ -226,7 +224,7 @@ def unblock_by_timeout():
226224
clock = Clock()
227225
start_time = clock.now()
228226
timeout = Duration.from_msg(goal.timeout)
229-
timeout_padding = Duration(seconds=self.timeout_padding)
227+
timeout_padding = self.timeout_padding
230228
while not send_goal_future.done() and not event.is_set():
231229
if clock.now() > start_time + timeout + timeout_padding:
232230
break
@@ -243,7 +241,7 @@ def unblock_by_timeout():
243241

244242
event.wait()
245243

246-
#This shouldn't happen, but could in rare cases where the server hangs
244+
# This shouldn't happen, but could in rare cases where the server hangs
247245
if not send_goal_future.done():
248246
raise tf2.TimeoutException("The LookupTransform goal sent to the BufferServer did not come back in the specified time. Something is likely wrong with the server.")
249247

0 commit comments

Comments
 (0)