Skip to content

Commit 0d8db31

Browse files
authored
Add launchfiles for ur7e and ur12e (#743)
1 parent 3130de9 commit 0d8db31

File tree

2 files changed

+59
-0
lines changed

2 files changed

+59
-0
lines changed
Lines changed: 30 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,30 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
4+
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
5+
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
6+
<arg name="reverse_ip" default="" doc="IP of the driver, if set to empty it will detect it automatically."/>
7+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
8+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
9+
<arg name="trajectory_port" default="50003" doc="Port that will be opened by the driver to allow trajectory forwarding."/>
10+
<arg name="script_command_port" default="50004" doc="Port that will be opened by the driver to allow forwarding script commands to the robot."/>
11+
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
12+
<arg name="controllers" default="joint_state_controller scaled_pos_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
13+
<arg name="stopped_controllers" default="pos_joint_traj_controller joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
14+
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur12e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
15+
<arg name="robot_description_file" default="$(find ur_description)/launch/load_ur12e.launch" doc="Robot description launch file."/>
16+
<arg name="kinematics_config" default="$(find ur_description)/config/ur12e/default_kinematics.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
17+
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>
18+
<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."/>
19+
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
20+
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
21+
<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."/>
22+
<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."/>
23+
<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."/>
24+
<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."/>
25+
<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."/>
26+
<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."/>
27+
<arg name="ur_hardware_interface_node_required" default="true" doc="Shut down ros environment if ur_hardware_interface-node dies."/>
28+
29+
<include file="$(find ur_robot_driver)/launch/ur_common.launch" pass_all_args="true"/>
30+
</launch>
Lines changed: 29 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,29 @@
1+
<?xml version="1.0"?>
2+
<launch>
3+
<arg name="debug" default="false" doc="Debug flag that will get passed on to ur_common.launch"/>
4+
<arg name="robot_ip" doc="IP address by which the robot can be reached."/>
5+
<arg name="reverse_ip" default="" doc="IP of the driver, if set to empty it will detect it automatically."/>
6+
<arg name="reverse_port" default="50001" doc="Port that will be opened by the driver to allow direct communication between the driver and the robot controller."/>
7+
<arg name="script_sender_port" default="50002" doc="The driver will offer an interface to receive the program's URScript on this port. If the robot cannot connect to this port, `External Control` will stop immediately."/>
8+
<arg name="trajectory_port" default="50003" doc="Port that will be opened by the driver to allow trajectory forwarding."/>
9+
<arg name="script_command_port" default="50004" doc="Port that will be opened by the driver to allow forwarding script commands to the robot."/>
10+
<arg name="tf_prefix" default="" doc="tf_prefix used for the robot."/>
11+
<arg name="controllers" default="joint_state_controller scaled_pos_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
12+
<arg name="stopped_controllers" default="pos_joint_traj_controller joint_group_vel_controller" doc="Controllers that are initally loaded, but not started."/>
13+
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur7e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
14+
<arg name="robot_description_file" default="$(find ur_description)/launch/load_ur7e.launch" doc="Robot description launch file."/>
15+
<arg name="kinematics_config" default="$(find ur_description)/config/ur7e/default_kinematics.yaml" doc="Kinematics config file used for calibration correction. This will be used to verify the robot's calibration is matching the robot_description."/>
16+
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>
17+
<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."/>
18+
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
19+
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
20+
<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."/>
21+
<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."/>
22+
<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."/>
23+
<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."/>
24+
<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."/>
25+
<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."/>
26+
<arg name="ur_hardware_interface_node_required" default="true" doc="Shut down ros environment if ur_hardware_interface-node dies."/>
27+
28+
<include file="$(find ur_robot_driver)/launch/ur_common.launch" pass_all_args="true" />
29+
</launch>

0 commit comments

Comments
 (0)