Skip to content

Commit 79bfddc

Browse files
Felix Exner (fexner)RobertWilbrandt
andauthored
Run robot driver test also with tf_prefix (#729)
* Run robot driver test also with tf_prefix * Use tf_prefix substitution in controllers config file * Set default value of tf_prefix in launchfile to empty instead of '""' --------- Co-authored-by: Robert Wilbrandt <[email protected]>
1 parent 7a8bf3f commit 79bfddc

File tree

4 files changed

+69
-54
lines changed

4 files changed

+69
-54
lines changed

ur_robot_driver/CMakeLists.txt

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -185,7 +185,7 @@ if(BUILD_TESTING)
185185
)
186186
add_launch_test(test/robot_driver.py
187187
TIMEOUT
188-
500
188+
800
189189
)
190190
add_launch_test(test/urscript_interface.py
191191
TIMEOUT

ur_robot_driver/config/ur_controllers.yaml

Lines changed: 41 additions & 41 deletions
Original file line numberDiff line numberDiff line change
@@ -28,35 +28,35 @@ controller_manager:
2828
speed_scaling_state_broadcaster:
2929
ros__parameters:
3030
state_publish_rate: 100.0
31-
tf_prefix: ""
31+
tf_prefix: "$(var tf_prefix)"
3232

3333
io_and_status_controller:
3434
ros__parameters:
35-
tf_prefix: ""
35+
tf_prefix: "$(var tf_prefix)"
3636

3737
force_torque_sensor_broadcaster:
3838
ros__parameters:
39-
sensor_name: tcp_fts_sensor
39+
sensor_name: $(var tf_prefix)tcp_fts_sensor
4040
state_interface_names:
4141
- force.x
4242
- force.y
4343
- force.z
4444
- torque.x
4545
- torque.y
4646
- torque.z
47-
frame_id: tool0
47+
frame_id: $(var tf_prefix)tool0
4848
topic_name: ft_data
4949

5050

5151
joint_trajectory_controller:
5252
ros__parameters:
5353
joints:
54-
- shoulder_pan_joint
55-
- shoulder_lift_joint
56-
- elbow_joint
57-
- wrist_1_joint
58-
- wrist_2_joint
59-
- wrist_3_joint
54+
- $(var tf_prefix)shoulder_pan_joint
55+
- $(var tf_prefix)shoulder_lift_joint
56+
- $(var tf_prefix)elbow_joint
57+
- $(var tf_prefix)wrist_1_joint
58+
- $(var tf_prefix)wrist_2_joint
59+
- $(var tf_prefix)wrist_3_joint
6060
command_interfaces:
6161
- position
6262
state_interfaces:
@@ -68,23 +68,23 @@ joint_trajectory_controller:
6868
constraints:
6969
stopped_velocity_tolerance: 0.2
7070
goal_time: 0.0
71-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
72-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
73-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
74-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
75-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
76-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
71+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
72+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
73+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
74+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
75+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
76+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
7777

7878

7979
scaled_joint_trajectory_controller:
8080
ros__parameters:
8181
joints:
82-
- shoulder_pan_joint
83-
- shoulder_lift_joint
84-
- elbow_joint
85-
- wrist_1_joint
86-
- wrist_2_joint
87-
- wrist_3_joint
82+
- $(var tf_prefix)shoulder_pan_joint
83+
- $(var tf_prefix)shoulder_lift_joint
84+
- $(var tf_prefix)elbow_joint
85+
- $(var tf_prefix)wrist_1_joint
86+
- $(var tf_prefix)wrist_2_joint
87+
- $(var tf_prefix)wrist_3_joint
8888
command_interfaces:
8989
- position
9090
state_interfaces:
@@ -96,31 +96,31 @@ scaled_joint_trajectory_controller:
9696
constraints:
9797
stopped_velocity_tolerance: 0.2
9898
goal_time: 0.0
99-
shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
100-
shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
101-
elbow_joint: { trajectory: 0.2, goal: 0.1 }
102-
wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
103-
wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
104-
wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
105-
speed_scaling_interface_name: speed_scaling/speed_scaling_factor
99+
$(var tf_prefix)shoulder_pan_joint: { trajectory: 0.2, goal: 0.1 }
100+
$(var tf_prefix)shoulder_lift_joint: { trajectory: 0.2, goal: 0.1 }
101+
$(var tf_prefix)elbow_joint: { trajectory: 0.2, goal: 0.1 }
102+
$(var tf_prefix)wrist_1_joint: { trajectory: 0.2, goal: 0.1 }
103+
$(var tf_prefix)wrist_2_joint: { trajectory: 0.2, goal: 0.1 }
104+
$(var tf_prefix)wrist_3_joint: { trajectory: 0.2, goal: 0.1 }
105+
speed_scaling_interface_name: $(var tf_prefix)speed_scaling/speed_scaling_factor
106106

107107
forward_velocity_controller:
108108
ros__parameters:
109109
joints:
110-
- shoulder_pan_joint
111-
- shoulder_lift_joint
112-
- elbow_joint
113-
- wrist_1_joint
114-
- wrist_2_joint
115-
- wrist_3_joint
110+
- $(var tf_prefix)shoulder_pan_joint
111+
- $(var tf_prefix)shoulder_lift_joint
112+
- $(var tf_prefix)elbow_joint
113+
- $(var tf_prefix)wrist_1_joint
114+
- $(var tf_prefix)wrist_2_joint
115+
- $(var tf_prefix)wrist_3_joint
116116
interface_name: velocity
117117

118118
forward_position_controller:
119119
ros__parameters:
120120
joints:
121-
- shoulder_pan_joint
122-
- shoulder_lift_joint
123-
- elbow_joint
124-
- wrist_1_joint
125-
- wrist_2_joint
126-
- wrist_3_joint
121+
- $(var tf_prefix)shoulder_pan_joint
122+
- $(var tf_prefix)shoulder_lift_joint
123+
- $(var tf_prefix)elbow_joint
124+
- $(var tf_prefix)wrist_1_joint
125+
- $(var tf_prefix)wrist_2_joint
126+
- $(var tf_prefix)wrist_3_joint

ur_robot_driver/launch/ur_control.launch.py

Lines changed: 12 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -30,6 +30,7 @@
3030
# Author: Denis Stogl
3131

3232
from launch_ros.actions import Node
33+
from launch_ros.parameter_descriptions import ParameterFile
3334
from launch_ros.substitutions import FindPackageShare
3435

3536
from launch import LaunchDescription
@@ -204,15 +205,23 @@ def launch_setup(context, *args, **kwargs):
204205
control_node = Node(
205206
package="controller_manager",
206207
executable="ros2_control_node",
207-
parameters=[robot_description, update_rate_config_file, initial_joint_controllers],
208+
parameters=[
209+
robot_description,
210+
update_rate_config_file,
211+
ParameterFile(initial_joint_controllers, allow_substs=True),
212+
],
208213
output="screen",
209214
condition=IfCondition(use_mock_hardware),
210215
)
211216

212217
ur_control_node = Node(
213218
package="ur_robot_driver",
214219
executable="ur_ros2_control_node",
215-
parameters=[robot_description, update_rate_config_file, initial_joint_controllers],
220+
parameters=[
221+
robot_description,
222+
update_rate_config_file,
223+
ParameterFile(initial_joint_controllers, allow_substs=True),
224+
],
216225
output="screen",
217226
condition=UnlessCondition(use_mock_hardware),
218227
)
@@ -427,7 +436,7 @@ def generate_launch_description():
427436
declared_arguments.append(
428437
DeclareLaunchArgument(
429438
"tf_prefix",
430-
default_value='""',
439+
default_value="",
431440
description="tf_prefix of the joint names, useful for \
432441
multi-robot setup. If changed, also joint names in the controllers' configuration \
433442
have to be updated.",

ur_robot_driver/test/robot_driver.py

Lines changed: 15 additions & 9 deletions
Original file line numberDiff line numberDiff line change
@@ -31,6 +31,7 @@
3131
import time
3232
import unittest
3333

34+
import launch_testing
3435
import pytest
3536
import rclpy
3637
from builtin_interfaces.msg import Duration
@@ -52,10 +53,10 @@
5253
from rclpy.node import Node
5354
from std_srvs.srv import Trigger
5455
from trajectory_msgs.msg import JointTrajectory, JointTrajectoryPoint
55-
from ur_msgs.msg import IOStates
56-
from ur_msgs.srv import SetIO
5756
from ur_dashboard_msgs.msg import RobotMode
5857
from ur_dashboard_msgs.srv import GetRobotMode
58+
from ur_msgs.msg import IOStates
59+
from ur_msgs.srv import SetIO
5960

6061
TIMEOUT_WAIT_SERVICE = 10
6162
TIMEOUT_WAIT_SERVICE_INITIAL = 60
@@ -73,7 +74,11 @@
7374

7475

7576
@pytest.mark.launch_test
76-
def generate_test_description():
77+
@launch_testing.parametrize(
78+
"tf_prefix",
79+
[(""), ("my_ur_")],
80+
)
81+
def generate_test_description(tf_prefix):
7782
declared_arguments = []
7883

7984
declared_arguments.append(
@@ -102,6 +107,7 @@ def generate_test_description():
102107
"headless_mode": "true",
103108
"launch_dashboard_client": "false",
104109
"start_joint_controller": "false",
110+
"tf_prefix": tf_prefix,
105111
}.items(),
106112
)
107113
ursim = ExecuteProcess(
@@ -269,7 +275,7 @@ def io_msg_cb(msg):
269275
# Clean up io subscription
270276
self.node.destroy_subscription(io_states_sub)
271277

272-
def test_trajectory(self):
278+
def test_trajectory(self, tf_prefix):
273279
"""Test robot movement."""
274280
# Construct test trajectory
275281
test_trajectory = [
@@ -279,7 +285,7 @@ def test_trajectory(self):
279285
]
280286

281287
trajectory = JointTrajectory(
282-
joint_names=ROBOT_JOINTS,
288+
joint_names=[tf_prefix + joint for joint in ROBOT_JOINTS],
283289
points=[
284290
JointTrajectoryPoint(positions=test_pos, time_from_start=test_time)
285291
for (test_time, test_pos) in test_trajectory
@@ -303,7 +309,7 @@ def test_trajectory(self):
303309
self.assertEqual(result.error_code, FollowJointTrajectory.Result.SUCCESSFUL)
304310
self.node.get_logger().info("Received result SUCCESSFUL")
305311

306-
def test_illegal_trajectory(self):
312+
def test_illegal_trajectory(self, tf_prefix):
307313
"""
308314
Test trajectory server.
309315
@@ -316,7 +322,7 @@ def test_illegal_trajectory(self):
316322
]
317323

318324
trajectory = JointTrajectory(
319-
joint_names=ROBOT_JOINTS,
325+
joint_names=[tf_prefix + joint for joint in ROBOT_JOINTS],
320326
points=[
321327
JointTrajectoryPoint(positions=test_pos, time_from_start=test_time)
322328
for (test_time, test_pos) in test_trajectory
@@ -334,7 +340,7 @@ def test_illegal_trajectory(self):
334340
self.assertEqual(goal_response.accepted, False)
335341
self.node.get_logger().info("Goal response REJECTED")
336342

337-
def test_trajectory_scaled(self):
343+
def test_trajectory_scaled(self, tf_prefix):
338344
"""Test robot movement."""
339345
# Construct test trajectory
340346
test_trajectory = [
@@ -343,7 +349,7 @@ def test_trajectory_scaled(self):
343349
]
344350

345351
trajectory = JointTrajectory(
346-
joint_names=ROBOT_JOINTS,
352+
joint_names=[tf_prefix + joint for joint in ROBOT_JOINTS],
347353
points=[
348354
JointTrajectoryPoint(positions=test_pos, time_from_start=test_time)
349355
for (test_time, test_pos) in test_trajectory

0 commit comments

Comments
 (0)