Skip to content

Commit 61bb094

Browse files
urmahpFelix Exner (fexner)
authored andcommitted
Added test for joint based cartesian trajectory interface
Added test of the robot moving slightly over time for both cartessian controllers.
1 parent 6ae99cc commit 61bb094

File tree

2 files changed

+95
-6
lines changed

2 files changed

+95
-6
lines changed

ur_robot_driver/test/driver.test

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@
2323
<remap from="forward_cartesian_trajectory" to="/forward_cartesian_traj_controller/follow_cartesian_trajectory" />
2424
<remap from="forward_joint_trajectory" to="/forward_joint_traj_controller/follow_joint_trajectory" />
2525
<remap from="follow_cartesian_trajectory" to="/pose_based_cartesian_traj_controller/follow_cartesian_trajectory" />
26+
<remap from="follow_joint_based_cartesian_trajectory" to="/joint_based_cartesian_traj_controller/follow_cartesian_trajectory" />
2627

2728
<test test-name="integration test" pkg="ur_robot_driver" type="integration_test.py" name="integration_test" time-limit="300.0"/>
2829

ur_robot_driver/test/integration_test.py

Lines changed: 94 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,7 @@
22
import sys
33
import time
44
import unittest
5+
import re
56

67
import rospy
78
import actionlib
@@ -12,6 +13,7 @@
1213
FollowJointTrajectoryResult,
1314
JointTolerance)
1415
from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode
16+
from ur_dashboard_msgs.srv import RawRequest
1517
from std_srvs.srv import Trigger, TriggerRequest
1618
import tf
1719
from trajectory_msgs.msg import JointTrajectoryPoint
@@ -93,6 +95,13 @@ def init_robot(self):
9395
"Could not reach cartesian controller action. Make sure that the driver is actually running."
9496
)
9597

98+
self.joint_based_cartesian_trajectory_client = actionlib.SimpleActionClient(
99+
'follow_joint_based_cartesian_trajectory', FollowCartesianTrajectoryAction)
100+
if not self.cartesian_trajectory_client.wait_for_server(timeout):
101+
self.fail(
102+
"Could not reach cartesian controller action. Make sure that the driver is actually running."
103+
" Msg: {}".format(err))
104+
96105
self.set_io_client = rospy.ServiceProxy('/ur_hardware_interface/set_io', SetIO)
97106
try:
98107
self.set_io_client.wait_for_service(timeout)
@@ -124,6 +133,19 @@ def init_robot(self):
124133
self.tf_listener = tf.TransformListener()
125134
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
126135

136+
# Get polyscope major version
137+
raw_request_srv = rospy.ServiceProxy('/ur_hardware_interface/dashboard/raw_request',
138+
RawRequest)
139+
try:
140+
raw_request_srv.wait_for_service(timeout)
141+
except rospy.exceptions.ROSException as err:
142+
self.fail(
143+
"Could not reach raw request service. Make sure that the driver is actually running."
144+
" Msg: {}".format(err))
145+
result = str(raw_request_srv("PolyscopeVersion"))
146+
match = re.search(r"\d", str(result))
147+
self.major_version = int(result[match.start()])
148+
127149
def set_robot_to_mode(self, target_mode):
128150
goal = SetModeGoal()
129151
goal.target_robot_mode.mode = RobotMode.RUNNING
@@ -367,6 +389,18 @@ def test_cartesian_trajectory_pose_interface(self):
367389
FollowCartesianTrajectoryResult.SUCCESSFUL)
368390
rospy.loginfo("Received result SUCCESSFUL")
369391

392+
# This will test that the controller is not moving the robot slightly, when no trajectory is running
393+
(trans_before, rot_before) = self.tf_listener.lookupTransform('base', 'tool0_controller', rospy.Time(0))
394+
rospy.sleep(5)
395+
(trans_after, rot_after) = self.tf_listener.lookupTransform('base', 'tool0_controller', rospy.Time(0))
396+
397+
self.assertAlmostEqual(rot_before[0], rot_after[0], delta=3e-6)
398+
self.assertAlmostEqual(rot_before[1], rot_after[1], delta=3e-6)
399+
self.assertAlmostEqual(rot_before[2], rot_after[2], delta=3e-6)
400+
self.assertAlmostEqual(trans_before[0], trans_after[0], delta=3e-6)
401+
self.assertAlmostEqual(trans_before[1], trans_after[1], delta=3e-6)
402+
self.assertAlmostEqual(trans_before[2], trans_after[2], delta=3e-6)
403+
370404
def test_twist_interface(self):
371405
#### Power cycle the robot in order to make sure it is running correctly####
372406
self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF))
@@ -408,13 +442,67 @@ def test_twist_interface(self):
408442

