|
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 | 18 | from ur_msgs.srv import SetIO, SetIORequest
|
@@ -120,6 +120,22 @@ def init_robot(self):
|
120 | 120 | "actually running in headless mode."
|
121 | 121 | " Msg: {}".format(err))
|
122 | 122 |
|
| 123 | + self.start_tool_contact = rospy.ServiceProxy('ur_hardware_interface/start_tool_contact', Trigger) |
| 124 | + try: |
| 125 | + self.start_tool_contact.wait_for_service(timeout) |
| 126 | + except rospy.exceptions.ROSException as err: |
| 127 | + self.fail( |
| 128 | + "Could not reach 'start tool contact' service. Make sure that the driver is actually running." |
| 129 | + " Msg: {}".format(err)) |
| 130 | + |
| 131 | + self.end_tool_contact = rospy.ServiceProxy('ur_hardware_interface/end_tool_contact', Trigger) |
| 132 | + try: |
| 133 | + self.end_tool_contact.wait_for_service(timeout) |
| 134 | + except rospy.exceptions.ROSException as err: |
| 135 | + self.fail( |
| 136 | + "Could not reach 'end tool contact' service. Make sure that the driver is actually running." |
| 137 | + " Msg: {}".format(err)) |
| 138 | + |
123 | 139 | self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
|
124 | 140 | self.tf_listener = tf.TransformListener()
|
125 | 141 | self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
|
@@ -262,6 +278,13 @@ def test_set_io(self):
|
262 | 278 | messages += 1
|
263 | 279 | self.assertEqual(pin_state, 1)
|
264 | 280 |
|
| 281 | + def test_tool_contact(self): |
| 282 | + start_response = self.start_tool_contact.call() |
| 283 | + self.assertEqual(start_response.success,True) |
| 284 | + |
| 285 | + end_response = self.end_tool_contact.call() |
| 286 | + self.assertEqual(end_response.success, True) |
| 287 | + |
265 | 288 | def test_cartesian_passthrough(self):
|
266 | 289 | #### Power cycle the robot in order to make sure it is running correctly####
|
267 | 290 | self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF))
|
|
0 commit comments