mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 10:00:48 +02:00
Implemented optional headless mode that directly sends the robot program via its interface, avoiding URCaps usage
This commit is contained in:
committed by
Felix Mauch
parent
74e98d6af1
commit
ea0908ed58
@@ -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)
|
||||
{
|
||||
|
||||
@@ -34,6 +34,7 @@
|
||||
#include "ur_rtde_driver/exceptions.h"
|
||||
#include "ur_rtde_driver/primary/primary_parser.h"
|
||||
#include <memory>
|
||||
#include <sstream>
|
||||
|
||||
#include <ur_rtde_driver/ur/calibration_checker.h>
|
||||
|
||||
@@ -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<void(bool)> handle_program_state,
|
||||
std::function<void(bool)> handle_program_state, bool headless_mode,
|
||||
std::unique_ptr<ToolCommSetup> 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
|
||||
|
||||
Reference in New Issue
Block a user