1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-12 19:10:47 +02:00

added RTDE writer class and required interfaces for use in the hardware interface

This commit is contained in:
Tristan Schnell
2019-07-25 18:30:28 +02:00
parent da53c3b45c
commit 8bacdc0fe1
13 changed files with 208 additions and 18 deletions

View File

@@ -55,19 +55,25 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
joint_efforts_ = { { 0, 0, 0, 0, 0, 0 } };
robot_ip_ = robot_hw_nh.param<std::string>("robot_ip", "192.168.56.101");
std::string script_filename;
std::string recipe_filename;
std::string output_recipe_filename;
std::string input_recipe_filename;
if (!robot_hw_nh.getParam("script_file", script_filename))
{
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("script_file") << " not given.");
return false;
}
if (!robot_hw_nh.getParam("recipe_file", recipe_filename))
if (!robot_hw_nh.getParam("output_recipe_file", output_recipe_filename))
{
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("recipe_file") << " not given.");
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("output_recipe_file") << " not given.");
return false;
}
if (!robot_hw_nh.getParam("input_recipe_file", input_recipe_filename))
{
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("input_recipe_file") << " not given.");
return false;
}
std::string tf_prefix = robot_hw_nh.param<std::string>("tf_prefix", "");
program_state_pub_ = robot_hw_nh.advertise<std_msgs::Bool>("robot_program_running", 10, true);
@@ -135,7 +141,7 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
ROS_INFO_STREAM("Initializing urdriver");
try
{
ur_driver_.reset(new UrDriver(robot_ip_, script_filename, recipe_filename,
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));
}