Skip to content

Commit 5c4d560

Browse files
urmarpURJala
authored andcommitted
Changed setForce mode to startForceMode and endForceMode. Also made changes to account for changes in msg in PR (ros-industrial/ur_msgs#20)
1 parent cc55afa commit 5c4d560

File tree

2 files changed

+241
-204
lines changed

2 files changed

+241
-204
lines changed

ur_robot_driver/include/ur_robot_driver/hardware_interface.h

Lines changed: 4 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -216,7 +216,8 @@ class HardwareInterface : public hardware_interface::RobotHW
216216
void commandCallback(const std_msgs::StringConstPtr& msg);
217217
bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& res);
218218
bool activateSplineInterpolation(std_srvs::SetBoolRequest& req, std_srvs::SetBoolResponse& res);
219-
bool setForceMode(ur_msgs::SetForceModeRequest& req, ur_msgs::SetForceModeResponse& res);
219+
bool startForceMode(ur_msgs::SetForceModeRequest& req, ur_msgs::SetForceModeResponse& res);
220+
bool endForceMode(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res);
220221

221222
std::unique_ptr<urcl::UrDriver> ur_driver_;
222223
std::unique_ptr<DashboardClientROS> dashboard_client_;
@@ -241,7 +242,8 @@ class HardwareInterface : public hardware_interface::RobotHW
241242
ros::ServiceServer tare_sensor_srv_;
242243
ros::ServiceServer set_payload_srv_;
243244
ros::ServiceServer activate_spline_interpolation_srv_;
244-
ros::ServiceServer set_force_mode_srv_;
245+
ros::ServiceServer start_force_mode_srv_;
246+
ros::ServiceServer end_force_mode_srv_;
245247

246248
hardware_interface::JointStateInterface js_interface_;
247249
scaled_controllers::ScaledPositionJointInterface spj_interface_;

0 commit comments

Comments
 (0)