@@ -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+
12041232void HardwareInterface::commandCallback (const std_msgs::StringConstPtr& msg)
12051233{
12061234 std::string str = msg->data ;
0 commit comments