Skip to content

Commit 08e7ca3

Browse files
committed
Added a service to setup the active payload
1 parent 5c02b0d commit 08e7ca3

File tree

3 files changed

+19
-0
lines changed

3 files changed

+19
-0
lines changed

ur_robot_driver/doc/ROS_INTERFACE.md

Lines changed: 4 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -744,6 +744,10 @@ When in headless mode, this sends the URScript program to the robot for executio
744744

745745
Service to set any of the robot's IOs
746746

747+
##### set_payload (ur_msgs/SetPayload)
748+
749+
Setup the mounted payload through a ROS service
750+
747751
##### set_speed_slider (ur_msgs/SetSpeedSliderFraction)
748752

749753
Set the speed slider fraction used by the robot's execution. Values should be between 0 and 1. Only set this smaller than 1 if you are using the scaled controllers (as by default) or you know what you're doing. Using this with other controllers might lead to unexpected behaviors.

ur_robot_driver/include/ur_robot_driver/ros/hardware_interface.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -214,6 +214,7 @@ class HardwareInterface : public hardware_interface::RobotHW
214214

215215
ros::ServiceServer deactivate_srv_;
216216
ros::ServiceServer tare_sensor_srv_;
217+
ros::ServiceServer set_payload_srv_;
217218

218219
hardware_interface::JointStateInterface js_interface_;
219220
ur_controllers::ScaledPositionJointInterface spj_interface_;

ur_robot_driver/src/ros/hardware_interface.cpp

Lines changed: 14 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -29,6 +29,8 @@
2929
#include "ur_robot_driver/ur/tool_communication.h"
3030
#include <ur_robot_driver/exceptions.h>
3131

32+
#include <ur_msgs/SetPayload.h>
33+
3234
#include <Eigen/Geometry>
3335

3436
using industrial_robot_status_interface::RobotMode;
@@ -379,6 +381,18 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
379381
ur_driver_->startRTDECommunication();
380382
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
381383

384+
// Setup the mounted payload through a ROS service
385+
set_payload_srv_ = robot_hw_nh.advertiseService<ur_msgs::SetPayload::Request, ur_msgs::SetPayload::Response>(
386+
"set_payload", [&](ur_msgs::SetPayload::Request& req, ur_msgs::SetPayload::Response& resp) {
387+
std::stringstream cmd;
388+
cmd << "sec setup():" << std::endl
389+
<< " set_payload(" << req.payload << ", [" << req.center_of_gravity.x << ", " << req.center_of_gravity.y
390+
<< ", " << req.center_of_gravity.z << "])" << std::endl
391+
<< "end";
392+
resp.success = this->ur_driver_->sendScript(cmd.str());
393+
return true;
394+
});
395+
382396
return true;
383397
}
384398

0 commit comments

Comments
 (0)