Skip to content

Commit e63390f

Browse files
committed
Revert "Tool contact and get version"
This reverts commit 7fdfc04.
1 parent 3d8638e commit e63390f

File tree

3 files changed

+2
-80
lines changed

3 files changed

+2
-80
lines changed

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

-7
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,6 @@
5454
#include <ur_msgs/SetIO.h>
5555
#include <ur_msgs/SetSpeedSliderFraction.h>
5656
#include <ur_msgs/SetPayload.h>
57-
#include <ur_msgs/GetVersion.h>
5857

5958
#include <cartesian_interface/cartesian_command_interface.h>
6059
#include <cartesian_interface/cartesian_state_handle.h>
@@ -216,9 +215,6 @@ class HardwareInterface : public hardware_interface::RobotHW
216215
void commandCallback(const std_msgs::StringConstPtr& msg);
217216
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
218217
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
219-
bool startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
220-
bool endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
221-
bool getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res);
222218

223219
std::unique_ptr<urcl::UrDriver> ur_driver_;
224220
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -243,9 +239,6 @@ class HardwareInterface : public hardware_interface::RobotHW
243239
ros::ServiceServer tare_sensor_srv_;
244240
ros::ServiceServer set_payload_srv_;
245241
ros::ServiceServer activate_spline_interpolation_srv_;
246-
ros::ServiceServer start_tool_contact_srv_;
247-
ros::ServiceServer end_tool_contact_srv_;
248-
ros::ServiceServer get_version_srv;
249242

250243
hardware_interface::JointStateInterface js_interface_;
251244
scaled_controllers::ScaledPositionJointInterface spj_interface_;

Diff for: ur_robot_driver/src/hardware_interface.cpp

-32
Original file line numberDiff line numberDiff line change
@@ -460,16 +460,6 @@ 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-
470-
// Calling this service will return the software version of the robot.
471-
get_version_srv = robot_hw_nh.advertiseService("get_version", &HardwareInterface::getVersion, this);
472-
473463
ur_driver_->startRTDECommunication();
474464
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
475465

@@ -1185,28 +1175,6 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
11851175
return true;
11861176
}
11871177

1188-
bool HardwareInterface::startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
1189-
{
1190-
res.success = this->ur_driver_->startToolContact();
1191-
return true;
1192-
}
1193-
1194-
bool HardwareInterface::endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res)
1195-
{
1196-
res.success = this->ur_driver_->endToolContact();
1197-
return true;
1198-
}
1199-
1200-
bool HardwareInterface::getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res)
1201-
{
1202-
urcl::VersionInformation version_info = this->ur_driver_->getVersion();
1203-
res.major = version_info.major;
1204-
res.minor = version_info.minor;
1205-
res.bugfix = version_info.bugfix;
1206-
res.build = version_info.build;
1207-
return true;
1208-
}
1209-
12101178
void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
12111179
{
12121180
std::string str = msg->data;

Diff for: ur_robot_driver/test/integration_test.py

+2-41
Original file line numberDiff line numberDiff line change
@@ -12,10 +12,10 @@
1212
FollowJointTrajectoryResult,
1313
JointTolerance)
1414
from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode
15-
from std_srvs.srv import Trigger
15+
from std_srvs.srv import Trigger, TriggerRequest
1616
import tf
1717
from trajectory_msgs.msg import JointTrajectoryPoint
18-
from ur_msgs.srv import SetIO, SetIORequest, GetVersion
18+
from ur_msgs.srv import SetIO, SetIORequest
1919
from ur_msgs.msg import IOStates
2020

2121
from cartesian_control_msgs.msg import (
@@ -120,30 +120,6 @@ def init_robot(self):
120120
"actually running in headless mode."
121121
" Msg: {}".format(err))
122122

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-
147123
self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
148124
self.tf_listener = tf.TransformListener()
149125
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
@@ -286,21 +262,6 @@ def test_set_io(self):
286262
messages += 1
287263
self.assertEqual(pin_state, 1)
288264

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

0 commit comments

Comments
 (0)