Skip to content

Commit 317008d

Browse files
authored
fix_flaky_force_mode_test (backport of #1429) (#1449)
1 parent 375c4cb commit 317008d

File tree

1 file changed

+27
-11
lines changed

1 file changed

+27
-11
lines changed

ur_robot_driver/test/integration_test_force_mode.py

Lines changed: 27 additions & 11 deletions
Original file line numberDiff line numberDiff line change
@@ -120,18 +120,30 @@ def setUp(self):
120120
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
121121
self.tf_buffer = Buffer()
122122
self.tf_listener = TransformListener(self.tf_buffer, self.node)
123-
124-
def lookup_tcp_in_base(self, tf_prefix, timepoint):
125-
trans = None
126-
while not trans:
127-
rclpy.spin_once(self.node)
123+
time.sleep(1) # Wait whether the controller stopper resets controllers
124+
125+
def wait_for_lookup(self, source, target, timepoint, timeout=5.0):
126+
"""
127+
Wait until the transform between source and target is available.
128+
129+
:param source: The source frame
130+
:param target: The target frame
131+
:param timeout: The point in time at which to make the lookup
132+
:param timeout: Timeout in seconds
133+
:return: transform between source and target at the given timepoint
134+
:raises TimeoutError: If the transform is not available within the timeout
135+
"""
136+
end_time = time.time() + timeout
137+
while time.time() < end_time:
128138
try:
129-
trans = self.tf_buffer.lookup_transform(
130-
tf_prefix + "base", tf_prefix + "tool0", timepoint
131-
)
139+
trans = self.tf_buffer.lookup_transform(source, target, timepoint)
140+
return trans
132141
except TransformException:
133-
pass
134-
return trans
142+
rclpy.spin_once(self.node)
143+
raise TimeoutError()
144+
145+
def lookup_tcp_in_base(self, tf_prefix, timepoint):
146+
return self.wait_for_lookup(tf_prefix + "base", tf_prefix + "tool0_controller", timepoint)
135147

136148
# Implementation of force mode test to be reused
137149
# todo: If we move to pytest this could be done using parametrization
@@ -201,6 +213,9 @@ def run_force_mode(self, tf_prefix):
201213
),
202214
header=trans_after.header,
203215
)
216+
self.wait_for_lookup(
217+
diff.header.frame_id, tf_prefix + "tool0_controller", diff.header.stamp
218+
)
204219
diff_in_tool0_controller = self.tf_buffer.transform(
205220
diff,
206221
tf_prefix + "tool0_controller",
@@ -519,7 +534,6 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
519534
],
520535
).ok
521536
)
522-
self._force_mode_controller_interface = ForceModeInterface(self.node)
523537

524538
time.sleep(0.5)
525539
trans_before_wait = self.lookup_tcp_in_base(tf_prefix, self.node.get_clock().now())
@@ -531,6 +545,8 @@ def test_deactivating_controller_stops_force_mode(self, tf_prefix):
531545
self.assertAlmostEqual(
532546
trans_before_wait.transform.translation.z,
533547
trans_after_wait.transform.translation.z,
548+
delta=1e-7,
549+
msg="Robot should not move after force mode is stopped",
534550
)
535551

536552
def test_params_out_of_range_fails(self, tf_prefix):

0 commit comments

Comments
 (0)