mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +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
@@ -9,6 +9,7 @@
|
||||
<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="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
|
||||
<arg name="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -21,6 +22,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -20,6 +20,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="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
|
||||
|
||||
<arg name="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -32,6 +33,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
<arg name="tool_voltage" value="$(arg tool_voltage)"/>
|
||||
<arg name="tool_parity" value="$(arg tool_parity)"/>
|
||||
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
|
||||
|
||||
@@ -9,6 +9,7 @@
|
||||
<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="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
|
||||
<arg name="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -21,6 +22,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -18,6 +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_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="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -30,6 +31,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
<arg name="tool_voltage" value="$(arg tool_voltage)"/>
|
||||
<arg name="tool_parity" value="$(arg tool_parity)"/>
|
||||
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
|
||||
|
||||
@@ -9,6 +9,7 @@
|
||||
<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="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
|
||||
<arg name="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -21,6 +22,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
</include>
|
||||
|
||||
</launch>
|
||||
|
||||
@@ -18,6 +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_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="headless_mode" default="false"/>
|
||||
|
||||
<include file="$(find ur_rtde_driver)/launch/ur_common.launch">
|
||||
<arg name="debug" value="$(arg debug)"/>
|
||||
@@ -30,6 +31,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
<arg name="tool_voltage" value="$(arg tool_voltage)"/>
|
||||
<arg name="tool_parity" value="$(arg tool_parity)"/>
|
||||
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
|
||||
|
||||
@@ -18,6 +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="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="headless_mode" default="false"/>
|
||||
|
||||
<!-- robot model -->
|
||||
<include file="$(arg robot_description_file)">
|
||||
@@ -37,6 +38,7 @@
|
||||
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<arg name="controllers" value="$(arg controllers)"/>
|
||||
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
|
||||
<arg name="headless_mode" value="$(arg headless_mode)"/>
|
||||
<arg name="tool_voltage" value="$(arg tool_voltage)"/>
|
||||
<arg name="tool_parity" value="$(arg tool_parity)"/>
|
||||
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
|
||||
|
||||
@@ -24,6 +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_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="headless_mode" default="false"/>
|
||||
|
||||
<!-- 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">
|
||||
@@ -32,6 +33,7 @@
|
||||
<param name="script_file" value="$(arg urscript_file)"/>
|
||||
<param name="output_recipe_file" value="$(arg rtde_output_recipe_file)"/>
|
||||
<param name="input_recipe_file" value="$(arg rtde_input_recipe_file)"/>
|
||||
<param name="headless_mode" value="$(arg headless_mode)"/>
|
||||
<param name="tf_prefix" value="$(arg tf_prefix)"/>
|
||||
<param name="use_tool_communication" value="$(arg use_tool_communication)"/>
|
||||
<!--<param name="reverse_port" type="int" value="$(arg reverse_port)" />-->
|
||||
|
||||
Reference in New Issue
Block a user