Skip to content

Commit f880ca9

Browse files
author
Felix Exner
committed
Added ur16 support
1 parent ff63674 commit f880ca9

File tree

2 files changed

+110
-0
lines changed

2 files changed

+110
-0
lines changed
Lines changed: 62 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,62 @@
1+
# Settings for ros_control control loop
2+
hardware_control_loop:
3+
loop_hz: &loop_hz 500
4+
5+
# Settings for ros_control hardware interface
6+
hardware_interface:
7+
joints: &robot_joints
8+
- shoulder_pan_joint
9+
- shoulder_lift_joint
10+
- elbow_joint
11+
- wrist_1_joint
12+
- wrist_2_joint
13+
- wrist_3_joint
14+
15+
# Publish all joint states ----------------------------------
16+
joint_state_controller:
17+
type: joint_state_controller/JointStateController
18+
publish_rate: *loop_hz
19+
20+
# Publish wrench ----------------------------------
21+
force_torque_sensor_controller:
22+
type: force_torque_sensor_controller/ForceTorqueSensorController
23+
publish_rate: *loop_hz
24+
25+
# Publish speed_scaling factor
26+
speed_scaling_state_controller:
27+
type: ur_controllers/SpeedScalingStateController
28+
publish_rate: *loop_hz
29+
30+
# Joint Trajectory Controller - position based -------------------------------
31+
# For detailed explanations of parameter see http://wiki.ros.org/joint_trajectory_controller
32+
scaled_pos_traj_controller:
33+
type: position_controllers/ScaledJointTrajectoryController
34+
joints: *robot_joints
35+
constraints:
36+
goal_time: 0.6
37+
stopped_velocity_tolerance: 0.05
38+
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
39+
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
40+
elbow_joint: {trajectory: 0.2, goal: 0.1}
41+
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
42+
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
43+
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
44+
stop_trajectory_duration: 0.5
45+
state_publish_rate: *loop_hz
46+
action_monitor_rate: 10
47+
48+
pos_traj_controller:
49+
type: position_controllers/JointTrajectoryController
50+
joints: *robot_joints
51+
constraints:
52+
goal_time: 0.6
53+
stopped_velocity_tolerance: 0.05
54+
shoulder_pan_joint: {trajectory: 0.2, goal: 0.1}
55+
shoulder_lift_joint: {trajectory: 0.2, goal: 0.1}
56+
elbow_joint: {trajectory: 0.2, goal: 0.1}
57+
wrist_1_joint: {trajectory: 0.2, goal: 0.1}
58+
wrist_2_joint: {trajectory: 0.2, goal: 0.1}
59+
wrist_3_joint: {trajectory: 0.2, goal: 0.1}
60+
stop_trajectory_duration: 0.5
61+
state_publish_rate: *loop_hz
62+
action_monitor_rate: 10
Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
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_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="tf_prefix" default="" doc="tf_prefix used for the robot."/>
9+
<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."/>
10+
<arg name="stopped_controllers" default="pos_traj_controller" doc="Controllers that are initally loaded, but not started."/>
11+
<arg name="controller_config_file" default="$(find ur_robot_driver)/config/ur16e_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
12+
<arg name="robot_description_file" default="$(find ur_description)/launch/ur16e_upload.launch" doc="Robot description launch file."/>
13+
<arg name="kinematics_config" default="$(find ur_description)/config/ur16e/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."/>
14+
<arg name="use_tool_communication" default="false" doc="On e-Series robots tool communication can be enabled with this argument"/>
15+
<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."/>
16+
<arg name="tool_parity" default="0" doc="Parity configuration used for tool communication. Only used, when `use_tool_communication` is set to true."/>
17+
<arg name="tool_baud_rate" default="115200" doc="Baud rate used for tool communication. Only used, when `use_tool_communication` is set to true."/>
18+
<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."/>
19+
<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."/>
20+
<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."/>
21+
<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."/>
22+
<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."/>
23+
<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."/>
24+
25+
<include file="$(find ur_robot_driver)/launch/ur_common.launch">
26+
<arg name="debug" value="$(arg debug)"/>
27+
<arg name="use_tool_communication" value="$(arg use_tool_communication)"/>
28+
<arg name="controller_config_file" value="$(arg controller_config_file)"/>
29+
<arg name="robot_description_file" value="$(arg robot_description_file)"/>
30+
<arg name="kinematics_config" value="$(arg kinematics_config)"/>
31+
<arg name="robot_ip" value="$(arg robot_ip)"/>
32+
<arg name="reverse_port" value="$(arg reverse_port)"/>
33+
<arg name="script_sender_port" value="$(arg script_sender_port)"/>
34+
<arg name="tf_prefix" value="$(arg tf_prefix)"/>
35+
<arg name="controllers" value="$(arg controllers)"/>
36+
<arg name="stopped_controllers" value="$(arg stopped_controllers)"/>
37+
<arg name="headless_mode" value="$(arg headless_mode)"/>
38+
<arg name="tool_voltage" value="$(arg tool_voltage)"/>
39+
<arg name="tool_parity" value="$(arg tool_parity)"/>
40+
<arg name="tool_baud_rate" value="$(arg tool_baud_rate)"/>
41+
<arg name="tool_stop_bits" value="$(arg tool_stop_bits)"/>
42+
<arg name="tool_rx_idle_chars" value="$(arg tool_rx_idle_chars)"/>
43+
<arg name="tool_tx_idle_chars" value="$(arg tool_tx_idle_chars)"/>
44+
<arg name="tool_device_name" value="$(arg tool_device_name)"/>
45+
<arg name="tool_tcp_port" value="$(arg tool_tcp_port)"/>
46+
</include>
47+
48+
</launch>

0 commit comments

Comments
 (0)