@@ -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
0 commit comments