Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Implemented get version service #695

Merged
merged 5 commits into from
Sep 20, 2024
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 4 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/GetRobotSoftwareVersion.h>

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

std::unique_ptr<urcl::UrDriver> ur_driver_;
std::unique_ptr<DashboardClientROS> dashboard_client_;
Expand All @@ -239,6 +242,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_robot_software_version_srv;

hardware_interface::JointStateInterface js_interface_;
scaled_controllers::ScaledPositionJointInterface spj_interface_;
Expand Down
15 changes: 15 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,10 @@ 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_robot_software_version_srv =
robot_hw_nh.advertiseService("get_robot_software_version", &HardwareInterface::getRobotSoftwareVersion, this);

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

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

bool HardwareInterface::getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req,
ur_msgs::GetRobotSoftwareVersionResponse& 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
10 changes: 9 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, GetRobotSoftwareVersion
from ur_msgs.msg import IOStates

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

self.get_robot_software_version = rospy.ServiceProxy("ur_hardware_interface/get_robot_software_version", GetRobotSoftwareVersion)
try:
self.get_robot_software_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.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