Skip to content

Commit 936ff8d

Browse files
authored
Merge pull request UniversalRobots#270 from UniversalRobots/ur16e
Ur16e
2 parents 406a330 + d1f8f39 commit 936ff8d

File tree

5 files changed

+174
-2
lines changed

5 files changed

+174
-2
lines changed

README.md

Lines changed: 11 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
# Universal_Robots_ROS_Driver
44
Universal Robots have become a dominant supplier of lightweight, robotic manipulators for industry, as well as for scientific research and education. The Robot Operating System (ROS) has developed from a community-centered movement to a mature framework and quasi standard, providing a rich set of powerful tools for robot engineers and researchers, working in many different domains.
55

6-
<center><img src="ur_robot_driver/doc/initial_setup_images/e-Series.png" alt="Universal Robot e-Series family" style="width: 45%;"/></center>
6+
<center><img src="ur_robot_driver/doc/initial_setup_images/e-Series.jpg" alt="Universal Robot e-Series family" style="width: 80%;"/></center>
77

88
With the release of UR’s new e-Series, the demand for a ROS driver that supports the new manipulators and the newest ROS releases and paradigms like ROS-control has increased further. The goal of this driver is to provide a stable and sustainable interface between UR robots and ROS that strongly benefit all parties.
99

@@ -91,6 +91,15 @@ To make sure that robot control isn't affected by system latencies, it is highly
9191
a real-time kernel with the system. See the [real-time setup guide](ur_robot_driver/doc/real_time.md)
9292
on information how to set this up.
9393

94+
## Preliminary UR16e support
95+
This driver supports all UR variants including the UR16e. However, upstream support for the UR16e is
96+
not finished, yet. When using the UR16e there is currently no support for gazebo or MoveIt!.
97+
98+
See [#97](https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/pull/97) for details on
99+
using the latest upstream develop branch of
100+
[ros_industrial/universal_robot](https://github.com/ros-industrial/universal_robot) which includes
101+
gazebo support for the ur16e, but no working MoveIt! support at the time of writing.
102+
94103
## Building
95104

96105
```bash
@@ -166,7 +175,7 @@ To actually start the robot driver use one of the existing launch files
166175

167176
$ roslaunch ur_robot_driver <robot_type>_bringup.launch robot_ip:=192.168.56.101
168177

169-
where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e*. Note that in this example we
178+
where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e, ur16e*. Note that in this example we
170179
load the calibration parameters for the robot "ur10_example".
171180

172181
If you calibrated your robot before, pass that calibration to the launch file:
Lines changed: 136 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,136 @@
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+
ur_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_joint_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: 20
47+
48+
pos_joint_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: 20
63+
64+
scaled_vel_joint_traj_controller:
65+
type: velocity_controllers/ScaledJointTrajectoryController
66+
joints: *robot_joints
67+
constraints:
68+
goal_time: 0.6
69+
stopped_velocity_tolerance: 0.05
70+
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
71+
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
72+
elbow_joint: {trajectory: 0.1, goal: 0.1}
73+
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
74+
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
75+
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
76+
gains:
77+
#!!These values have not been optimized!!
78+
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
79+
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
80+
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
81+
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
82+
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
83+
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
84+
# Use a feedforward term to reduce the size of PID gains
85+
velocity_ff:
86+
shoulder_pan_joint: 1.0
87+
shoulder_lift_joint: 1.0
88+
elbow_joint: 1.0
89+
wrist_1_joint: 1.0
90+
wrist_2_joint: 1.0
91+
wrist_3_joint: 1.0
92+
stop_trajectory_duration: 0.5
93+
state_publish_rate: *loop_hz
94+
action_monitor_rate: 20
95+
96+
vel_joint_traj_controller:
97+
type: velocity_controllers/JointTrajectoryController
98+
joints: *robot_joints
99+
constraints:
100+
goal_time: 0.6
101+
stopped_velocity_tolerance: 0.05
102+
shoulder_pan_joint: {trajectory: 0.1, goal: 0.1}
103+
shoulder_lift_joint: {trajectory: 0.1, goal: 0.1}
104+
elbow_joint: {trajectory: 0.1, goal: 0.1}
105+
wrist_1_joint: {trajectory: 0.1, goal: 0.1}
106+
wrist_2_joint: {trajectory: 0.1, goal: 0.1}
107+
wrist_3_joint: {trajectory: 0.1, goal: 0.1}
108+
gains:
109+
#!!These values have not been optimized!!
110+
shoulder_pan_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
111+
shoulder_lift_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
112+
elbow_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
113+
wrist_1_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
114+
wrist_2_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
115+
wrist_3_joint: {p: 5.0, i: 0.05, d: 0.1, i_clamp: 1}
116+
# Use a feedforward term to reduce the size of PID gains
117+
velocity_ff:
118+
shoulder_pan_joint: 1.0
119+
shoulder_lift_joint: 1.0
120+
elbow_joint: 1.0
121+
wrist_1_joint: 1.0
122+
wrist_2_joint: 1.0
123+
wrist_3_joint: 1.0
124+
stop_trajectory_duration: 0.5
125+
state_publish_rate: *loop_hz
126+
action_monitor_rate: 20
127+
128+
# Pass an array of joint velocities directly to the joints
129+
joint_group_vel_controller:
130+
type: velocity_controllers/JointGroupVelocityController
131+
joints: *robot_joints
132+
133+
robot_status_controller:
134+
type: industrial_robot_status_controller/IndustrialRobotStatusController
135+
handle_name: industrial_robot_status_handle
136+
publish_rate: 10
41.3 KB
Loading
Binary file not shown.
Lines changed: 27 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,27 @@
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_joint_traj_controller speed_scaling_state_controller force_torque_sensor_controller" doc="Controllers that are activated by default."/>
10+
<arg name="stopped_controllers" default="pos_joint_traj_controller joint_group_vel_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_e_description)/launch/ur16e_upload.launch" doc="Robot description launch file."/>
13+
<arg name="kinematics_config" default="$(find ur_e_description)/config/ur16e_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."/>
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="limited" default="false" doc="Use the description in limited mode (Every axis rotates from -PI to PI)"/>
24+
<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."/>
25+
26+
<include file="$(find ur_robot_driver)/launch/ur_common.launch" pass_all_args="true"/>
27+
</launch>

0 commit comments

Comments
 (0)