diff --git a/src/ur_ros_wrapper.cpp b/src/ur_ros_wrapper.cpp index 48c9a4c..c9196d8 100644 --- a/src/ur_ros_wrapper.cpp +++ b/src/ur_ros_wrapper.cpp @@ -32,15 +32,18 @@ class RosWrapper { protected: + UrDriver robot_; + std::condition_variable msg_cond_; ros::NodeHandle nh_; actionlib::SimpleActionServer as_; actionlib::SimpleActionServer::Goal goal_; control_msgs::FollowJointTrajectoryFeedback feedback_; control_msgs::FollowJointTrajectoryResult result_; ros::Subscriber speedSub_; - UrDriver robot_; + ros::ServiceServer ioSrv_; + ros::ServiceServer payloadSrv_; std::thread* rt_publish_thread_; - std::condition_variable msg_cond_; + public: RosWrapper(std::string host) : as_(nh_, "follow_joint_trajectory", false), robot_(msg_cond_, host) { @@ -71,6 +74,9 @@ public: speedSub_ = nh_.subscribe("joint_speed", 1, &RosWrapper::speedInterface, this); + ioSrv_ = nh_.advertiseService("ur_driver/set_io", &RosWrapper::setIO, this); + payloadSrv_ = nh_.advertiseService("ur_driver/set_payload", &RosWrapper::setPayload, this); + rt_publish_thread_ = new std::thread( boost::bind(&RosWrapper::publishRTMsg, this)); ROS_INFO("The action server for this driver has been started"); @@ -145,7 +151,7 @@ private: return resp.success; } - bool setPayloaf(ur_msgs::SetPayloadRequest& req, + bool setPayload(ur_msgs::SetPayloadRequest& req, ur_msgs::SetPayloadResponse& resp) { robot_.setPayloaf(req.payload); resp.success = true;