Skip to content

Commit 3da9ae1

Browse files
committed
Added a service to setup the active payload
1 parent 72453e1 commit 3da9ae1

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
@@ -751,6 +751,10 @@ Service to set any of the robot's IOs
751751
##### set_speed_slider (ur_msgs/SetSpeedSliderFraction)
752752

753753
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.
754+
755+
#### set_payload (ur_msgs/SetPayload)
756+
757+
Setup the mounted payload through a ROS service
754758

755759
##### zero_ftsensor ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html))
756760

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;
@@ -383,6 +385,18 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
383385
ur_driver_->startRTDECommunication();
384386
ROS_INFO_STREAM_NAMED("hardware_interface", "Loaded ur_robot_driver hardware_interface");
385387

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

0 commit comments

Comments
 (0)