Skip to content

Commit 013990f

Browse files
committed
Move all mock harrdware tests in to their own file
1 parent 62df581 commit 013990f

File tree

4 files changed

+628
-49
lines changed

4 files changed

+628
-49
lines changed

ur_robot_driver/test/integration_test_config_controller.py

Lines changed: 6 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -50,23 +50,18 @@
5050

5151

5252
@pytest.mark.launch_test
53-
@launch_testing.parametrize(
54-
"tf_prefix, use_mock_hardware", [("", "false"), ("my_ur_", "false"), ("", "true")]
55-
)
56-
def generate_test_description(tf_prefix, use_mock_hardware):
57-
return generate_driver_test_description(
58-
tf_prefix=tf_prefix, use_mock_hardware=use_mock_hardware
59-
)
53+
@launch_testing.parametrize("tf_prefix", [(""), ("my_ur_")])
54+
def generate_test_description(tf_prefix):
55+
return generate_driver_test_description(tf_prefix=tf_prefix)
6056

6157

6258
class RobotDriverTest(unittest.TestCase):
6359
@classmethod
64-
def setUpClass(cls, use_mock_hardware):
60+
def setUpClass(cls):
6561
# Initialize the ROS context
6662
rclpy.init()
6763
cls.node = Node("robot_driver_test")
6864
time.sleep(1)
69-
cls.mock_hardware = use_mock_hardware == "true"
7065
cls.init_robot(cls)
7166

7267
@classmethod
@@ -76,10 +71,7 @@ def tearDownClass(cls):
7671
rclpy.shutdown()
7772

7873
def init_robot(self):
79-
if not self.mock_hardware:
80-
self._dashboard_interface = DashboardInterface(self.node)
81-
else:
82-
self._dashboard_interface = None
74+
self._dashboard_interface = DashboardInterface(self.node)
8375
self._controller_manager_interface = ControllerManagerInterface(self.node)
8476
self._io_status_controller_interface = IoStatusInterface(self.node)
8577
self._configuration_controller_interface = ConfigurationInterface(self.node)
@@ -96,8 +88,7 @@ def init_robot(self):
9688
)
9789

9890
def setUp(self):
99-
if self._dashboard_interface:
100-
self._dashboard_interface.start_robot()
91+
self._dashboard_interface.start_robot()
10192
time.sleep(1)
10293
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
10394

ur_robot_driver/test/integration_test_io_controller.py

Lines changed: 6 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -52,23 +52,18 @@
5252

5353

5454
@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-
)
55+
@launch_testing.parametrize("tf_prefix", [(""), ("my_ur_")])
56+
def generate_test_description(tf_prefix):
57+
return generate_driver_test_description(tf_prefix=tf_prefix)
6258

6359

6460
class RobotDriverTest(unittest.TestCase):
6561
@classmethod
66-
def setUpClass(cls, use_mock_hardware):
62+
def setUpClass(cls):
6763
# Initialize the ROS context
6864
rclpy.init()
6965
cls.node = Node("robot_driver_test")
7066
time.sleep(1)
71-
cls.mock_hardware = use_mock_hardware == "true"
7267
cls.init_robot(cls)
7368

7469
@classmethod
@@ -78,10 +73,7 @@ def tearDownClass(cls):
7873
rclpy.shutdown()
7974

8075
def init_robot(self):
81-
if not self.mock_hardware:
82-
self._dashboard_interface = DashboardInterface(self.node)
83-
else:
84-
self._dashboard_interface = None
76+
self._dashboard_interface = DashboardInterface(self.node)
8577
self._controller_manager_interface = ControllerManagerInterface(self.node)
8678
self._io_status_controller_interface = IoStatusInterface(self.node)
8779
self._configuration_controller_interface = ConfigurationInterface(self.node)
@@ -98,8 +90,7 @@ def init_robot(self):
9890
)
9991

10092
def setUp(self):
101-
if self._dashboard_interface:
102-
self._dashboard_interface.start_robot()
93+
self._dashboard_interface.start_robot()
10394
time.sleep(1)
10495
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
10596

@@ -109,8 +100,6 @@ def setUp(self):
109100

110101
def test_set_io(self):
111102
"""Test to set an IO and check whether it has been set."""
112-
if self.mock_hardware:
113-
return True
114103
# Create io callback to verify result
115104
io_msg = None
116105

ur_robot_driver/test/integration_test_scaled_joint_controller.py

Lines changed: 6 additions & 17 deletions
Original file line numberDiff line numberDiff line change
@@ -56,23 +56,18 @@
5656

5757

5858
@pytest.mark.launch_test
59-
@launch_testing.parametrize(
60-
"tf_prefix, use_mock_hardware", [("", "false"), ("my_ur_", "false"), ("", "true")]
61-
)
62-
def generate_test_description(tf_prefix, use_mock_hardware):
63-
return generate_driver_test_description(
64-
tf_prefix=tf_prefix, use_mock_hardware=use_mock_hardware
65-
)
59+
@launch_testing.parametrize("tf_prefix", [(""), ("my_ur_")])
60+
def generate_test_description(tf_prefix):
61+
return generate_driver_test_description(tf_prefix=tf_prefix)
6662

6763

6864
class RobotDriverTest(unittest.TestCase):
6965
@classmethod
70-
def setUpClass(cls, use_mock_hardware):
66+
def setUpClass(cls):
7167
# Initialize the ROS context
7268
rclpy.init()
7369
cls.node = Node("robot_driver_test")
7470
time.sleep(1)
75-
cls.mock_hardware = use_mock_hardware == "true"
7671
cls.init_robot(cls)
7772

7873
@classmethod
@@ -82,10 +77,7 @@ def tearDownClass(cls):
8277
rclpy.shutdown()
8378

8479
def init_robot(self):
85-
if not self.mock_hardware:
86-
self._dashboard_interface = DashboardInterface(self.node)
87-
else:
88-
self._dashboard_interface = None
80+
self._dashboard_interface = DashboardInterface(self.node)
8981
self._controller_manager_interface = ControllerManagerInterface(self.node)
9082
self._io_status_controller_interface = IoStatusInterface(self.node)
9183
self._configuration_controller_interface = ConfigurationInterface(self.node)
@@ -102,8 +94,7 @@ def init_robot(self):
10294
)
10395

10496
def setUp(self):
105-
if self._dashboard_interface:
106-
self._dashboard_interface.start_robot()
97+
self._dashboard_interface.start_robot()
10798
time.sleep(1)
10899
self.assertTrue(self._io_status_controller_interface.resend_robot_program().success)
109100

@@ -206,8 +197,6 @@ def test_trajectory_scaled(self, tf_prefix):
206197

207198
def test_trajectory_scaled_aborts_on_violation(self, tf_prefix):
208199
"""Test that the robot correctly aborts the trajectory when the constraints are violated."""
209-
if self.mock_hardware:
210-
return True
211200
# Construct test trajectory
212201
test_trajectory = [
213202
(Duration(sec=6, nanosec=0), [0.0 for j in ROBOT_JOINTS]),

0 commit comments

Comments
 (0)