|
| 1 | +#!/usr/bin/env python |
| 2 | +# Copyright 2025, Universal Robots A/S |
| 3 | +# |
| 4 | +# Redistribution and use in source and binary forms, with or without |
| 5 | +# modification, are permitted provided that the following conditions are met: |
| 6 | +# |
| 7 | +# * Redistributions of source code must retain the above copyright |
| 8 | +# notice, this list of conditions and the following disclaimer. |
| 9 | +# |
| 10 | +# * Redistributions in binary form must reproduce the above copyright |
| 11 | +# notice, this list of conditions and the following disclaimer in the |
| 12 | +# documentation and/or other materials provided with the distribution. |
| 13 | +# |
| 14 | +# * Neither the name of the {copyright_holder} nor the names of its |
| 15 | +# contributors may be used to endorse or promote products derived from |
| 16 | +# this software without specific prior written permission. |
| 17 | +# |
| 18 | +# THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" |
| 19 | +# AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE |
| 20 | +# IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE |
| 21 | +# ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE |
| 22 | +# LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR |
| 23 | +# CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF |
| 24 | +# SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS |
| 25 | +# INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN |
| 26 | +# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) |
| 27 | +# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE |
| 28 | +# POSSIBILITY OF SUCH DAMAGE. |
| 29 | + |
| 30 | +import logging |
| 31 | +import os |
| 32 | +import sys |
| 33 | +import time |
| 34 | +import unittest |
| 35 | + |
| 36 | +import launch_testing |
| 37 | +import pytest |
| 38 | +import rclpy |
| 39 | +from control_msgs.action import FollowJointTrajectory |
| 40 | +from rclpy.node import Node |
| 41 | +from ur_msgs.msg import IOStates |
| 42 | + |
| 43 | +sys.path.append(os.path.dirname(__file__)) |
| 44 | +from test_common import ( # noqa: E402 |
| 45 | + ActionInterface, |
| 46 | + ControllerManagerInterface, |
| 47 | + DashboardInterface, |
| 48 | + IoStatusInterface, |
| 49 | + ConfigurationInterface, |
| 50 | + generate_driver_test_description, |
| 51 | +) |
| 52 | + |
| 53 | + |
| 54 | +@pytest.mark.launch_test |
| 55 | +@launch_testing.parametrize( |
| 56 | + "tf_prefix, use_mock_hardware", [("", "false"), ("my_ur_", "false"), ("", "true")] |
| 57 | +) |
| 58 | +def generate_test_description(tf_prefix, use_mock_hardware): |
| 59 | + return generate_driver_test_description( |
| 60 | + tf_prefix=tf_prefix, use_mock_hardware=use_mock_hardware |
| 61 | + ) |
| 62 | + |
| 63 | + |
| 64 | +class RobotDriverTest(unittest.TestCase): |
| 65 | + @classmethod |
| 66 | + def setUpClass(cls, use_mock_hardware): |
| 67 | + # Initialize the ROS context |
| 68 | + rclpy.init() |
| 69 | + cls.node = Node("robot_driver_test") |
| 70 | + time.sleep(1) |
| 71 | + cls.mock_hardware = use_mock_hardware == "true" |
| 72 | + cls.init_robot(cls) |
| 73 | + |
| 74 | + @classmethod |
| 75 | + def tearDownClass(cls): |
| 76 | + # Shutdown the ROS context |
| 77 | + cls.node.destroy_node() |
| 78 | + rclpy.shutdown() |
| 79 | + |
| 80 | + def init_robot(self): |
| 81 | + if not self.mock_hardware: |
| 82 | + self._dashboard_interface = DashboardInterface(self.node) |
| 83 | + else: |
| 84 | + self._dashboard_interface = None |
| 85 | + self._controller_manager_interface = ControllerManagerInterface(self.node) |
| 86 | + self._io_status_controller_interface = IoStatusInterface(self.node) |
| 87 | + self._configuration_controller_interface = ConfigurationInterface(self.node) |
| 88 | + |
| 89 | + self._scaled_follow_joint_trajectory = ActionInterface( |
| 90 | + self.node, |
| 91 | + "/scaled_joint_trajectory_controller/follow_joint_trajectory", |
| 92 | + FollowJointTrajectory, |
| 93 | + ) |
| 94 | + self._passthrough_forward_joint_trajectory = ActionInterface( |
| 95 | + self.node, |
| 96 | + "/passthrough_trajectory_controller/follow_joint_trajectory", |
| 97 | + FollowJointTrajectory, |
| 98 | + ) |
| 99 | + |
| 100 | + def setUp(self): |
| 101 | + if self._dashboard_interface: |
| 102 | + self._dashboard_interface.start_robot() |
| 103 | + time.sleep(1) |
| 104 | + self.assertTrue(self._io_status_controller_interface.resend_robot_program().success) |
| 105 | + |
| 106 | + # |
| 107 | + # Test functions |
| 108 | + # |
| 109 | + |
| 110 | + def test_set_io(self): |
| 111 | + """Test to set an IO and check whether it has been set.""" |
| 112 | + if self.mock_hardware: |
| 113 | + return True |
| 114 | + # Create io callback to verify result |
| 115 | + io_msg = None |
| 116 | + |
| 117 | + def io_msg_cb(msg): |
| 118 | + nonlocal io_msg |
| 119 | + io_msg = msg |
| 120 | + |
| 121 | + io_states_sub = self.node.create_subscription( |
| 122 | + IOStates, |
| 123 | + "/io_and_status_controller/io_states", |
| 124 | + io_msg_cb, |
| 125 | + rclpy.qos.qos_profile_system_default, |
| 126 | + ) |
| 127 | + |
| 128 | + # Set pin 0 to 1.0 |
| 129 | + test_pin = 0 |
| 130 | + |
| 131 | + logging.info("Setting pin %d to 1.0", test_pin) |
| 132 | + self._io_status_controller_interface.set_io(fun=1, pin=test_pin, state=1.0) |
| 133 | + |
| 134 | + # Wait until the pin state has changed |
| 135 | + pin_state = False |
| 136 | + end_time = time.time() + 5 |
| 137 | + while not pin_state and time.time() < end_time: |
| 138 | + rclpy.spin_once(self.node, timeout_sec=0.1) |
| 139 | + if io_msg is not None: |
| 140 | + pin_state = io_msg.digital_out_states[test_pin].state |
| 141 | + |
| 142 | + self.assertEqual(pin_state, 1.0) |
| 143 | + |
| 144 | + # Set pin 0 to 0.0 |
| 145 | + logging.info("Setting pin %d to 0.0", test_pin) |
| 146 | + self._io_status_controller_interface.set_io(fun=1, pin=test_pin, state=0.0) |
| 147 | + |
| 148 | + # Wait until the pin state has changed back |
| 149 | + end_time = time.time() + 5 |
| 150 | + while pin_state and time.time() < end_time: |
| 151 | + rclpy.spin_once(self.node, timeout_sec=0.1) |
| 152 | + if io_msg is not None: |
| 153 | + pin_state = io_msg.digital_out_states[test_pin].state |
| 154 | + |
| 155 | + self.assertEqual(pin_state, 0.0) |
| 156 | + |
| 157 | + # Clean up io subscription |
| 158 | + self.node.destroy_subscription(io_states_sub) |
0 commit comments