Skip to content

Commit 601c452

Browse files
URJalaFelix Exner (fexner)
authored andcommitted
Implemented get version service, and integrated it with the tool contact test
1 parent d73f7f7 commit 601c452

File tree

3 files changed

+56
-1
lines changed

3 files changed

+56
-1
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -54,6 +54,7 @@
5454
#include <ur_msgs/SetIO.h>
5555
#include <ur_msgs/SetSpeedSliderFraction.h>
5656
#include <ur_msgs/SetPayload.h>
57+
#include <ur_msgs/GetVersion.h>
5758

5859
#include <cartesian_interface/cartesian_command_interface.h>
5960
#include <cartesian_interface/cartesian_state_handle.h>
@@ -215,6 +216,7 @@ class HardwareInterface : public hardware_interface::RobotHW
215216
void commandCallback(const std_msgs::StringConstPtr& msg);
216217
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
217218
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
219+
bool getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res);
218220

219221
std::unique_ptr<urcl::UrDriver> ur_driver_;
220222
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -239,6 +241,7 @@ 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 get_version_srv;
242245

243246
hardware_interface::JointStateInterface js_interface_;
244247
scaled_controllers::ScaledPositionJointInterface spj_interface_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 13 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -460,6 +460,9 @@ 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 return the software version of the robot.
464+
get_version_srv = robot_hw_nh.advertiseService("get_version", &HardwareInterface::getVersion, this);
465+
463466
ur_driver_->startRTDECommunication();
464467
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
465468

@@ -1175,6 +1178,16 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
11751178
return true;
11761179
}
11771180

1181+
bool HardwareInterface::getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res)
1182+
{
1183+
urcl::VersionInformation version_info = this->ur_driver_->getVersion();
1184+
res.major = version_info.major;
1185+
res.minor = version_info.minor;
1186+
res.bugfix = version_info.bugfix;
1187+
res.build = version_info.build;
1188+
return true;
1189+
}
1190+
11781191
void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
11791192
{
11801193
std::string str = msg->data;

ur_robot_driver/test/integration_test.py

Lines changed: 40 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -15,7 +15,7 @@
1515
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
18+
from ur_msgs.srv import SetIO, SetIORequest, GetVersion
1919
from ur_msgs.msg import IOStates
2020

2121
from cartesian_control_msgs.msg import (
@@ -120,6 +120,30 @@ 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+
123147
self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
124148
self.tf_listener = tf.TransformListener()
125149
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
@@ -262,6 +286,21 @@ def test_set_io(self):
262286
messages += 1
263287
self.assertEqual(pin_state, 1)
264288

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

0 commit comments

Comments
 (0)