Skip to content

Commit cdf1881

Browse files
urmarpurfeex
authored andcommitted
Added service to set force mode through ROS
1 parent 481c932 commit cdf1881

File tree

2 files changed

+31
-0
lines changed

2 files changed

+31
-0
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -56,6 +56,7 @@
5656
#include <ur_msgs/SetSpeedSliderFraction.h>
5757
#include <ur_msgs/SetPayload.h>
5858
#include <ur_msgs/GetRobotSoftwareVersion.h>
59+
#include <ur_msgs/SetForceMode.h>
5960

6061
#include <cartesian_interface/cartesian_command_interface.h>
6162
#include <cartesian_interface/cartesian_state_handle.h>
@@ -220,6 +221,7 @@ class HardwareInterface : public hardware_interface::RobotHW
220221
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
221222
bool getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersionRequest& req,
222223
ur_msgs::GetRobotSoftwareVersionResponse& res);
224+
bool setForceMode(ur_msgs::SetForceModeRequest& req, ur_msgs::SetForceModeResponse& res);
223225

224226
std::unique_ptr<urcl::UrDriver> ur_driver_;
225227
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -245,6 +247,7 @@ class HardwareInterface : public hardware_interface::RobotHW
245247
ros::ServiceServer set_payload_srv_;
246248
ros::ServiceServer activate_spline_interpolation_srv_;
247249
ros::ServiceServer get_robot_software_version_srv;
250+
ros::ServiceServer set_force_mode_srv_;
248251

249252
hardware_interface::JointStateInterface js_interface_;
250253
scaled_controllers::ScaledPositionJointInterface spj_interface_;

ur_robot_driver/src/hardware_interface.cpp

Lines changed: 28 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -456,6 +456,9 @@ bool HardwareInterface::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_hw
456456
// Setup the mounted payload through a ROS service
457457
set_payload_srv_ = robot_hw_nh.advertiseService("set_payload", &HardwareInterface::setPayload, this);
458458

459+
// Calling this service will set the robot in force mode
460+
set_force_mode_srv_ = robot_hw_nh.advertiseService("set_force_mode", &HardwareInterface::setForceMode, this);
461+
459462
// Call this to activate or deactivate using spline interpolation locally on the UR controller, when forwarding
460463
// trajectories to the UR robot.
461464
activate_spline_interpolation_srv_ = robot_hw_nh.advertiseService(
@@ -1201,6 +1204,31 @@ bool HardwareInterface::getRobotSoftwareVersion(ur_msgs::GetRobotSoftwareVersion
12011204
return true;
12021205
}
12031206

1207+
bool HardwareInterface::setForceMode(ur_msgs::SetForceModeRequest& req, ur_msgs::SetForceModeResponse& res)
1208+
{
1209+
if (req.task_frame.size() != 6 || req.selection_vector.size() != 6 || req.wrench.size() != 6 ||
1210+
req.limits.size() != 6)
1211+
{
1212+
URCL_LOG_WARN("Size of received SetForceMode message is wrong");
1213+
res.success = false;
1214+
return false;
1215+
}
1216+
urcl::vector6d_t task_frame;
1217+
urcl::vector6uint32_t selection_vector;
1218+
urcl::vector6d_t wrench;
1219+
urcl::vector6d_t limits;
1220+
for (size_t i = 0; i < 6; i++)
1221+
{
1222+
task_frame[i] = req.task_frame[i];
1223+
selection_vector[i] = req.selection_vector[i];
1224+
wrench[i] = req.wrench[i];
1225+
limits[i] = req.limits[i];
1226+
}
1227+
unsigned int type = req.type;
1228+
res.success = this->ur_driver_->startForceMode(task_frame, selection_vector, wrench, type, limits);
1229+
return res.success;
1230+
}
1231+
12041232
void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg)
12051233
{
12061234
std::string str = msg->data;

0 commit comments

Comments
 (0)