Skip to content

Commit 318811f

Browse files
authored
Merge branch 'UniversalRobots:master' into enable_tool_contact
2 parents bfc6550 + 4479de9 commit 318811f

File tree

9 files changed

+212
-4
lines changed

9 files changed

+212
-4
lines changed

README.md

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -203,7 +203,7 @@ To actually start the robot driver use one of the existing launch files
203203

204204
$ roslaunch ur_robot_driver <robot_type>_bringup.launch robot_ip:=192.168.56.101
205205

206-
where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e, ur16e, ur20*. Note that in this example we
206+
where **<robot_type>** is one of *ur3, ur5, ur10, ur3e, ur5e, ur10e, ur16e, ur20, ur30*. Note that in this example we
207207
load the calibration parameters for the robot "ur10_example".
208208

209209
If you calibrated your robot before, pass that calibration to the launch file:

ur_calibration/CHANGELOG.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,6 @@
1+
2.1.4 (2024-04-08)
2+
------------------
3+
14
2.1.3 (2023-12-18)
25
------------------
36
* Bump cmake minimum version for all packages in repo

ur_calibration/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>ur_calibration</name>
4-
<version>2.1.3</version>
4+
<version>2.1.4</version>
55
<description>Package for extracting the factory calibration from a UR robot and change it such that it can be used by ur_description to gain a correct URDF</description>
66

77
<maintainer email="[email protected]">Felix Exner</maintainer>

ur_dashboard_msgs/CHANGELOG.rst

Lines changed: 3 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,6 +2,9 @@
22
Changelog for package ur_dashboard_msgs
33
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
44

5+
2.1.4 (2024-04-08)
6+
------------------
7+
58
2.1.3 (2023-12-18)
69
------------------
710
* Bump cmake minimum version for all packages in repo

ur_dashboard_msgs/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
11
<?xml version="1.0"?>
22
<package format="2">
33
<name>ur_dashboard_msgs</name>
4-
<version>2.1.3</version>
4+
<version>2.1.4</version>
55
<description>Messages around the UR Dashboard server.</description>
66

77
<maintainer email="[email protected]">Felix Exner</maintainer>

ur_robot_driver/CHANGELOG.rst

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1,3 +1,9 @@
1+
2.1.4 (2024-04-08)
2+
------------------
3+
* Added support for UR30 (`#688 <https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/issues/688>`_)
4+
* Added arg to enable/disable launch of ursim (`#679 <https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/pull/679>`_)
5+
* Contributors: Vincenzo Di Pentima, mahp
6+
17
2.1.3 (2023-12-18)
28
------------------
39
* Added support for UR20 (`#659 <https://github.com/UniversalRobots/Universal_Robots_ROS_Driver/issues/659>`_)
Lines changed: 166 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,166 @@
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: scaled_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+
forward_joint_traj_controller:
134+
type: "pass_through_controllers/JointTrajectoryController"
135+
joints: *robot_joints
136+
137+
forward_cartesian_traj_controller:
138+
type: "pass_through_controllers/CartesianTrajectoryController"
139+
joints: *robot_joints
140+
141+
twist_controller:
142+
type: "ros_controllers_cartesian/TwistController"
143+
frame_id: "tool0_controller"
144+
publish_rate: *loop_hz
145+
joints: *robot_joints
146+
147+
pose_based_cartesian_traj_controller:
148+
type: pose_controllers/CartesianTrajectoryController
149+
150+
# UR driver convention
151+
base: base
152+
tip: tool0_controller
153+
joints: *robot_joints
154+
155+
joint_based_cartesian_traj_controller:
156+
type: position_controllers/CartesianTrajectoryController
157+
158+
# UR driver convention
159+
base: base
160+
tip: tool0
161+
joints: *robot_joints
162+
163+
robot_status_controller:
164+
type: industrial_robot_status_controller/IndustrialRobotStatusController
165+
handle_name: industrial_robot_status_handle
166+
publish_rate: 10
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/ur30_controllers.yaml" doc="Config file used for defining the ROS-Control controllers."/>
15+
<arg name="robot_description_file" default="$(find ur_description)/launch/load_ur30.launch" doc="Robot description launch file."/>
16+
<arg name="kinematics_config" default="$(find ur_description)/config/ur30/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>

ur_robot_driver/package.xml

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -2,7 +2,7 @@
22
<?xml-model href="http://download.ros.org/schema/package_format2.xsd" schematypens="http://www.w3.org/2001/XMLSchema"?>
33
<package format="2">
44
<name>ur_robot_driver</name>
5-
<version>2.1.3</version>
5+
<version>2.1.4</version>
66
<description>The new driver for Universal Robots UR3, UR5 and UR10 robots with CB3 controllers and the e-series.</description>
77
<author>Thomas Timm Andersen</author>
88
<author>Simon Rasmussen</author>

0 commit comments

Comments
 (0)