1
0
mirror of https://gitlab.com/obbart/universal_robots_ros_driver.git synced 2026-04-10 01:50:46 +02:00

Added doc for headless_mode attribute

This commit is contained in:
Felix Mauch
2019-09-30 17:50:03 +02:00
parent 888db15012
commit 39b4d23049
11 changed files with 57 additions and 13 deletions

View File

@@ -40,10 +40,9 @@ on details.
**Note to e-Series users:** **Note to e-Series users:**
The robot won't accept script code from a remote source unless the robot is put into The robot won't accept script code from a remote source unless the robot is put into
*remote_control-mode*. However, if put into *remote_control-mode*, the program containing the *remote_control-mode*. However, if put into *remote_control-mode*, the program containing the
**External Control** program node can't be started from the panel. In the future, this will be **External Control** program node can't be started from the panel. If this behavior is required,
supported in the *headless* mode which doesn't require a panel being connected. Until that, a please use the headless mode that does not require having a program running on the teach pendant.
possible workaround is to use a third party dashboard client (e.g. [ur_dash](https://github.com/gocarter/ur_dash)) Note: The current headless mode doesn't offer the full functionality of the teach pendant.
to start the program through the dashboard server.
For using the **tool communication interface** on e-Series robots, a `socat` script is prepared to For using the **tool communication interface** on e-Series robots, a `socat` script is prepared to
forward the robot's tool communication interface to a local device on the ROS PC. See [the tool forward the robot's tool communication interface to a local device on the ROS PC. See [the tool

View File

@@ -20,6 +20,10 @@ Standalone launchfile to startup a ur3e. This requires a robot reachable via a n
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_e_description)/config/ur3e_default.yaml") * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur3e_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -97,6 +101,10 @@ Standalone launchfile to startup a ur10 robot. This requires a robot reachable v
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_description)/config/ur10_default.yaml") * "**kinematics_config**" (default: "$(find ur_description)/config/ur10_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -138,6 +146,10 @@ Robot bringup launchfile without the robot description. Include this, if you wan
If set to true, will start the driver inside gdb If set to true, will start the driver inside gdb
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" * "**kinematics_config**"
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Pass the same config file that is passed to the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Pass the same config file that is passed to the robot_description.
@@ -223,6 +235,10 @@ Launchfile that starts a robot description with robot_state publisher and the dr
Debug flag that will get passed on to ur_control.launch Debug flag that will get passed on to ur_control.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" * "**kinematics_config**"
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -300,6 +316,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_description)/config/ur5_default.yaml") * "**kinematics_config**" (default: "$(find ur_description)/config/ur5_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -341,6 +361,10 @@ Standalone launchfile to startup a ur5e robot. This requires a robot reachable v
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_e_description)/config/ur5e_default.yaml") * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur5e_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -418,6 +442,10 @@ Standalone launchfile to startup a ur5 robot. This requires a robot reachable vi
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_description)/config/ur3_default.yaml") * "**kinematics_config**" (default: "$(find ur_description)/config/ur3_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -459,6 +487,10 @@ Standalone launchfile to startup a ur10e robot. This requires a robot reachable
Debug flag that will get passed on to ur_common.launch Debug flag that will get passed on to ur_common.launch
* "**headless_mode**" (default: "false")
Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot.
* "**kinematics_config**" (default: "$(find ur_e_description)/config/ur10e_default.yaml") * "**kinematics_config**" (default: "$(find ur_e_description)/config/ur10e_default.yaml")
Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description. Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description.
@@ -529,6 +561,11 @@ This is the actual driver node containing the ROS-Control stack. Interfaces docu
Calling this service will make the "External Control" program node on the UR-Program return. Calling this service will make the "External Control" program node on the UR-Program return.
* "**resend_robot_program**" ([std_srvs/Trigger](http://docs.ros.org/api/std_srvs/html/srv/Trigger.html))
When in headless mode, this sends the URScript program to the robot for execution. Use this
after the program has been interrupted, e.g. by a protective- or EM-stop.
* "**set_io**" (ur_msgs/SetIO) * "**set_io**" (ur_msgs/SetIO)
Service to set any of the robot's IOs Service to set any of the robot's IOs
@@ -542,6 +579,10 @@ This is the actual driver node containing the ROS-Control stack. Interfaces docu
Names of the joints. Usually, this is given in the controller config file. Names of the joints. Usually, this is given in the controller config file.
* "**headless_mode**"
Start robot in headless mode. This does not require the 'External Control' URCap to be running on the robot, but this will send the URScript to the robot directly. On e-Series robots this requires the robot to run in 'remote-control' mode.
* "**input_recipe_file**" * "**input_recipe_file**"
Path to the file containing the recipe used for requesting RTDE inputs. This is a required parameter. Path to the file containing the recipe used for requesting RTDE inputs. This is a required parameter.

View File

@@ -9,7 +9,7 @@
<arg name="robot_description_file" default="$(find ur_description)/launch/ur10_upload.launch" doc="Robot description launch file."/> <arg name="robot_description_file" default="$(find ur_description)/launch/ur10_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_description)/config/ur10_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/> <arg name="kinematics_config" default="$(find ur_description)/config/ur10_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -19,8 +19,7 @@
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<arg name="headless_mode" default="false"/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -9,7 +9,7 @@
<arg name="robot_description_file" default="$(find ur_description)/launch/ur3_upload.launch" doc="Robot description launch file."/> <arg name="robot_description_file" default="$(find ur_description)/launch/ur3_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_description)/config/ur3_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/> <arg name="kinematics_config" default="$(find ur_description)/config/ur3_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -18,7 +18,7 @@
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -9,7 +9,7 @@
<arg name="robot_description_file" default="$(find ur_description)/launch/ur5_upload.launch" doc="Robot description launch file."/> <arg name="robot_description_file" default="$(find ur_description)/launch/ur5_upload.launch" doc="Robot description launch file."/>
<arg name="kinematics_config" default="$(find ur_description)/config/ur5_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/> <arg name="kinematics_config" default="$(find ur_description)/config/ur5_default.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -18,7 +18,7 @@
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<include file="$(find ur_rtde_driver)/launch/ur_common.launch"> <include file="$(find ur_rtde_driver)/launch/ur_common.launch">
<arg name="debug" value="$(arg debug)"/> <arg name="debug" value="$(arg debug)"/>

View File

@@ -18,7 +18,7 @@
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="robot_description_file" doc="Robot description launch file."/> <arg name="robot_description_file" doc="Robot description launch file."/>
<arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/> <arg name="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<!-- robot model --> <!-- robot model -->
<include file="$(arg robot_description_file)"> <include file="$(arg robot_description_file)">

View File

@@ -24,7 +24,7 @@
<arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tx_idle_chars" default="3.5" doc="Number of idle chars in TX channel used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_device_name" default="/tmp/ttyUR" doc="Local device name used for tool communication. Only used, when `use_tool_communication` is set to true."/>
<arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/> <arg name="tool_tcp_port" default="54321" doc="Port on which the robot controller publishes the tool comm interface. Only used, when `use_tool_communication` is set to true."/>
<arg name="headless_mode" default="false"/> <arg name="headless_mode" default="false" doc="Automatically send URScript to robot to execute. On e-Series this does require the robot to be in 'remote-control' mode. With this, the URCap is not needed on the robot."/>
<!-- Load hardware interface --> <!-- Load hardware interface -->
<node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_rtde_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true"> <node name="ur_hardware_interface" pkg="ur_rtde_driver" type="ur_rtde_driver_node" output="screen" launch-prefix="$(arg launch_prefix)" required="true">

View File

@@ -90,6 +90,9 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
} }
bool headless_mode; bool headless_mode;
// Start robot in headless mode. This does not require the 'External Control' URCap to be running
// on the robot, but this will send the URScript to the robot directly. On e-Series robots this
// requires the robot to run in 'remote-control' mode.
if (!robot_hw_nh.getParam("headless_mode", headless_mode)) if (!robot_hw_nh.getParam("headless_mode", headless_mode))
{ {
ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("headless_mode") << " not given."); ROS_ERROR_STREAM("Required parameter " << robot_hw_nh.resolveName("headless_mode") << " not given.");
@@ -296,6 +299,8 @@ bool HardwareInterface ::init(ros::NodeHandle& root_nh, ros::NodeHandle& robot_h
if (headless_mode) if (headless_mode)
{ {
// When in headless mode, this sends the URScript program to the robot for execution. Use this
// after the program has been interrupted, e.g. by a protective- or EM-stop.
resend_robot_program_srv_ = resend_robot_program_srv_ =
robot_hw_nh.advertiseService("resend_robot_program", &HardwareInterface::resendRobotProgram, this); robot_hw_nh.advertiseService("resend_robot_program", &HardwareInterface::resendRobotProgram, this);
} }