Skip to content

Commit 133ff7b

Browse files
RobertWilbrandtmergify[bot]
authored andcommitted
Simplify tests (#849)
* Remove duplication of launch description in tests * Move launch and interfacing boilerplate to common file * Move all test logs to python logging This makes it easier to differentiate between ROS and test framework messages * Move waiting for a controller to test_common * Move robot starting to dashboard interface * Remove unused request definition (cherry picked from commit b28a870) # Conflicts: # ur_robot_driver/test/dashboard_client.py # ur_robot_driver/test/robot_driver.py # ur_robot_driver/test/urscript_interface.py
1 parent 83a084d commit 133ff7b

File tree

4 files changed

+464
-406
lines changed

4 files changed

+464
-406
lines changed

ur_robot_driver/test/dashboard_client.py

Lines changed: 14 additions & 82 deletions
Original file line numberDiff line numberDiff line change
@@ -26,38 +26,23 @@
2626
# CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
2727
# ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
2828
# POSSIBILITY OF SUCH DAMAGE.
29-
30-
29+
import os
30+
import sys
3131
import time
3232
import unittest
3333

3434
import pytest
3535
import rclpy
36-
from launch import LaunchDescription
37-
from launch.actions import DeclareLaunchArgument, ExecuteProcess, IncludeLaunchDescription
38-
from launch.launch_description_sources import PythonLaunchDescriptionSource
39-
from launch.substitutions import LaunchConfiguration, PathJoinSubstitution
40-
from launch_ros.substitutions import FindPackagePrefix, FindPackageShare
41-
from launch_testing.actions import ReadyToTest
4236
from rclpy.node import Node
43-
from std_srvs.srv import Trigger
4437
from ur_dashboard_msgs.msg import RobotMode
45-
from ur_dashboard_msgs.srv import (
46-
GetLoadedProgram,
47-
GetProgramState,
48-
GetRobotMode,
49-
IsProgramRunning,
50-
Load,
51-
)
5238

53-
TIMEOUT_WAIT_SERVICE = 10
54-
# If we download the docker image simultaneously to the tests, it can take quite some time until the
55-
# dashboard server is reachable and usable.
56-
TIMEOUT_WAIT_SERVICE_INITIAL = 120
39+
sys.path.append(os.path.dirname(__file__))
40+
from test_common import DashboardInterface, generate_dashboard_test_description # noqa: E402
5741

5842

5943
@pytest.mark.launch_test
6044
def generate_test_description():
45+
<<<<<<< HEAD
6146
declared_arguments = []
6247

6348
declared_arguments.append(
@@ -104,6 +89,9 @@ def generate_test_description():
10489
)
10590

10691
return LaunchDescription(declared_arguments + [ReadyToTest(), dashboard_client, ursim])
92+
=======
93+
return generate_dashboard_test_description()
94+
>>>>>>> b28a870 (Simplify tests (#849))
10795

10896

10997
class DashboardClientTest(unittest.TestCase):
@@ -121,38 +109,7 @@ def tearDownClass(cls):
121109
rclpy.shutdown()
122110

123111
def init_robot(self):
124-
# We wait longer for the first client, as the robot is still starting up
125-
power_on_client = waitForService(
126-
self.node, "/dashboard_client/power_on", Trigger, timeout=TIMEOUT_WAIT_SERVICE_INITIAL
127-
)
128-
129-
# Connect to all other expected services
130-
dashboard_interfaces = {
131-
"power_off": Trigger,
132-
"brake_release": Trigger,
133-
"unlock_protective_stop": Trigger,
134-
"restart_safety": Trigger,
135-
"get_robot_mode": GetRobotMode,
136-
"load_installation": Load,
137-
"load_program": Load,
138-
"close_popup": Trigger,
139-
"get_loaded_program": GetLoadedProgram,
140-
"program_state": GetProgramState,
141-
"program_running": IsProgramRunning,
142-
"play": Trigger,
143-
"stop": Trigger,
144-
}
145-
self.dashboard_clients = {
146-
srv_name: waitForService(self.node, f"/dashboard_client/{srv_name}", srv_type)
147-
for (srv_name, srv_type) in dashboard_interfaces.items()
148-
}
149-
150-
# Add first client to dict
151-
self.dashboard_clients["power_on"] = power_on_client
152-
153-
#
154-
# Test functions
155-
#
112+
self._dashboard_interface = DashboardInterface(self.node)
156113

157114
def test_switch_on(self):
158115
"""Test power on a robot."""
@@ -161,59 +118,34 @@ def test_switch_on(self):
161118
mode = RobotMode.DISCONNECTED
162119
while mode != RobotMode.POWER_OFF and time.time() < end_time:
163120
time.sleep(0.1)
164-
result = self.call_dashboard_service("get_robot_mode", GetRobotMode.Request())
121+
result = self._dashboard_interface.get_robot_mode()
165122
self.assertTrue(result.success)
166123
mode = result.robot_mode.mode
167124

168125
# Power on robot
169-
self.assertTrue(self.call_dashboard_service("power_on", Trigger.Request()).success)
126+
self.assertTrue(self._dashboard_interface.power_on().success)
170127

171128
# Wait until robot mode changes
172129
end_time = time.time() + 10
173130
mode = RobotMode.DISCONNECTED
174131
while mode not in (RobotMode.IDLE, RobotMode.RUNNING) and time.time() < end_time:
175132
time.sleep(0.1)
176-
result = self.call_dashboard_service("get_robot_mode", GetRobotMode.Request())
133+
result = self._dashboard_interface.get_robot_mode()
177134
self.assertTrue(result.success)
178135
mode = result.robot_mode.mode
179136

180137
self.assertIn(mode, (RobotMode.IDLE, RobotMode.RUNNING))
181138

182139
# Release robot brakes
183-
self.assertTrue(self.call_dashboard_service("brake_release", Trigger.Request()).success)
140+
self.assertTrue(self._dashboard_interface.brake_release().success)
184141

185142
# Wait until robot mode is RUNNING
186143
end_time = time.time() + 10
187144
mode = RobotMode.DISCONNECTED
188145
while mode != RobotMode.RUNNING and time.time() < end_time:
189146
time.sleep(0.1)
190-
result = self.call_dashboard_service("get_robot_mode", GetRobotMode.Request())
147+
result = self._dashboard_interface.get_robot_mode()
191148
self.assertTrue(result.success)
192149
mode = result.robot_mode.mode
193150

194151
self.assertEqual(mode, RobotMode.RUNNING)
195-
196-
#
197-
# Utility functions
198-
#
199-
200-
def call_dashboard_service(self, srv_name, request):
201-
self.node.get_logger().info(
202-
f"Calling dashboard service '{srv_name}' with request {request}"
203-
)
204-
future = self.dashboard_clients[srv_name].call_async(request)
205-
rclpy.spin_until_future_complete(self.node, future)
206-
if future.result() is not None:
207-
self.node.get_logger().info(f"Received result {future.result()}")
208-
return future.result()
209-
else:
210-
raise Exception(f"Exception while calling service: {future.exception()}")
211-
212-
213-
def waitForService(node, srv_name, srv_type, timeout=TIMEOUT_WAIT_SERVICE):
214-
client = node.create_client(srv_type, srv_name)
215-
if client.wait_for_service(timeout) is False:
216-
raise Exception(f"Could not reach service '{srv_name}' within timeout of {timeout}")
217-
218-
node.get_logger().info(f"Successfully connected to service '{srv_name}'")
219-
return client

0 commit comments

Comments
 (0)