Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
55 changes: 19 additions & 36 deletions ur_robot_driver/test/integration_test_controller_switch.py
Original file line number Diff line number Diff line change
Expand Up @@ -48,6 +48,16 @@
generate_driver_test_description,
)

ALL_CONTROLLERS = [
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_position_controller",
"forward_velocity_controller",
"passthrough_trajectory_controller",
"force_mode_controller",
"freedrive_mode_controller",
]


@pytest.mark.launch_test
@launch_testing.parametrize(
Expand Down Expand Up @@ -78,6 +88,8 @@ def init_robot(self):
self._dashboard_interface = DashboardInterface(self.node)
self._controller_manager_interface = ControllerManagerInterface(self.node)
self._io_status_controller_interface = IoStatusInterface(self.node)
for controller in ALL_CONTROLLERS:
self._controller_manager_interface.wait_for_controller(controller)

def setUp(self):
self._dashboard_interface.start_robot()
Expand All @@ -89,15 +101,7 @@ def test_activating_multiple_controllers_same_interface_fails(self):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_position_controller",
"forward_velocity_controller",
"passthrough_trajectory_controller",
"force_mode_controller",
"freedrive_mode_controller",
],
deactivate_controllers=ALL_CONTROLLERS,
).ok
)

Expand Down Expand Up @@ -126,15 +130,7 @@ def test_activating_multiple_controllers_different_interface_fails(self):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_position_controller",
"forward_velocity_controller",
"force_mode_controller",
"passthrough_trajectory_controller",
"freedrive_mode_controller",
],
deactivate_controllers=ALL_CONTROLLERS,
).ok
)
self.assertFalse(
Expand Down Expand Up @@ -261,7 +257,9 @@ def test_activating_controller_with_running_position_controller_fails(self):
).ok
)

def test_activating_controller_with_running_passthrough_trajectory_controller_fails(self):
def test_activating_controller_with_running_passthrough_trajectory_controller_fails(
self,
):
# Having a position-based controller active, no other controller should be able to
# activate.
self.assertTrue(
Expand Down Expand Up @@ -332,14 +330,7 @@ def test_force_mode_and_trajectory_passthrough_controller_are_compatible(self):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_position_controller",
"forward_velocity_controller",
"passthrough_trajectory_controller",
"force_mode_controller",
],
deactivate_controllers=ALL_CONTROLLERS,
).ok
)

Expand Down Expand Up @@ -411,15 +402,7 @@ def test_tool_contact_compatibility(self):
self.assertTrue(
self._controller_manager_interface.switch_controller(
strictness=SwitchController.Request.BEST_EFFORT,
deactivate_controllers=[
"scaled_joint_trajectory_controller",
"joint_trajectory_controller",
"forward_position_controller",
"forward_velocity_controller",
"passthrough_trajectory_controller",
"force_mode_controller",
"tool_contact_controller",
],
deactivate_controllers=ALL_CONTROLLERS,
).ok
)

Expand Down
15 changes: 10 additions & 5 deletions ur_robot_driver/test/test_common.py
Original file line number Diff line number Diff line change
Expand Up @@ -256,14 +256,19 @@ class ControllerManagerInterface(
},
services={"list_controllers": ListControllers},
):
def wait_for_controller(self, controller_name, target_state="active"):
while True:
def wait_for_controller(self, controller_name, target_state=None, timeout=TIMEOUT_WAIT_SERVICE):
start_time = time.time()
while time.time() - start_time < timeout:
controllers = self.list_controllers().controller
for controller in controllers:
if (controller.name == controller_name) and (controller.state == target_state):
return

if controller.name == controller_name:
if (target_state is None) or (controller.state == target_state):
return
time.sleep(1)
raise Exception(
"Controller '%s' not found or not in state '%s' within %fs"
% (controller_name, target_state, timeout)
)


class IoStatusInterface(
Expand Down
4 changes: 3 additions & 1 deletion ur_robot_driver/test/urscript_interface.py
Original file line number Diff line number Diff line change
Expand Up @@ -81,7 +81,9 @@ def setUp(self):
time.sleep(1)
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)

self._controller_manager_interface.wait_for_controller("io_and_status_controller")
self._controller_manager_interface.wait_for_controller(
"io_and_status_controller", target_state="active"
)

def test_set_io(self):
"""Test setting an IO using a direct program call."""
Expand Down
Loading