Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Add UR30 model #126

Merged
merged 5 commits into from Dec 22, 2023
Merged
Show file tree
Hide file tree
Changes from 3 commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Jump to
Jump to file
Failed to load files.
Diff view
Diff view
6 changes: 4 additions & 2 deletions README.md
Expand Up @@ -20,8 +20,10 @@ repository](https://github.com/UniversalRobots/Universal_Robots_ROS2_Driver/tree
not clone this repository into a Foxy workspace.

## License
The [UR20 meshes](ur_description/meshes/ur20) constitutes “Graphical Documentation” the use of which is subject to and governed by our “[Terms and Conditions for use of Graphical Documentation](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt)”.\
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).
The [UR20 meshes](ur_description/meshes/ur20) and [UR30 meshes](ur_description/meshes/ur30) constitutes “Graphical Documentation” the use of which is subject to and governed by our “[Terms and Conditions for use of Graphical Documentation](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt)”.

Universal Robots' [Terms and Conditions for use of Graphical Documentation](https://www.universal-robots.com/legal/terms-and-conditions/terms_and_conditions_for_use_of_graphical_documentation.txt) do not fully comply with [OSI's definition of Open Source](https://opensource.org/osd/), but they do allow you to use, modify and share “Graphical Documentation”, including [UR20](meshes/ur20) and [UR30](meshes/ur30) meshes, subject to certain restrictions.\
If you have any questions regarding this license or if this license doesn't fit your use-case, please contact [legal@universal-robots.com](mailto:legal@universal-robots.com).

All other content is licensed under the BSD-3-Clause license

Expand Down
44 changes: 44 additions & 0 deletions config/ur30/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.637
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.5037
y: 0
z: 0.20100000000000001
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.1593
z: 0
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
77 changes: 77 additions & 0 deletions config/ur30/joint_limits.yaml
@@ -0,0 +1,77 @@
# Joints limits
#
# Sources:
#
# - Universal Robots e-Series, User Manual, UR20, Version 5.14
# https://s3-eu-west-1.amazonaws.com/ur-support-site/203281/706-276-00_UR20_User_Manual_en_Global.pdf
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: 730.0
max_position: !degrees 360.0
max_velocity: !degrees 120.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: 730.0
max_position: !degrees 360.0
max_velocity: !degrees 120.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: 430.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 150.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: 100.0
max_position: !degrees 360.0
max_velocity: !degrees 210.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: 100.0
max_position: !degrees 360.0
max_velocity: !degrees 210.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: 100.0
max_position: !degrees 360.0
max_velocity: !degrees 210.0
min_position: !degrees -360.0
80 changes: 80 additions & 0 deletions config/ur30/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.637
forearm:
radius: 0.075
length: 0.5037
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.40757
forearm_cog:
x: -0.00012
y: 0.06112
z: 0.2084
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/ur30/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/ur30/visual/upperarm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur30/collision/upperarm.stl
mesh_files:

forearm:
visual:
mesh:
package: ur_description
path: meshes/ur30/visual/forearm.dae
material:
name: "LightGrey"
color: "0.7 0.7 0.7 1.0"
collision:
mesh:
package: ur_description
path: meshes/ur30/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
2 changes: 1 addition & 1 deletion launch/view_ur.launch.py
Expand Up @@ -42,7 +42,7 @@ def generate_launch_description():
DeclareLaunchArgument(
"ur_type",
description="Type/series of used UR robot.",
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20"],
choices=["ur3", "ur3e", "ur5", "ur5e", "ur10", "ur10e", "ur16e", "ur20", "ur30"],
)
)
declared_arguments.append(
Expand Down
1 change: 1 addition & 0 deletions meshes/ur30/LICENSE.txt
fmauch marked this conversation as resolved.
Show resolved Hide resolved
Binary file added meshes/ur30/collision/forearm.stl
Binary file not shown.
Binary file added meshes/ur30/collision/upperarm.stl
Binary file not shown.
Binary file added meshes/ur30/visual/UR30_DIFF_8bit_2K.png
Sorry, something went wrong. Reload?
Sorry, we cannot display this file.
Sorry, this file is invalid so it cannot be displayed.