Skip to content

Commit a5a3ed6

Browse files
committed
Add test parameter of initial joint controller to test with different motion controllers.
1 parent a45d546 commit a5a3ed6

File tree

2 files changed

+8
-6
lines changed

2 files changed

+8
-6
lines changed

ur_robot_driver/test/integration_test_tool_contact.py

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -90,7 +90,7 @@ def init_robot(self):
9090
self.node, "/tool_contact_controller/enable_tool_contact", ToolContact
9191
)
9292
self._trajectory_until_interface = ActionInterface(
93-
self.node, "/trajectory_until/execute", TrajectoryUntil
93+
self.node, "/trajectory_until_node/execute", TrajectoryUntil
9494
)
9595

9696
def setUp(self):
@@ -117,14 +117,14 @@ def test_tool_contact(self):
117117
cancel_res = self._tool_contact_interface.cancel_goal(goal_handle)
118118
self.assertEqual(cancel_res.return_code, 0)
119119

120-
def test_trajectory_until(self):
120+
def test_trajectory_until(self, tf_prefix):
121121
L_pose_to_down = {
122-
"waypts": [[-0.45, -1.5, 1.5, -1.5, -1.5, -1.5], [-0.45, -1.2, 2.1, -2.4, -1.5, -1.5]],
122+
"waypts": [[1.5, -1.5, -0.45, -1.5, -1.5, -1.5], [2.1, -1.2, -0.45, -2.4, -1.5, -1.5]],
123123
"time_vec": [Duration(sec=3, nanosec=0), Duration(sec=6, nanosec=0)],
124124
}
125125

126126
trajectory = JointTrajectory()
127-
trajectory.joint_names = ROBOT_JOINTS
127+
trajectory.joint_names = [tf_prefix + joint for joint in ROBOT_JOINTS]
128128

129129
trajectory.points = [
130130
JointTrajectoryPoint(

ur_robot_driver/test/test_common.py

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -353,7 +353,9 @@ def generate_dashboard_test_description():
353353

354354

355355
def generate_driver_test_description(
356-
tf_prefix="", controller_spawner_timeout=TIMEOUT_WAIT_SERVICE_INITIAL
356+
tf_prefix="",
357+
initial_joint_controller="scaled_joint_trajectory_controller",
358+
controller_spawner_timeout=TIMEOUT_WAIT_SERVICE_INITIAL,
357359
):
358360
ur_type = LaunchConfiguration("ur_type")
359361

@@ -362,7 +364,7 @@ def generate_driver_test_description(
362364
"ur_type": ur_type,
363365
"launch_rviz": "false",
364366
"controller_spawner_timeout": str(controller_spawner_timeout),
365-
"initial_joint_controller": "scaled_joint_trajectory_controller",
367+
"initial_joint_controller": initial_joint_controller,
366368
"headless_mode": "true",
367369
"launch_dashboard_client": "true",
368370
"start_joint_controller": "false",

0 commit comments

Comments
 (0)