Skip to content

Commit 1c6e90d

Browse files
committed
Running integration tests with mock hardware
Added some launch arguments and some checks to avoid connecting to the dashboard interface when using mock hardware, as that will not work. Maybe not the most elegant, but it works for now. Currently passthrough controller does not work at all with mock hardware, and is bypassed if using that in the test. test_trajectory_scaled_aborts_on_violation fails, as the hardware doesnt abort. test_set_io also fails as the controller cant verify that a pin has been set.
1 parent accd58b commit 1c6e90d

File tree

4 files changed

+28
-9
lines changed

4 files changed

+28
-9
lines changed

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -182,6 +182,9 @@ def controller_spawner(controllers, active=True):
182182
if activate_joint_controller.perform(context) == "true":
183183
controllers_active.append(initial_joint_controller.perform(context))
184184
controllers_inactive.remove(initial_joint_controller.perform(context))
185+
186+
if use_mock_hardware.perform(context) == "true":
187+
controllers_active.remove("tcp_pose_broadcaster")
185188

186189
controller_spawners = [
187190
controller_spawner(controllers_active),

ur_robot_driver/test/robot_driver.py

Lines changed: 18 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -56,16 +56,22 @@
5656
)
5757

5858
TIMEOUT_EXECUTE_TRAJECTORY = 30
59+
MOCK_HARDWARE = False
60+
61+
def set_mock_hardware_flag(use_mock_hardware):
62+
return use_mock_hardware=="true"
5963

6064

6165
@pytest.mark.launch_test
6266
@launch_testing.parametrize(
63-
"tf_prefix",
64-
[(""), ("my_ur_")],
67+
"tf_prefix, use_mock_hardware, mock_sensor_commands",
68+
[("", "false", "false"), ("my_ur_", "false", "false"), ("", "true", "true")]
6569
)
66-
def generate_test_description(tf_prefix):
67-
return generate_driver_test_description(tf_prefix=tf_prefix)
6870

71+
def generate_test_description(tf_prefix, use_mock_hardware, mock_sensor_commands):
72+
global MOCK_HARDWARE
73+
MOCK_HARDWARE = set_mock_hardware_flag(use_mock_hardware)
74+
return generate_driver_test_description(tf_prefix=tf_prefix, use_mock_hardware=use_mock_hardware, mock_sensor_commands=mock_sensor_commands)
6975

7076
class RobotDriverTest(unittest.TestCase):
7177
@classmethod
@@ -83,7 +89,10 @@ def tearDownClass(cls):
8389
rclpy.shutdown()
8490

8591
def init_robot(self):
86-
self._dashboard_interface = DashboardInterface(self.node)
92+
if(not MOCK_HARDWARE):
93+
self._dashboard_interface = DashboardInterface(self.node)
94+
else:
95+
self._dashboard_interface = None
8796
self._controller_manager_interface = ControllerManagerInterface(self.node)
8897
self._io_status_controller_interface = IoStatusInterface(self.node)
8998
self._configuration_controller_interface = ConfigurationInterface(self.node)
@@ -100,7 +109,8 @@ def init_robot(self):
100109
)
101110

102111
def setUp(self):
103-
self._dashboard_interface.start_robot()
112+
if(self._dashboard_interface):
113+
self._dashboard_interface.start_robot()
104114
time.sleep(1)
105115
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
106116

@@ -351,6 +361,8 @@ def js_cb(msg):
351361
# self.node.get_logger().info("Received result GOAL_TOLERANCE_VIOLATED")
352362

353363
def test_passthrough_trajectory(self, tf_prefix):
364+
if(MOCK_HARDWARE):
365+
return True
354366
self.assertTrue(
355367
self._controller_manager_interface.switch_controller(
356368
strictness=SwitchController.Request.BEST_EFFORT,

ur_robot_driver/test/test_common.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -341,8 +341,8 @@ def generate_dashboard_test_description():
341341

342342

343343
def generate_driver_test_description(
344-
tf_prefix="", controller_spawner_timeout=TIMEOUT_WAIT_SERVICE_INITIAL
345-
):
344+
tf_prefix="", controller_spawner_timeout=TIMEOUT_WAIT_SERVICE_INITIAL, use_mock_hardware="false", mock_sensor_commands="false"
345+
):
346346
ur_type = LaunchConfiguration("ur_type")
347347

348348
launch_arguments = {
@@ -354,6 +354,8 @@ def generate_driver_test_description(
354354
"headless_mode": "true",
355355
"launch_dashboard_client": "true",
356356
"start_joint_controller": "false",
357+
"use_mock_hardware": use_mock_hardware,
358+
"mock_sensor_commands": mock_sensor_commands,
357359
}
358360
if tf_prefix:
359361
launch_arguments["tf_prefix"] = tf_prefix

ur_robot_driver/urdf/ur.ros2_control.xacro

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -293,7 +293,9 @@
293293

294294

295295
<gpio name="${tf_prefix}get_robot_software_version">
296-
<state_interface name="get_version_major"/>
296+
<state_interface name="get_version_major">
297+
<param name="initial_value">1</param>
298+
</state_interface>
297299
<state_interface name="get_version_minor"/>
298300
<state_interface name="get_version_build"/>
299301
<state_interface name="get_version_bugfix"/>

0 commit comments

Comments
 (0)