409443
(trans_end, rot_end) = self.tf_listener.lookupTransform('base', 'tool0_controller', rospy.Time(0))
410444

411-
self.assertAlmostEqual(rot_start[0], rot_end[0], delta=3e-6)
412-
self.assertAlmostEqual(rot_start[1], rot_end[1], delta=1e-6)
413-
self.assertAlmostEqual(rot_start[2], rot_end[2], delta=1e-6)
414-
self.assertAlmostEqual(trans_start[1], trans_end[1], delta=1e-6)
415-
self.assertAlmostEqual(trans_start[2], trans_end[2], delta=1e-6)
416-
self.assertTrue(trans_end[0] > trans_start[0])
445+
if self.major_version == 3:
446+
self.assertAlmostEqual(rot_start[0], rot_end[0], delta=3e-6)
447+
self.assertAlmostEqual(rot_start[1], rot_end[1], delta=3e-6)
448+
self.assertAlmostEqual(rot_start[2], rot_end[2], delta=3e-6)
449+
self.assertAlmostEqual(trans_start[1], trans_end[1], delta=3e-6)
450+
self.assertAlmostEqual(trans_start[2], trans_end[2], delta=3e-6)
451+
self.assertTrue(trans_end[0] > trans_start[0])
452+
else:
453+
self.assertAlmostEqual(rot_start[0], rot_end[0], delta=3e-6)
454+
self.assertAlmostEqual(rot_start[1], rot_end[1], delta=1e-6)
455+
self.assertAlmostEqual(rot_start[2], rot_end[2], delta=1e-6)
456+
self.assertAlmostEqual(trans_start[1], trans_end[1], delta=1e-6)
457+
self.assertAlmostEqual(trans_start[2], trans_end[2], delta=1e-6)
458+
self.assertTrue(trans_end[0] > trans_start[0])
459+
460+
461+
def test_joint_based_cartesian_trajectory_interface(self):
462+
#### Power cycle the robot in order to make sure it is running correctly####
463+
self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF))
464+
rospy.sleep(0.5)
465+
self.assertTrue(self.set_robot_to_mode(RobotMode.RUNNING))
466+
rospy.sleep(0.5)
467+
468+
# Make sure the robot is at a valid start position for our cartesian motions
469+
self.script_publisher.publish("movej([1, -1.7, -1.7, -1, -1.57, -2])")
470+
# As we don't have any feedback from that interface, sleep for a while
471+
rospy.sleep(5)
472+
473+
474+
self.send_program_srv.call()
475+
rospy.sleep(0.5) # TODO properly wait until the controller is running
417476

477+
self.switch_on_controller("joint_based_cartesian_traj_controller")
478+
479+
position_list = [geometry_msgs.msg.Vector3(0.4,0.4,0.4)]
480+
position_list.append(geometry_msgs.msg.Vector3(0.5,0.5,0.5))
481+
duration_list = [3.0, 6.0]
482+
goal = FollowCartesianTrajectoryGoal()
483+
484+
for i, position in enumerate(position_list):
485+
point = CartesianTrajectoryPoint()
486+
point.pose = geometry_msgs.msg.Pose(position, geometry_msgs.msg.Quaternion(0,0,0,1))
487+
point.time_from_start = rospy.Duration(duration_list[i])
488+
goal.trajectory.points.append(point)
489+
self.joint_based_cartesian_trajectory_client.send_goal(goal)
490+
self.joint_based_cartesian_trajectory_client.wait_for_result()
491+
self.assertEqual(self.joint_based_cartesian_trajectory_client.get_result().error_code,
492+
FollowCartesianTrajectoryResult.SUCCESSFUL)
493+
rospy.loginfo("Received result SUCCESSFUL")
494+
495+
# This will test that the controller is not moving the robot slightly, when no trajectory is running
496+
(trans_before, rot_before) = self.tf_listener.lookupTransform('base', 'tool0_controller', rospy.Time(0))
497+
rospy.sleep(5)
498+
(trans_after, rot_after) = self.tf_listener.lookupTransform('base', 'tool0_controller', rospy.Time(0))
499+
500+
self.assertAlmostEqual(rot_before[0], rot_after[0], delta=3e-6)
501+
self.assertAlmostEqual(rot_before[1], rot_after[1], delta=3e-6)
502+
self.assertAlmostEqual(rot_before[2], rot_after[2], delta=3e-6)
503+
self.assertAlmostEqual(trans_before[0], trans_after[0], delta=3e-6)
504+
self.assertAlmostEqual(trans_before[1], trans_after[1], delta=3e-6)
505+
self.assertAlmostEqual(trans_before[2], trans_after[2], delta=3e-6)
418506

419507
def switch_on_controller(self, controller_name):
420508
"""Switches on the given controller stopping all other known controllers with best_effort

0 commit comments

Comments
 (0)