Skip to content

Commit a7176e1

Browse files
committed
Renamed get_version service to "GetRobotSoftwareVersion" everywhere
1 parent 1cc6e4a commit a7176e1

File tree

3 files changed

+9
-9
lines changed

3 files changed

+9
-9
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +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>
57+
#include <ur_msgs/GetRobotSoftwareVersion.h>
5858

5959
#include <cartesian_interface/cartesian_command_interface.h>
6060
#include <cartesian_interface/cartesian_state_handle.h>
@@ -216,7 +216,7 @@ class HardwareInterface : public hardware_interface::RobotHW
216216
void commandCallback(const std_msgs::StringConstPtr& msg);
217217
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
218218
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
219-
bool getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res);
219+
bool getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req, ur_msgs::GetRobotSoftwareVersionResponse& res);
220220

221221
std::unique_ptr<urcl::UrDriver> ur_driver_;
222222
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -241,7 +241,7 @@ class HardwareInterface : public hardware_interface::RobotHW
241241
ros::ServiceServer tare_sensor_srv_;
242242
ros::ServiceServer set_payload_srv_;
243243
ros::ServiceServer activate_spline_interpolation_srv_;
244-
ros::ServiceServer get_version_srv;
244+
ros::ServiceServer get_robot_software_version_srv;
245245

246246
hardware_interface::JointStateInterface js_interface_;
247247
scaled_controllers::ScaledPositionJointInterface spj_interface_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -461,7 +461,7 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
461461
"activate_spline_interpolation", &HardwareInterface::activateSplineInterpolation, this);
462462

463463
// Calling this service will return the software version of the robot.
464-
get_version_srv = robot_hw_nh.advertiseService("get_version", &HardwareInterface::getVersion, this);
464+
get_robot_software_version_srv = robot_hw_nh.advertiseService("get_robot_software_version", &HardwareInterface::getRobotSoftwareVersion, this);
465465

466466
ur_driver_->startRTDECommunication();
467467
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
@@ -1178,7 +1178,7 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
11781178
return true;
11791179
}
11801180

1181-
bool HardwareInterface::getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res)
1181+
bool HardwareInterface::getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req, ur_msgs::GetRobotSoftwareVersionResponse& res)
11821182
{
11831183
urcl::VersionInformation version_info = this->ur_driver_->getVersion();
11841184
res.major = version_info.major;

ur_robot_driver/test/integration_test.py

Lines changed: 4 additions & 4 deletions
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, GetVersion
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,9 +120,9 @@ 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)
123+
self.get_robot_software_version = rospy.ServiceProxy("ur_hardware_interface/get_robot_software_version", GetRobotSoftwareVersion)
124124
try:
125-
self.get_version.wait_for_service(timeout)
125+
self.get_robot_software_version.wait_for_service(timeout)
126126
except rospy.exceptions.ROSException as err:
127127
self.fail(
128128
"Could not reach 'get version' service. Make sure that the driver is actually running."
@@ -287,7 +287,7 @@ def test_set_io(self):
287287
self.assertEqual(pin_state, 1)
288288

289289
def test_tool_contact(self):
290-
version_info = self.get_version.call()
290+
version_info = self.get_robot_software_version.call()
291291
if version_info.major >= 5:
292292
start_response = self.start_tool_contact.call()
293293
self.assertEqual(start_response.success,True)

0 commit comments

Comments
 (0)