From 3d8638e1f3de870bf17a85ebf202329e1c6011d3 Mon Sep 17 00:00:00 2001 From: URJala Date: Thu, 22 Feb 2024 08:36:32 +0000 Subject: [PATCH 1/4] Added service to enable and disable tool contact. Also added service to get robot software version. --- .../ur_robot_driver/hardware_interface.h | 7 +++ ur_robot_driver/src/hardware_interface.cpp | 32 ++++++++++++++ ur_robot_driver/test/integration_test.py | 43 ++++++++++++++++++- 3 files changed, 80 insertions(+), 2 deletions(-) diff --git a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h index 5d435aaf3..42337fa98 100644 --- a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h +++ b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h @@ -54,6 +54,7 @@ #include #include #include +#include #include #include @@ -215,6 +216,9 @@ 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 startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); + bool endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); + bool getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res); std::unique_ptr ur_driver_; std::unique_ptr dashboard_client_; @@ -239,6 +243,9 @@ class HardwareInterface : public hardware_interface::RobotHW ros::ServiceServer tare_sensor_srv_; ros::ServiceServer set_payload_srv_; ros::ServiceServer activate_spline_interpolation_srv_; + ros::ServiceServer start_tool_contact_srv_; + ros::ServiceServer end_tool_contact_srv_; + ros::ServiceServer get_version_srv; hardware_interface::JointStateInterface js_interface_; scaled_controllers::ScaledPositionJointInterface spj_interface_; diff --git a/ur_robot_driver/src/hardware_interface.cpp b/ur_robot_driver/src/hardware_interface.cpp index 63ecdbe2b..2fd0b1caa 100644 --- a/ur_robot_driver/src/hardware_interface.cpp +++ b/ur_robot_driver/src/hardware_interface.cpp @@ -460,6 +460,16 @@ 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 enable the tool contact functionality on the robot. + start_tool_contact_srv_ = + robot_hw_nh.advertiseService("start_tool_contact", &HardwareInterface::startToolContact, this); + + // Calling this service will disable the tool contact functionality on the robot. + end_tool_contact_srv_ = robot_hw_nh.advertiseService("end_tool_contact", &HardwareInterface::endToolContact, 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"); @@ -1175,6 +1185,28 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set return true; } +bool HardwareInterface::startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) +{ + res.success = this->ur_driver_->startToolContact(); + return true; +} + +bool HardwareInterface::endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) +{ + res.success = this->ur_driver_->endToolContact(); + 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; diff --git a/ur_robot_driver/test/integration_test.py b/ur_robot_driver/test/integration_test.py index 1de325dbf..89314fb46 100755 --- a/ur_robot_driver/test/integration_test.py +++ b/ur_robot_driver/test/integration_test.py @@ -12,10 +12,10 @@ FollowJointTrajectoryResult, JointTolerance) from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode -from std_srvs.srv import Trigger, TriggerRequest +from std_srvs.srv import Trigger 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 ( @@ -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) @@ -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)) From e63390f190f3a72072a83f65e395f5d29ddc3876 Mon Sep 17 00:00:00 2001 From: URJala Date: Thu, 11 Apr 2024 09:32:03 +0000 Subject: [PATCH 2/4] Revert "Tool contact and get version" This reverts commit 7fdfc04bbd01ad12373c29a765b08a77b424bef7. --- .../ur_robot_driver/hardware_interface.h | 7 --- ur_robot_driver/src/hardware_interface.cpp | 32 -------------- ur_robot_driver/test/integration_test.py | 43 +------------------ 3 files changed, 2 insertions(+), 80 deletions(-) diff --git a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h index 42337fa98..5d435aaf3 100644 --- a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h +++ b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h @@ -54,7 +54,6 @@ #include #include #include -#include #include #include @@ -216,9 +215,6 @@ 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 startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); - bool endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); - bool getVersion(ur_msgs::GetVersionRequest& req, ur_msgs::GetVersionResponse& res); std::unique_ptr ur_driver_; std::unique_ptr dashboard_client_; @@ -243,9 +239,6 @@ class HardwareInterface : public hardware_interface::RobotHW ros::ServiceServer tare_sensor_srv_; ros::ServiceServer set_payload_srv_; ros::ServiceServer activate_spline_interpolation_srv_; - ros::ServiceServer start_tool_contact_srv_; - ros::ServiceServer end_tool_contact_srv_; - ros::ServiceServer get_version_srv; hardware_interface::JointStateInterface js_interface_; scaled_controllers::ScaledPositionJointInterface spj_interface_; diff --git a/ur_robot_driver/src/hardware_interface.cpp b/ur_robot_driver/src/hardware_interface.cpp index 2fd0b1caa..63ecdbe2b 100644 --- a/ur_robot_driver/src/hardware_interface.cpp +++ b/ur_robot_driver/src/hardware_interface.cpp @@ -460,16 +460,6 @@ 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 enable the tool contact functionality on the robot. - start_tool_contact_srv_ = - robot_hw_nh.advertiseService("start_tool_contact", &HardwareInterface::startToolContact, this); - - // Calling this service will disable the tool contact functionality on the robot. - end_tool_contact_srv_ = robot_hw_nh.advertiseService("end_tool_contact", &HardwareInterface::endToolContact, 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"); @@ -1185,28 +1175,6 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set return true; } -bool HardwareInterface::startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) -{ - res.success = this->ur_driver_->startToolContact(); - return true; -} - -bool HardwareInterface::endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) -{ - res.success = this->ur_driver_->endToolContact(); - 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; diff --git a/ur_robot_driver/test/integration_test.py b/ur_robot_driver/test/integration_test.py index 89314fb46..1de325dbf 100755 --- a/ur_robot_driver/test/integration_test.py +++ b/ur_robot_driver/test/integration_test.py @@ -12,10 +12,10 @@ FollowJointTrajectoryResult, JointTolerance) from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode -from std_srvs.srv import Trigger +from std_srvs.srv import Trigger, TriggerRequest import tf from trajectory_msgs.msg import JointTrajectoryPoint -from ur_msgs.srv import SetIO, SetIORequest, GetVersion +from ur_msgs.srv import SetIO, SetIORequest from ur_msgs.msg import IOStates from cartesian_control_msgs.msg import ( @@ -120,30 +120,6 @@ 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) @@ -286,21 +262,6 @@ 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)) From d14e7ff057d45a12c372d8919d3e707f813ff181 Mon Sep 17 00:00:00 2001 From: URJala Date: Thu, 11 Apr 2024 10:13:23 +0000 Subject: [PATCH 3/4] Implement tool contact and test --- .../ur_robot_driver/hardware_interface.h | 4 +++ ur_robot_driver/src/hardware_interface.cpp | 19 ++++++++++++++ ur_robot_driver/test/integration_test.py | 25 ++++++++++++++++++- 3 files changed, 47 insertions(+), 1 deletion(-) diff --git a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h index 5d435aaf3..50c84cc29 100644 --- a/ur_robot_driver/include/ur_robot_driver/hardware_interface.h +++ b/ur_robot_driver/include/ur_robot_driver/hardware_interface.h @@ -215,6 +215,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 startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); + bool endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); std::unique_ptr ur_driver_; std::unique_ptr dashboard_client_; @@ -239,6 +241,8 @@ class HardwareInterface : public hardware_interface::RobotHW ros::ServiceServer tare_sensor_srv_; ros::ServiceServer set_payload_srv_; ros::ServiceServer activate_spline_interpolation_srv_; + ros::ServiceServer start_tool_contact_srv_; + ros::ServiceServer end_tool_contact_srv_; hardware_interface::JointStateInterface js_interface_; scaled_controllers::ScaledPositionJointInterface spj_interface_; diff --git a/ur_robot_driver/src/hardware_interface.cpp b/ur_robot_driver/src/hardware_interface.cpp index 63ecdbe2b..0458c4a5d 100644 --- a/ur_robot_driver/src/hardware_interface.cpp +++ b/ur_robot_driver/src/hardware_interface.cpp @@ -460,6 +460,13 @@ 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 enable the tool contact functionality on the robot. + start_tool_contact_srv_ = + robot_hw_nh.advertiseService("start_tool_contact", &HardwareInterface::startToolContact, this); + + // Calling this service will disable the tool contact functionality on the robot. + end_tool_contact_srv_ = robot_hw_nh.advertiseService("end_tool_contact", &HardwareInterface::endToolContact, this); + ur_driver_->startRTDECommunication(); ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface"); @@ -1175,6 +1182,18 @@ bool HardwareInterface::setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::Set return true; } +bool HardwareInterface::startToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) +{ + res.success = this->ur_driver_->startToolContact(); + return true; +} + +bool HardwareInterface::endToolContact(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) +{ + res.success = this->ur_driver_->endToolContact(); + return true; +} + void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg) { std::string str = msg->data; diff --git a/ur_robot_driver/test/integration_test.py b/ur_robot_driver/test/integration_test.py index 1de325dbf..e6f878e4b 100755 --- a/ur_robot_driver/test/integration_test.py +++ b/ur_robot_driver/test/integration_test.py @@ -12,7 +12,7 @@ FollowJointTrajectoryResult, JointTolerance) from ur_dashboard_msgs.msg import SetModeAction, SetModeGoal, RobotMode -from std_srvs.srv import Trigger, TriggerRequest +from std_srvs.srv import Trigger import tf from trajectory_msgs.msg import JointTrajectoryPoint from ur_msgs.srv import SetIO, SetIORequest @@ -120,6 +120,22 @@ def init_robot(self): "actually running in headless mode." " 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) @@ -262,6 +278,13 @@ def test_set_io(self): messages += 1 self.assertEqual(pin_state, 1) + def test_tool_contact(self): + 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) + 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)) From 6157255bc5c1162ad9416ae1bdc2b4207403cc73 Mon Sep 17 00:00:00 2001 From: URJala Date: Thu, 11 Apr 2024 10:14:28 +0000 Subject: [PATCH 4/4] Fixed indentation --- ur_robot_driver/test/integration_test.py | 8 ++++---- 1 file changed, 4 insertions(+), 4 deletions(-) diff --git a/ur_robot_driver/test/integration_test.py b/ur_robot_driver/test/integration_test.py index e6f878e4b..9fd9a934e 100755 --- a/ur_robot_driver/test/integration_test.py +++ b/ur_robot_driver/test/integration_test.py @@ -279,11 +279,11 @@ def test_set_io(self): self.assertEqual(pin_state, 1) def test_tool_contact(self): - start_response = self.start_tool_contact.call() - self.assertEqual(start_response.success,True) + 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) + end_response = self.end_tool_contact.call() + self.assertEqual(end_response.success, True) def test_cartesian_passthrough(self): #### Power cycle the robot in order to make sure it is running correctly####