Skip to content

Commit

Permalink
Implemented get version service, and integrated it with the tool cont…
Browse files Browse the repository at this point in the history
…act test
  • Loading branch information
URJala committed Apr 11, 2024
1 parent 4479de9 commit 1cc6e4a
Show file tree
Hide file tree
Showing 3 changed files with 56 additions and 1 deletion.
3 changes: 3 additions & 0 deletions ur_robot_driver/include/ur_robot_driver/hardware_interface.h
Original file line number Diff line number Diff line change
Expand Up @@ -54,6 +54,7 @@
#include <ur_msgs/SetIO.h>
#include <ur_msgs/SetSpeedSliderFraction.h>
#include <ur_msgs/SetPayload.h>
#include <ur_msgs/GetVersion.h>

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

std::unique_ptr<urcl::UrDriver> ur_driver_;
std::unique_ptr<DashboardClientROS> dashboard_client_;
Expand All @@ -239,6 +241,7 @@ class HardwareInterface : public hardware_interface::RobotHW
ros::ServiceServer tare_sensor_srv_;
ros::ServiceServer set_payload_srv_;
ros::ServiceServer activate_spline_interpolation_srv_;
ros::ServiceServer get_version_srv;

hardware_interface::JointStateInterface js_interface_;
scaled_controllers::ScaledPositionJointInterface spj_interface_;
Expand Down
13 changes: 13 additions & 0 deletions ur_robot_driver/src/hardware_interface.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -460,6 +460,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
activate_spline_interpolation_srv_ = robot_hw_nh.advertiseService(
"activate_spline_interpolation", &HardwareInterface::activateSplineInterpolation, this);

// Calling this service will return the software version of the robot.
get_version_srv = robot_hw_nh.advertiseService("get_version", &HardwareInterface::getVersion, this);

ur_driver_->startRTDECommunication();
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");

Expand Down Expand Up @@ -1175,6 +1178,16 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set
return true;
}

bool HardwareInterface::getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res)
{
urcl::VersionInformation version_info = this->ur_driver_->getVersion();
res.major = version_info.major;
res.minor = version_info.minor;
res.bugfix = version_info.bugfix;
res.build = version_info.build;
return true;
}

void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
{
std::string str = msg->data;
Expand Down
41 changes: 40 additions & 1 deletion ur_robot_driver/test/integration_test.py
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
from std_srvs.srv import Trigger, TriggerRequest
import tf
from trajectory_msgs.msg import JointTrajectoryPoint
from ur_msgs.srv import SetIO, SetIORequest
from ur_msgs.srv import SetIO, SetIORequest, GetVersion
from ur_msgs.msg import IOStates

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

self.get_version = rospy.ServiceProxy("ur_hardware_interface/get_version", GetVersion)
try:
self.get_version.wait_for_service(timeout)
except rospy.exceptions.ROSException as err:
self.fail(
"Could not reach 'get version' service. Make sure that the driver is actually running."
" Msg: {}".format(err))

self.start_tool_contact = rospy.ServiceProxy('ur_hardware_interface/start_tool_contact', Trigger)
try:
self.start_tool_contact.wait_for_service(timeout)
except rospy.exceptions.ROSException as err:
self.fail(
"Could not reach 'start tool contact' service. Make sure that the driver is actually running."
" Msg: {}".format(err))

self.end_tool_contact = rospy.ServiceProxy('ur_hardware_interface/end_tool_contact', Trigger)
try:
self.end_tool_contact.wait_for_service(timeout)
except rospy.exceptions.ROSException as err:
self.fail(
"Could not reach 'end tool contact' service. Make sure that the driver is actually running."
" Msg: {}".format(err))

self.script_publisher = rospy.Publisher("/ur_hardware_interface/script_command", std_msgs.msg.String, queue_size=1)
self.tf_listener = tf.TransformListener()
self.twist_pub = rospy.Publisher("/twist_controller/command", geometry_msgs.msg.Twist, queue_size=1)
Expand Down Expand Up @@ -262,6 +286,21 @@ def test_set_io(self):
messages += 1
self.assertEqual(pin_state, 1)

def test_tool_contact(self):
version_info = self.get_version.call()
if version_info.major >= 5:
start_response = self.start_tool_contact.call()
self.assertEqual(start_response.success,True)

end_response = self.end_tool_contact.call()
self.assertEqual(end_response.success, True)
else:
start_response = self.start_tool_contact.call()
self.assertEqual(start_response.success,False)

end_response = self.end_tool_contact.call()
self.assertEqual(end_response.success, False)

def test_cartesian_passthrough(self):
#### Power cycle the robot in order to make sure it is running correctly####
self.assertTrue(self.set_robot_to_mode(RobotMode.POWER_OFF))
Expand Down

0 comments on commit 1cc6e4a

Please sign in to comment.