Skip to content

Commit d675a36

Browse files
authored
Fix flaky controller switch test (UniversalRobots#1447)
We were starting the tests right after we started the driver. However, the test requires that all controllers are actually available. This commit adds a check whether all required controllers are actually loaded. If not all required controllers are found in a specific time, the test will throw an exception and therefore fail.
1 parent 0d5d77e commit d675a36

File tree

3 files changed

+32
-42
lines changed

3 files changed

+32
-42
lines changed

ur_robot_driver/test/integration_test_controller_switch.py

Lines changed: 19 additions & 36 deletions
Original file line numberDiff line numberDiff line change
@@ -48,6 +48,16 @@
4848
generate_driver_test_description,
4949
)
5050

51+
ALL_CONTROLLERS = [
52+
"scaled_joint_trajectory_controller",
53+
"joint_trajectory_controller",
54+
"forward_position_controller",
55+
"forward_velocity_controller",
56+
"passthrough_trajectory_controller",
57+
"force_mode_controller",
58+
"freedrive_mode_controller",
59+
]
60+
5161

5262
@pytest.mark.launch_test
5363
@launch_testing.parametrize(
@@ -78,6 +88,8 @@ def init_robot(self):
7888
self._dashboard_interface = DashboardInterface(self.node)
7989
self._controller_manager_interface = ControllerManagerInterface(self.node)
8090
self._io_status_controller_interface = IoStatusInterface(self.node)
91+
for controller in ALL_CONTROLLERS:
92+
self._controller_manager_interface.wait_for_controller(controller)
8193

8294
def setUp(self):
8395
self._dashboard_interface.start_robot()
@@ -89,15 +101,7 @@ def test_activating_multiple_controllers_same_interface_fails(self):
89101
self.assertTrue(
90102
self._controller_manager_interface.switch_controller(
91103
strictness=SwitchController.Request.BEST_EFFORT,
92-
deactivate_controllers=[
93-
"scaled_joint_trajectory_controller",
94-
"joint_trajectory_controller",
95-
"forward_position_controller",
96-
"forward_velocity_controller",
97-
"passthrough_trajectory_controller",
98-
"force_mode_controller",
99-
"freedrive_mode_controller",
100-
],
104+
deactivate_controllers=ALL_CONTROLLERS,
101105
).ok
102106
)
103107

@@ -126,15 +130,7 @@ def test_activating_multiple_controllers_different_interface_fails(self):
126130
self.assertTrue(
127131
self._controller_manager_interface.switch_controller(
128132
strictness=SwitchController.Request.BEST_EFFORT,
129-
deactivate_controllers=[
130-
"scaled_joint_trajectory_controller",
131-
"joint_trajectory_controller",
132-
"forward_position_controller",
133-
"forward_velocity_controller",
134-
"force_mode_controller",
135-
"passthrough_trajectory_controller",
136-
"freedrive_mode_controller",
137-
],
133+
deactivate_controllers=ALL_CONTROLLERS,
138134
).ok
139135
)
140136
self.assertFalse(
@@ -261,7 +257,9 @@ def test_activating_controller_with_running_position_controller_fails(self):
261257
).ok
262258
)
263259

264-
def test_activating_controller_with_running_passthrough_trajectory_controller_fails(self):
260+
def test_activating_controller_with_running_passthrough_trajectory_controller_fails(
261+
self,
262+
):
265263
# Having a position-based controller active, no other controller should be able to
266264
# activate.
267265
self.assertTrue(
@@ -332,14 +330,7 @@ def test_force_mode_and_trajectory_passthrough_controller_are_compatible(self):
332330
self.assertTrue(
333331
self._controller_manager_interface.switch_controller(
334332
strictness=SwitchController.Request.BEST_EFFORT,
335-
deactivate_controllers=[
336-
"scaled_joint_trajectory_controller",
337-
"joint_trajectory_controller",
338-
"forward_position_controller",
339-
"forward_velocity_controller",
340-
"passthrough_trajectory_controller",
341-
"force_mode_controller",
342-
],
333+
deactivate_controllers=ALL_CONTROLLERS,
343334
).ok
344335
)
345336

@@ -411,15 +402,7 @@ def test_tool_contact_compatibility(self):
411402
self.assertTrue(
412403
self._controller_manager_interface.switch_controller(
413404
strictness=SwitchController.Request.BEST_EFFORT,
414-
deactivate_controllers=[
415-
"scaled_joint_trajectory_controller",
416-
"joint_trajectory_controller",
417-
"forward_position_controller",
418-
"forward_velocity_controller",
419-
"passthrough_trajectory_controller",
420-
"force_mode_controller",
421-
"tool_contact_controller",
422-
],
405+
deactivate_controllers=ALL_CONTROLLERS,
423406
).ok
424407
)
425408

ur_robot_driver/test/test_common.py

Lines changed: 10 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -256,14 +256,19 @@ class ControllerManagerInterface(
256256
},
257257
services={"list_controllers": ListControllers},
258258
):
259-
def wait_for_controller(self, controller_name, target_state="active"):
260-
while True:
259+
def wait_for_controller(self, controller_name, target_state=None, timeout=TIMEOUT_WAIT_SERVICE):
260+
start_time = time.time()
261+
while time.time() - start_time < timeout:
261262
controllers = self.list_controllers().controller
262263
for controller in controllers:
263-
if (controller.name == controller_name) and (controller.state == target_state):
264-
return
265-
264+
if controller.name == controller_name:
265+
if (target_state is None) or (controller.state == target_state):
266+
return
266267
time.sleep(1)
268+
raise Exception(
269+
"Controller '%s' not found or not in state '%s' within %fs"
270+
% (controller_name, target_state, timeout)
271+
)
267272

268273

269274
class IoStatusInterface(

ur_robot_driver/test/urscript_interface.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -81,7 +81,9 @@ def setUp(self):
8181
time.sleep(1)
8282
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
8383

84-
self._controller_manager_interface.wait_for_controller("io_and_status_controller")
84+
self._controller_manager_interface.wait_for_controller(
85+
"io_and_status_controller", target_state="active"
86+
)
8587

8688
def test_set_io(self):
8789
"""Test setting an IO using a direct program call."""

0 commit comments

Comments
 (0)