Skip to content

Commit 7b2245c

Browse files
committed
Fix formatting
Signed-off-by: Florian Vahl <[email protected]>
1 parent c4b1d68 commit 7b2245c

File tree

2 files changed

+41
-18
lines changed

2 files changed

+41
-18
lines changed

tf2_ros_py/test/test_buffer.py

Lines changed: 31 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -133,7 +133,6 @@ def test_await_transform_full_delayed(self):
133133
assert transform == excinfo.value.value
134134
coro.close()
135135

136-
137136
def await_transform_timeout_template(self, transform_coroutine):
138137
# wait for timeout in an async call
139138

@@ -153,7 +152,7 @@ async def async_environment():
153152

154153
# Indicate that we had a success
155154
stop_fut.set_result(True)
156-
except tf2.LookupException as e:
155+
except tf2.LookupException:
157156
# Indicate that we had a timeout
158157
stop_fut.set_result(False)
159158

@@ -163,7 +162,8 @@ async def async_environment():
163162
# Trigger the guard condition to start the async call
164163
gc.trigger()
165164

166-
# Runs the event loop until the future is done or times out (not the timeout that we want to test)
165+
# Runs the event loop until the future is done
166+
# or times out (not the timeout that we want to test)
167167
rclpy.spin_until_future_complete(node, stop_fut, executor, timeout_sec=0.2)
168168

169169
# Check if we actually timed out
@@ -185,36 +185,59 @@ async def async_environment():
185185
# Check if we can still get the transform after the timeout
186186
assert stop_fut.done() and stop_fut.result()
187187

188-
189188
def test_await_transform_timeout(self):
190189
# wait for timeout in an async call
191190

192191
def transform_coroutine(buffer, target, source, rclpy_time):
193-
return buffer.wait_for_transform_async(target, source, rclpy_time, timeout=rclpy.duration.Duration(seconds=0.1))
192+
return buffer.wait_for_transform_async(
193+
target,
194+
source,
195+
rclpy_time,
196+
timeout=rclpy.duration.Duration(seconds=0.1)
197+
)
194198

195199
self.await_transform_timeout_template(transform_coroutine)
196200

197201
def test_await_transform_full_timeout(self):
198202
# wait for timeout in an async call
199203

200204
def transform_coroutine(buffer, target, source, rclpy_time):
201-
return buffer.wait_for_transform_full_async(target, rclpy_time, source, rclpy_time, target, timeout=rclpy.duration.Duration(seconds=0.1))
205+
return buffer.wait_for_transform_full_async(
206+
target,
207+
rclpy_time,
208+
source,
209+
rclpy_time,
210+
target,
211+
timeout=rclpy.duration.Duration(seconds=0.1)
212+
)
202213

203214
self.await_transform_timeout_template(transform_coroutine)
204215

205216
def test_async_lookup_transform_timeout(self):
206217
# wait for timeout in an async call
207218

208219
def transform_coroutine(buffer, target, source, rclpy_time):
209-
return buffer.lookup_transform_async(target, source, rclpy_time, timeout=rclpy.duration.Duration(seconds=0.1))
220+
return buffer.lookup_transform_async(
221+
target,
222+
source,
223+
rclpy_time,
224+
timeout=rclpy.duration.Duration(seconds=0.1)
225+
)
210226

211227
self.await_transform_timeout_template(transform_coroutine)
212228

213229
def test_async_lookup_transform_full_timeout(self):
214230
# wait for timeout in an async call
215231

216232
def transform_coroutine(buffer, target, source, rclpy_time):
217-
return buffer.lookup_transform_full_async(target, rclpy_time, source, rclpy_time, target, timeout=rclpy.duration.Duration(seconds=0.1))
233+
return buffer.lookup_transform_full_async(
234+
target,
235+
rclpy_time,
236+
source,
237+
rclpy_time,
238+
target,
239+
timeout=rclpy.duration.Duration(seconds=0.1)
240+
)
218241

219242
self.await_transform_timeout_template(transform_coroutine)
220243

tf2_ros_py/tf2_ros/buffer.py

Lines changed: 10 additions & 10 deletions
Original file line numberDiff line numberDiff line change
@@ -166,8 +166,8 @@ async def lookup_transform_async(
166166
:param target_frame: Name of the frame to transform into.
167167
:param source_frame: Name of the input frame.
168168
: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.
169+
:param timeout: Time to wait for the target frame to become available.
170+
Needs a Node instance to be set on the Buffer to work.
171171
:return: The transform between the frames.
172172
"""
173173
return await self.wait_for_transform_async(target_frame, source_frame, time, timeout)
@@ -214,8 +214,8 @@ async def lookup_transform_full_async(
214214
:param source_frame: Name of the input frame.
215215
:param source_time: The time at which source_frame will be evaluated (0 gets the latest).
216216
: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.
217+
:param timeout: Time to wait for the target frame to become available.
218+
Needs a Node instance to be set on the Buffer to work.
219219
:return: The transform between the frames.
220220
"""
221221
return await self.wait_for_transform_full_async(
@@ -313,8 +313,8 @@ def wait_for_transform_async(
313313
:param target_frame: Name of the frame to transform into.
314314
:param source_frame: Name of the input frame.
315315
:param time: The time at which to get the transform (0 will get the latest).
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.
316+
:param timeout: Time to wait for the target frame to become available.
317+
Needs a Node instance to be set on the Buffer to work.
318318
:return: A future that contains the transform when it becomes available.
319319
"""
320320
fut = rclpy.task.Future()
@@ -344,7 +344,7 @@ def _on_timeout():
344344
# Check if a timeout is specified
345345
if timeout is not None:
346346
if self.node is None:
347-
raise RuntimeError("Async timeouts require a Node instance to be set.")
347+
raise RuntimeError('Async timeouts require a Node instance to be set.')
348348

349349
timeout_timer = self.node.create_timer(
350350
timeout.nanoseconds / 1e9, _on_timeout, clock=self.node.get_clock(),
@@ -380,8 +380,8 @@ def wait_for_transform_full_async(
380380
:param source_frame: Name of the input frame.
381381
:param source_time: The time at which source_frame will be evaluated (0 gets the latest).
382382
: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.
383+
:param timeout: Time to wait for the target frame to become available.
384+
Needs a Node instance to be set on the Buffer to work.
385385
:return: A future that becomes true when the transform is available.
386386
"""
387387
fut = rclpy.task.Future()
@@ -414,7 +414,7 @@ def _on_timeout():
414414
# Check if a timeout is specified
415415
if timeout is not None:
416416
if self.node is None:
417-
raise RuntimeError("Async timeouts require a Node instance to be set.")
417+
raise RuntimeError('Async timeouts require a Node instance to be set.')
418418

419419
timeout_timer = self.node.create_timer(
420420
timeout.nanoseconds / 1e9, _on_timeout, clock=self.node.get_clock(),

0 commit comments

Comments
 (0)