diff --git a/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h b/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h index 8ef0a80..c227aa7 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h +++ b/ur_rtde_driver/include/ur_rtde_driver/ros/hardware_interface.h @@ -184,6 +184,7 @@ protected: bool setSpeedSlider(ur_msgs::SetSpeedSliderFractionRequest& req, ur_msgs::SetSpeedSliderFractionResponse& res); bool setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse& res); + bool resendRobotProgram(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res); void commandCallback(const std_msgs::StringConstPtr& msg); std::unique_ptr ur_driver_; @@ -229,6 +230,7 @@ protected: ros::ServiceServer set_speed_slider_srv_; ros::ServiceServer set_io_srv_; + ros::ServiceServer resend_robot_program_srv_; ros::Subscriber command_sub_; uint32_t runtime_state_; diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index 844fc25..de5f787 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -294,6 +294,12 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h // Service to set any of the robot's IOs set_io_srv_ = robot_hw_nh.advertiseService("set_io", &HardwareInterface::setIO, this); + if (headless_mode) + { + resend_robot_program_srv_ = + robot_hw_nh.advertiseService("resend_robot_program", &HardwareInterface::resendRobotProgram, this); + } + // Calling this service will make the "External Control" program node on the UR-Program return. deactivate_srv_ = robot_hw_nh.advertiseService("hand_back_control", &HardwareInterface::stopControl, this); @@ -657,6 +663,21 @@ bool HardwareInterface::setIO(ur_msgs::SetIORequest& req, ur_msgs::SetIOResponse return true; } +bool HardwareInterface::resendRobotProgram(std_srvs::TriggerRequest& req, std_srvs::TriggerResponse& res) +{ + res.success = ur_driver_->sendRobotProgram(); + if (res.success) + { + res.message = "Successfully resent robot program"; + } + else + { + res.message = "Could not resend robot program"; + } + + return true; +} + void HardwareInterface::commandCallback(const std_msgs::StringConstPtr& msg) { std::string str = msg->data;