Skip to content

Commit 5407dfe

Browse files
authored
Implemented get version service (#695)
Add a service to get the polyscope version.
1 parent 999aa7e commit 5407dfe

File tree

3 files changed

+28
-1
lines changed

3 files changed

+28
-1
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 4 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/GetRobotSoftwareVersion.h>
5758

5859
#include <cartesian_interface/cartesian_command_interface.h>
5960
#include <cartesian_interface/cartesian_state_handle.h>
@@ -215,6 +216,8 @@ 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 getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req,
220+
ur_msgs::GetRobotSoftwareVersionResponse& res);
218221

219222
std::unique_ptr<urcl::UrDriver> ur_driver_;
220223
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -239,6 +242,7 @@ class HardwareInterface : public hardware_interface::RobotHW
239242
ros::ServiceServer tare_sensor_srv_;
240243
ros::ServiceServer set_payload_srv_;
241244
ros::ServiceServer activate_spline_interpolation_srv_;
245+
ros::ServiceServer get_robot_software_version_srv;
242246

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

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 15 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -460,6 +460,10 @@ 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_robot_software_version_srv =
465+
robot_hw_nh.advertiseService("get_robot_software_version", &HardwareInterface::getRobotSoftwareVersion, this);
466+
463467
ur_driver_->startRTDECommunication();
464468
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
465469

@@ -1175,6 +1179,17 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
11751179
return true;
11761180
}
11771181

1182+
bool HardwareInterface::getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req,
1183+
ur_msgs::GetRobotSoftwareVersionResponse& res)
1184+
{
1185+
urcl::VersionInformation version_info = this->ur_driver_->getVersion();
1186+
res.major = version_info.major;
1187+
res.minor = version_info.minor;
1188+
res.bugfix = version_info.bugfix;
1189+
res.build = version_info.build;
1190+
return true;
1191+
}
1192+
11781193
void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
11791194
{
11801195
std::string str = msg->data;

ur_robot_driver/test/integration_test.py

Lines changed: 9 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, GetRobotSoftwareVersion
1919
from ur_msgs.msg import IOStates
2020

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

123+
self.get_robot_software_version = rospy.ServiceProxy("ur_hardware_interface/get_robot_software_version", GetRobotSoftwareVersion)
124+
try:
125+
self.get_robot_software_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+
123131
self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
124132
self.tf_listener = tf.TransformListener()
125133
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)

0 commit comments

Comments
 (0)