diff --git a/ur_rtde_driver/include/ur_rtde_driver/ur/ur_driver.h b/ur_rtde_driver/include/ur_rtde_driver/ur/ur_driver.h index be2f7b0..c820dbe 100644 --- a/ur_rtde_driver/include/ur_rtde_driver/ur/ur_driver.h +++ b/ur_rtde_driver/include/ur_rtde_driver/ur/ur_driver.h @@ -53,12 +53,13 @@ public: * \param output_recipe_file Filename where the output recipe is stored in. * \param input_recipe_file Filename where the input recipe is stored in. * \param handle_program_state Function handle to a callback on program state changes. + * \param headless_mode Parameter to control if the driver should be started in headless mode. * \param tool_comm_setup Configuration for using the tool communication. * \param calibration_checksum Expected checksum of calibration. Will be matched against the * calibration reported by the robot. */ UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, - const std::string& input_recipe_file, std::function handle_program_state, + const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, std::unique_ptr tool_comm_setup, const std::string& calibration_checksum = ""); /*! * \brief Constructs a new UrDriver object. @@ -68,13 +69,14 @@ public: * \param output_recipe_file Filename where the output recipe is stored in. * \param input_recipe_file Filename where the input recipe is stored in. * \param handle_program_state Function handle to a callback on program state changes. + * \param headless_mode Parameter to control if the driver should be started in headless mode. * \param calibration_checksum Expected checksum of calibration. Will be matched against the * calibration reported by the robot. */ UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, - const std::string& input_recipe_file, std::function handle_program_state, + const std::string& input_recipe_file, std::function handle_program_state, bool headless_mode, const std::string& calibration_checksum = "") - : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, + : UrDriver(robot_ip, script_file, output_recipe_file, input_recipe_file, handle_program_state, headless_mode, std::unique_ptr{}, calibration_checksum) { } @@ -154,6 +156,15 @@ public: */ bool sendScript(const std::string& program); + /*! + * \brief Sends the external control program to the robot. + * + * Only for use in headless mode, as it replaces the use of the URCaps program. + * + * \returns true on successful upload, false otherwise + */ + bool sendRobotProgram(); + private: std::string readScriptFile(const std::string& filename); std::string readKeepalive(); @@ -176,6 +187,8 @@ private: std::function handle_program_state_; std::string robot_ip_; + bool in_headless_mode_; + std::string full_robot_program_; }; } // namespace ur_driver #endif // ifndef UR_RTDE_DRIVER_UR_UR_DRIVER_H_INCLUDED diff --git a/ur_rtde_driver/launch/ur10_bringup.launch b/ur_rtde_driver/launch/ur10_bringup.launch index 6111d51..46888a2 100644 --- a/ur_rtde_driver/launch/ur10_bringup.launch +++ b/ur_rtde_driver/launch/ur10_bringup.launch @@ -9,6 +9,7 @@ + @@ -21,6 +22,7 @@ + diff --git a/ur_rtde_driver/launch/ur10e_bringup.launch b/ur_rtde_driver/launch/ur10e_bringup.launch index feb898b..07376b0 100644 --- a/ur_rtde_driver/launch/ur10e_bringup.launch +++ b/ur_rtde_driver/launch/ur10e_bringup.launch @@ -20,6 +20,7 @@ + @@ -32,6 +33,7 @@ + diff --git a/ur_rtde_driver/launch/ur3_bringup.launch b/ur_rtde_driver/launch/ur3_bringup.launch index 05cbbbb..7453427 100644 --- a/ur_rtde_driver/launch/ur3_bringup.launch +++ b/ur_rtde_driver/launch/ur3_bringup.launch @@ -9,6 +9,7 @@ + @@ -21,6 +22,7 @@ + diff --git a/ur_rtde_driver/launch/ur3e_bringup.launch b/ur_rtde_driver/launch/ur3e_bringup.launch index feb5dcd..fcf4ff0 100644 --- a/ur_rtde_driver/launch/ur3e_bringup.launch +++ b/ur_rtde_driver/launch/ur3e_bringup.launch @@ -18,6 +18,7 @@ + @@ -30,6 +31,7 @@ + diff --git a/ur_rtde_driver/launch/ur5_bringup.launch b/ur_rtde_driver/launch/ur5_bringup.launch index fb292e6..841d6a5 100644 --- a/ur_rtde_driver/launch/ur5_bringup.launch +++ b/ur_rtde_driver/launch/ur5_bringup.launch @@ -9,6 +9,7 @@ + @@ -21,6 +22,7 @@ + diff --git a/ur_rtde_driver/launch/ur5e_bringup.launch b/ur_rtde_driver/launch/ur5e_bringup.launch index f2326b5..3223fcd 100644 --- a/ur_rtde_driver/launch/ur5e_bringup.launch +++ b/ur_rtde_driver/launch/ur5e_bringup.launch @@ -18,6 +18,7 @@ + @@ -30,6 +31,7 @@ + diff --git a/ur_rtde_driver/launch/ur_common.launch b/ur_rtde_driver/launch/ur_common.launch index 76e03f1..5997b86 100644 --- a/ur_rtde_driver/launch/ur_common.launch +++ b/ur_rtde_driver/launch/ur_common.launch @@ -18,6 +18,7 @@ + @@ -37,6 +38,7 @@ + diff --git a/ur_rtde_driver/launch/ur_control.launch b/ur_rtde_driver/launch/ur_control.launch index 9da4898..408ecbc 100644 --- a/ur_rtde_driver/launch/ur_control.launch +++ b/ur_rtde_driver/launch/ur_control.launch @@ -24,6 +24,7 @@ + @@ -32,6 +33,7 @@ + diff --git a/ur_rtde_driver/src/ros/hardware_interface.cpp b/ur_rtde_driver/src/ros/hardware_interface.cpp index 2cab893..844fc25 100644 --- a/ur_rtde_driver/src/ros/hardware_interface.cpp +++ b/ur_rtde_driver/src/ros/hardware_interface.cpp @@ -89,6 +89,13 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h return false; } + bool headless_mode; + if (!robot_hw_nh.getParam("headless_mode", headless_mode)) + { + ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("headless_mode") << " not given."); + return false; + } + // Whenever the runtime state of the "External Control" program node in the UR-program changes, a // message gets published here. So this is equivalent to the information whether the robot accepts // commands from ROS side. @@ -195,7 +202,7 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h { ur_driver_.reset(new UrDriver(robot_ip_, script_filename, output_recipe_filename, input_recipe_filename, std::bind(&HardwareInterface::handleRobotProgramState, this, std::placeholders::_1), - std::move(tool_comm_setup), calibration_checksum)); + headless_mode, std::move(tool_comm_setup), calibration_checksum)); } catch (ur_driver::ToolCommNotAvailable& e) { diff --git a/ur_rtde_driver/src/ur/ur_driver.cpp b/ur_rtde_driver/src/ur/ur_driver.cpp index 9923227..8894a17 100644 --- a/ur_rtde_driver/src/ur/ur_driver.cpp +++ b/ur_rtde_driver/src/ur/ur_driver.cpp @@ -34,6 +34,7 @@ #include "ur_rtde_driver/exceptions.h" #include "ur_rtde_driver/primary/primary_parser.h" #include +#include #include @@ -48,7 +49,7 @@ static const std::string SERVER_PORT_REPLACE("{{SERVER_PORT_REPLACE}}"); ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& script_file, const std::string& output_recipe_file, const std::string& input_recipe_file, - std::function handle_program_state, + std::function handle_program_state, bool headless_mode, std::unique_ptr tool_comm_setup, const std::string& calibration_checksum) : servoj_time_(0.008) , servoj_gain_(2000) @@ -113,9 +114,25 @@ ur_driver::UrDriver::UrDriver(const std::string& robot_ip, const std::string& sc } prog.replace(prog.find(BEGIN_REPLACE), BEGIN_REPLACE.length(), begin_replace.str()); - script_sender_.reset(new comm::ScriptSender(script_sender_port, prog)); - script_sender_->start(); - LOG_DEBUG("Created script sender"); + in_headless_mode_ = headless_mode; + if (in_headless_mode_) + { + full_robot_program_ = "def externalControl():\n"; + std::istringstream prog_stream(prog); + std::string line; + while (std::getline(prog_stream, line)) + { + full_robot_program_ += "\t" + line + "\n"; + } + full_robot_program_ += "end\n"; + sendRobotProgram(); + } + else + { + script_sender_.reset(new comm::ScriptSender(script_sender_port, prog)); + script_sender_->start(); + LOG_DEBUG("Created script sender"); + } reverse_port_ = reverse_port; watchdog_thread_ = std::thread(&UrDriver::startWatchdog, this); @@ -256,4 +273,17 @@ bool UrDriver::sendScript(const std::string& program) LOG_ERROR("Could not send program to robot"); return false; } + +bool UrDriver::sendRobotProgram() +{ + if (in_headless_mode_) + { + return sendScript(full_robot_program_); + } + else + { + LOG_ERROR("Tried to send robot program directly while not in headless mode"); + return false; + } +} } // namespace ur_driver