Skip to content

Commit

Permalink
UR20 description and meshes
Browse files Browse the repository at this point in the history
The UR20 meshes are added under Universal Robots A/S’
Terms and Conditions for Use of Graphical Documentation
  • Loading branch information
urrsk committed Sep 5, 2023
1 parent 379beee commit e74e2a8
Show file tree
Hide file tree
Showing 25 changed files with 4,227 additions and 5 deletions.
1 change: 1 addition & 0 deletions .pre-commit-config.yaml
Expand Up @@ -19,6 +19,7 @@ repos:
rev: v4.4.0
hooks:
- id: check-added-large-files
args: ['--maxkb=1500']
- id: check-ast
- id: check-case-conflict
- id: check-docstring-first
Expand Down
6 changes: 6 additions & 0 deletions README.md
Expand Up @@ -19,6 +19,12 @@ Note that for ROS2 **Foxy** the description is in the [driver's
repository](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/tree/foxy). Please do
not clone this repository into a Foxy workspace.

## License
The majority of this repository is licensed under the BSD-3-Clause license. However, the **UR20
meshes** are licensed under Universal Robots A/S’ Terms and Conditions for Use of Graphical Documentation. See the separate
[LICENSE.txt](/meshes/ur20/LICENSE.txt) file for details. If you have any questions regarding the
license or the license doesn't fit you use-case, please contact [legal@universal-robots.com](mailto:legal@universal-robots.com).

## Structure of the repository

The most relevant files are:
Expand Down
44 changes: 44 additions & 0 deletions config/ur20/default_kinematics.yaml
@@ -0,0 +1,44 @@
kinematics:
shoulder:
x: 0
y: 0
z: 0.23630000000000001
roll: -0
pitch: 0
yaw: -0
upper_arm:
x: 0
y: 0
z: 0
roll: 1.570796327
pitch: 0
yaw: -0
forearm:
x: -0.86199999999999999
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.72870000000000001
y: 0
z: 0.20100000000000001
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.1593
z: -3.2672976162492252e-11
roll: 1.570796327
pitch: 0
yaw: -0
wrist_3:
x: 0
y: 0.15429999999999999
z: -3.1647459019915597e-11
roll: 1.5707963265897931
pitch: 3.1415926535897931
yaw: 3.1415926535897931
hash: calib_4890363623803256388
80 changes: 80 additions & 0 deletions config/ur20/joint_limits.yaml
@@ -0,0 +1,80 @@
# Joints limits
#
# Sources:
#
# - Universal Robots e-Series, User Manual, UR16e, Version 5.8
# https://s3-eu-west-1.amazonaws.com/ur-support-site/69187/99473_UR16e_User_Manual_en_Global.pdf
# - Support > Articles > UR articles > Max. joint torques
# https://www.universal-robots.com/articles/ur-articles/max-joint-torques
# retrieved: 2020-06-16, last modified: 2020-06-09
joint_limits:
shoulder_pan_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 330.0
max_position: !degrees 360.0
max_velocity: !degrees 130.0
min_position: !degrees -360.0
shoulder_lift_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 330.0
max_position: !degrees 360.0
max_velocity: !degrees 130.0
min_position: !degrees -360.0
elbow_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 150.0
# we artificially limit this joint to half its actual joint position limit
# to avoid (MoveIt/OMPL) planning problems, as due to the physical
# construction of the robot, it's impossible to rotate the 'elbow_joint'
# over more than approx +- 1 pi (the shoulder lift joint gets in the way).
#
# This leads to planning problems as the search space will be divided into
# two sections, with no connections from one to the other.
#
# Refer to https://github.com/ros-industrial/universal_robot/issues/265 for
# more information.
max_position: !degrees 180.0
max_velocity: !degrees 160.0
min_position: !degrees -180.0
wrist_1_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_position: !degrees 360.0
max_velocity: !degrees 220.0
min_position: !degrees -360.0
wrist_2_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_position: !degrees 360.0
max_velocity: !degrees 220.0
min_position: !degrees -360.0
wrist_3_joint:
# acceleration limits are not publicly available
has_acceleration_limits: false
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_position: !degrees 360.0
max_velocity: !degrees 220.0
min_position: !degrees -360.0
80 changes: 80 additions & 0 deletions config/ur20/physical_parameters.yaml
@@ -0,0 +1,80 @@
# Physical parameters

# from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/
dh_parameters:
d1: 0.2363
a2: -0.8620
a3: -0.7287
d4: 0.201
d5: 0.1593
d6: 0.1543

offsets:
shoulder_offset: 0.260 # measured from model
elbow_offset: 0.043 # measured from model

inertia_parameters:
# taken from https://www.universal-robots.com/how-tos-and-faqs/faq/ur-faq/parameters-for-calculations-of-kinematics-and-dynamics-45257/
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 16.343
upper_arm_mass: 29.632
upper_arm_inertia_offset: 0.275 # measured from model
forearm_mass: 7.879
wrist_1_mass: 3.054
wrist_2_mass: 3.126
wrist_3_mass: 0.846

shoulder_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE
upper_arm_radius: x0.054 # FROM UR5 CURRENTLY NOT USED ANYMORE
elbow_radius: x0.060 # FROM UR5 CURRENTLY NOT USED ANYMORE
forearm_radius: x0.040 # FROM UR5 CURRENTLY NOT USED ANYMORE
wrist_radius: x0.045 # FROM UR5 CURRENTLY NOT USED ANYMORE

links:
base:
radius: 0.075
length: 0.038
shoulder:
radius: 0.075
length: 0.178
upperarm:
radius: 0.075
length: 0.852
forearm:
radius: 0.075
length: 0.7287
wrist_1:
radius: 0.075
length: 0.12
wrist_2:
radius: 0.075
length: 0.12
wrist_3:
radius: 0.045
length: 0.05

center_of_mass: # Adjusted manually
shoulder_cog:
x: 0.0
y: 0.00244
z: -0.037
upper_arm_cog:
x: 0.00001
y: 0.15061
z: 0.48757
forearm_cog:
x: -0.00012
y: 0.06112
z: 0.2984
wrist_1_cog:
x: -0.00021
y: -0.00112
z: 0.02269
wrist_2_cog:
x: -0.00021
y: 0.00112
z: 0.002269
wrist_3_cog:
x: 0.0
y: -0.001156
z: -0.00149
97 changes: 97 additions & 0 deletions config/ur20/visual_parameters.yaml
@@ -0,0 +1,97 @@
# Visualisation

mesh_files:
base:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/base.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/base.stl

shoulder:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/shoulder.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/shoulder.stl

upper_arm:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/upperarm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/upperarm.stl
mesh_files:

forearm:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/forearm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/forearm.stl

wrist_1:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist1.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist1.stl
visual_offset: -0.0775

wrist_2:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist2.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist2.stl
visual_offset: -0.0749

wrist_3:
visual:
mesh:
package: ur_description
path: meshes/ur20/visual/wrist3.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur20/collision/wrist3.stl
visual_offset: -0.07
4 changes: 1 addition & 3 deletions launch/view_ur.launch.py
Expand Up @@ -42,11 +42,9 @@ def generate_launch_description():
DeclareLaunchArgument(
"ur_type",
description="Type/series of used UR robot.",
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e"],
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"],
)
)
# TODO(anyone): enable this when added into ROS2-foxy
# choices=['ur3', 'ur3e', 'ur5', 'ur5e', 'ur10', 'ur10e', 'ur16e']))
declared_arguments.append(
DeclareLaunchArgument(
"safety_limits",
Expand Down

0 comments on commit e74e2a8

Please sign in to comment.