|
12 | 12 | FollowJointTrajectoryResult, |
13 | 13 | JointTolerance) |
14 | 14 | from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode |
15 | | -from std_srvs.srv import Trigger, TriggerRequest |
| 15 | +from std_srvs.srv import Trigger |
16 | 16 | import tf |
17 | 17 | from trajectory_msgs.msg import JointTrajectoryPoint |
18 | | -from ur_msgs.srv import SetIO, SetIORequest |
| 18 | +from ur_msgs.srv import SetIO, SetIORequest, GetVersion |
19 | 19 | from ur_msgs.msg import IOStates |
20 | 20 |
|
21 | 21 | from cartesian_control_msgs.msg import ( |
@@ -120,6 +120,30 @@ def init_robot(self): |
120 | 120 | "actually running in headless mode." |
121 | 121 | " Msg: {}".format(err)) |
122 | 122 |
|
| 123 | + self.get_version = rospy.ServiceProxy("ur_hardware_interface/get_version", GetVersion) |
| 124 | + try: |
| 125 | + self.get_version.wait_for_service(timeout) |
| 126 | + except rospy.exceptions.ROSException as err: |
| 127 | + self.fail( |
| 128 | + "Could not reach 'get version' service. Make sure that the driver is actually running." |
| 129 | + " Msg: {}".format(err)) |
| 130 | + |
| 131 | + self.start_tool_contact = rospy.ServiceProxy('ur_hardware_interface/start_tool_contact', Trigger) |
| 132 | + try: |
| 133 | + self.start_tool_contact.wait_for_service(timeout) |
| 134 | + except rospy.exceptions.ROSException as err: |
| 135 | + self.fail( |
| 136 | + "Could not reach 'start tool contact' service. Make sure that the driver is actually running." |
| 137 | + " Msg: {}".format(err)) |
| 138 | + |
| 139 | + self.end_tool_contact = rospy.ServiceProxy('ur_hardware_interface/end_tool_contact', Trigger) |
| 140 | + try: |
| 141 | + self.end_tool_contact.wait_for_service(timeout) |
| 142 | + except rospy.exceptions.ROSException as err: |
| 143 | + self.fail( |
| 144 | + "Could not reach 'end tool contact' service. Make sure that the driver is actually running." |
| 145 | + " Msg: {}".format(err)) |
| 146 | + |
123 | 147 | self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1) |
124 | 148 | self.tf_listener = tf.TransformListener() |
125 | 149 | self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1) |
@@ -262,6 +286,21 @@ def test_set_io(self): |
262 | 286 | messages += 1 |
263 | 287 | self.assertEqual(pin_state, 1) |
264 | 288 |
|
| 289 | + def test_tool_contact(self): |
| 290 | + version_info = self.get_version.call() |
| 291 | + if version_info.major >= 5: |
| 292 | + start_response = self.start_tool_contact.call() |
| 293 | + self.assertEqual(start_response.success,True) |
| 294 | + |
| 295 | + end_response = self.end_tool_contact.call() |
| 296 | + self.assertEqual(end_response.success, True) |
| 297 | + else: |
| 298 | + start_response = self.start_tool_contact.call() |
| 299 | + self.assertEqual(start_response.success,False) |
| 300 | + |
| 301 | + end_response = self.end_tool_contact.call() |
| 302 | + self.assertEqual(end_response.success, False) |
| 303 | + |
265 | 304 | def test_cartesian_passthrough(self): |
266 | 305 | #### Power cycle the robot in order to make sure it is running correctly#### |
267 | 306 | self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF)) |
|
0 commit comments