Skip to content

Commit d14e7ff

Browse files
committed
Implement tool contact and test
1 parent e63390f commit d14e7ff

File tree

3 files changed

+47
-1
lines changed

3 files changed

+47
-1
lines changed

Diff for: ur_robot_driver/include/ur_robot_driver/hardware_interface.h

+4
Original file line numberDiff line numberDiff line change
@@ -215,6 +215,8 @@ class HardwareInterface : public hardware_interface::RobotHW
215215
void commandCallback(const std_msgs::StringConstPtr& msg);
216216
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
217217
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
218+
bool startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
219+
bool endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
218220

219221
std::unique_ptr<urcl::UrDriver> ur_driver_;
220222
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -239,6 +241,8 @@ class HardwareInterface : public hardware_interface::RobotHW
239241
ros::ServiceServer tare_sensor_srv_;
240242
ros::ServiceServer set_payload_srv_;
241243
ros::ServiceServer activate_spline_interpolation_srv_;
244+
ros::ServiceServer start_tool_contact_srv_;
245+
ros::ServiceServer end_tool_contact_srv_;
242246

243247
hardware_interface::JointStateInterface js_interface_;
244248
scaled_controllers::ScaledPositionJointInterface spj_interface_;

Diff for: ur_robot_driver/src/hardware_interface.cpp

+19
Original file line numberDiff line numberDiff line change
@@ -460,6 +460,13 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
460460
activate_spline_interpolation_srv_ = robot_hw_nh.advertiseService(
461461
"activate_spline_interpolation", &HardwareInterface::activateSplineInterpolation, this);
462462

463+
// Calling this service will enable the tool contact functionality on the robot.
464+
start_tool_contact_srv_ =
465+
robot_hw_nh.advertiseService("start_tool_contact", &HardwareInterface::startToolContact, this);
466+
467+
// Calling this service will disable the tool contact functionality on the robot.
468+
end_tool_contact_srv_ = robot_hw_nh.advertiseService("end_tool_contact", &HardwareInterface::endToolContact, this);
469+
463470
ur_driver_->startRTDECommunication();
464471
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
465472

@@ -1175,6 +1182,18 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
11751182
return true;
11761183
}
11771184

1185+
bool HardwareInterface::startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
1186+
{
1187+
res.success = this->ur_driver_->startToolContact();
1188+
return true;
1189+
}
1190+
1191+
bool HardwareInterface::endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
1192+
{
1193+
res.success = this->ur_driver_->endToolContact();
1194+
return true;
1195+
}
1196+
11781197
void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
11791198
{
11801199
std::string str = msg->data;

Diff for: ur_robot_driver/test/integration_test.py

+24-1
Original file line numberDiff line numberDiff line change
@@ -12,7 +12,7 @@
1212
FollowJointTrajectoryResult,
1313
JointTolerance)
1414
from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode
15-
from std_srvs.srv import Trigger, TriggerRequest
15+
from std_srvs.srv import Trigger
1616
import tf
1717
from trajectory_msgs.msg import JointTrajectoryPoint
1818
from ur_msgs.srv import SetIO, SetIORequest
@@ -120,6 +120,22 @@ def init_robot(self):
120120
"actually running in headless mode."
121121
" Msg: {}".format(err))
122122

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+
123139
self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
124140
self.tf_listener = tf.TransformListener()
125141
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
@@ -262,6 +278,13 @@ def test_set_io(self):
262278
messages += 1
263279
self.assertEqual(pin_state, 1)
264280

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+
265288
def test_cartesian_passthrough(self):
266289
#### Power cycle the robot in order to make sure it is running correctly####
267290
self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF))

0 commit comments

Comments
 (0)