mirror of
https://gitlab.com/obbart/universal_robots_ros_driver.git
synced 2026-04-10 01:50:46 +02:00
Documented launch files
This commit is contained in:
@@ -2,28 +2,28 @@
|
||||
<launch>
|
||||
|
||||
<!-- GDB functionality -->
|
||||
<arg name="debug" default="false" />
|
||||
<arg name="debug" default="false" doc="If set to true, will start the driver inside gdb" />
|
||||
<arg unless="$(arg debug)" name="launch_prefix" value="" />
|
||||
<arg if="$(arg debug)" name="launch_prefix" value="gdb --ex run --args" />
|
||||
|
||||
<arg name="use_tool_communication"/>
|
||||
<arg name="controller_config_file"/>
|
||||
<arg name="robot_ip"/>
|
||||
<arg name="kinematics_config"/>
|
||||
<arg name="tf_prefix" default="" />
|
||||
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller"/>
|
||||
<arg name="stopped_controllers" default="pos_traj_controller"/>
|
||||
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript"/>
|
||||
<arg name="rtde_output_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_output_recipe.txt"/>
|
||||
<arg name="rtde_input_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_input_recipe.txt"/>
|
||||
<arg name="tool_voltage" default="0"/>
|
||||
<arg name="tool_parity" default="0"/>
|
||||
<arg name="tool_baud_rate" default="115200"/>
|
||||
<arg name="tool_stop_bits" default="1"/>
|
||||
<arg name="tool_rx_idle_chars" default="1.5"/>
|
||||
<arg name="tool_tx_idle_chars" default="3.5"/>
|
||||
<arg name="tool_device_name" default="/tmp/ttyUR"/>
|
||||
<arg name="tool_tcp_port" default="54321"/>
|
||||
<arg name="use_tool_communication" doc="On e-Series robots tool communication can be enabled with this argument"/>
|
||||
<arg name="controller_config_file" doc="Config file used for defining the ROS-Control controllers."/>
|
||||
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
|
||||
<arg name="kinematics_config" doc="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."/>
|
||||
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
|
||||
<arg name="controllers" default="joint_state_controller scaled_pos_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
|
||||
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
|
||||
<arg name="urscript_file" default="$(find ur_rtde_driver)/resources/servoj.urscript" doc="Path to URScript that will be sent to the robot and that forms the main control program."/>
|
||||
<arg name="rtde_output_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_output_recipe.txt" doc="Recipe file used for the RTDE-outputs. Only change this if you know what you're doing."/>
|
||||
<arg name="rtde_input_recipe_file" default="$(find ur_rtde_driver)/resources/rtde_input_recipe.txt" doc="Recipe file used for the RTDE-inputs. Only change this if you know what you're doing."/>
|
||||
<arg name="tool_voltage" default="0" doc="Tool voltage set at the beginning of the UR program. Only used, when `use_tool_communication` is set to true."/>
|
||||
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
|
||||
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
|
||||
<arg name="tool_stop_bits" default="1" doc="Number of stop bits used for tool communication. Only used, when `use_tool_communication` is set to true."/>
|
||||
<arg name="tool_rx_idle_chars" default="1.5" doc="Number of idle chars in RX 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_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."/>
|
||||
|
||||
<!-- 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">
|
||||
|
||||
Reference in New Issue
Block a user