Skip to content
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
4 changes: 2 additions & 2 deletions README.md
Original file line number Diff line number Diff line change
Expand Up @@ -17,9 +17,9 @@ users an overview of the current released state.


## License
The [UR15 meshes](meshes/ur15), [UR20 meshes](meshes/ur20) and [UR30 meshes](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)”.
The [UR8LONG meshes](meshes/ur8long), [UR15 meshes](meshes/ur15), [UR20 meshes](meshes/ur20) and [UR30 meshes](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 [UR15 meshes](meshes/ur15), [UR20](meshes/ur20) and [UR30](meshes/ur30) meshes, subject to certain restrictions.\
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 [UR8LONG meshes](meshes/ur8long), [UR15 meshes](meshes/ur15), [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/ur8long/default_kinematics.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,44 @@
kinematics:
shoulder:
x: 0
y: 0
z: 0.21859999999999999
roll: -0
pitch: 0
yaw: -0
upper_arm:
x: 0
y: 0
z: 0
roll: 1.570796327
pitch: 0
yaw: -0
forearm:
x: -0.89890000000000003
y: 0
z: 0
roll: -0
pitch: 0
yaw: -0
wrist_1:
x: -0.71489999999999998
y: 0
z: 0.18240000000000001
roll: -0
pitch: 0
yaw: -0
wrist_2:
x: 0
y: -0.1361
z: -2.7914576620936571e-11
roll: 1.570796327
pitch: 0
yaw: -0
wrist_3:
x: 0
y: 0.1434
z: -2.941183164909849e-11
roll: 1.5707963265897931
pitch: 3.1415926535897931
yaw: 3.1415926535897931
hash: calib_464256464824449623
72 changes: 72 additions & 0 deletions config/ur8long/joint_limits.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,72 @@
---
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: 433.0
max_position: !degrees 360.0
max_velocity: !degrees 180.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: 433.0
max_position: !degrees 360.0
max_velocity: !degrees 180.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: 204.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 240.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: 70.0
max_position: !degrees 360.0
max_velocity: !degrees 300.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: 70.0
max_position: !degrees 360.0
max_velocity: !degrees 300.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: 70.0
max_position: !degrees 360.0
max_velocity: !degrees 300.0
min_position: !degrees -360.0
114 changes: 114 additions & 0 deletions config/ur8long/physical_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,114 @@
---
# Physical parameters

inertia_parameters:
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 9.9883
upper_arm_mass: 17.0738
forearm_mass: 7.6393
wrist_1_mass: 2.089
wrist_2_mass: 2.0869
wrist_3_mass: 1.0666

# used to approximate the inertia tensor of the fixed base using a cylinder approximation. This
# is only relevant if the robot's base is moving e.g. when it's mounted on a mobile platform.
links:
base:
radius: 0.17
length: 0.1

center_of_mass:
shoulder_cog:
x: 0.000024 # model.x
y: -0.025304 # -model.z
z: -0.033309 # model.y
upper_arm_cog:
x: -0.333471 # model.x - upperarm_length
y: -0.000074 # model.y
z: 0.195420 # model.z
forearm_cog:
x: -0.298798 # model.x - forearm_length
y: 0.000058 # model.y
z: 0.065663 # model.z
wrist_1_cog:
x: 0.000025 # model.x
y: -0.016413 # -model.z
z: -0.019695 # model.y
wrist_2_cog:
x: 0.000025 # model.x
y: 0.015886 # model.z
z: -0.019960 # -model.y
wrist_3_cog:
x: -0.000018 # model.x
y: -0.000112 # model.y
z: -0.053397 # model.z

rotation:
shoulder:
roll: 1.570796326794897
pitch: 0
yaw: 0
upper_arm:
roll: 0
pitch: 0
yaw: 0
forearm:
roll: 0
pitch: 0
yaw: 0
wrist_1:
roll: 1.570796326794897
pitch: 0
yaw: 0
wrist_2:
roll: -1.570796326794897
pitch: 0
yaw: 0
wrist_3:
roll: 0
pitch: 0
yaw: 0

tensor:
shoulder:
ixx: 0.051334
ixy: 0.000025
ixz: -0.000016
iyy: 0.047702
iyz: 0.008805
izz: 0.034263
upper_arm:
ixx: 0.056709
ixy: 0.000292
ixz: -0.054852
iyy: 2.440120
iyz: -0.000014
izz: 2.432744
forearm:
ixx: 0.022148
ixy: 0.000052
ixz: 0.019779
iyy: 0.633274
iyz: 0.000003
izz: 0.625889
wrist_1:
ixx: 0.004339
ixy: 0.000019
ixz: 0.000001
iyy: 0.002548
iyz: 0.000706
izz: 0.003912
wrist_2:
ixx: 0.004288
ixy: 0.000017
ixz: -0.000003
iyy: 0.002566
iyz: -0.000716
izz: 0.003927
wrist_3:
ixx: 0.001406
ixy: -0.000003
ixz: 0.000010
iyy: 0.001404
iyz: -0.000024
izz: 0.001002
121 changes: 121 additions & 0 deletions config/ur8long/visual_parameters.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,121 @@
# Visualisation

mesh_files:
base:
visual:
mesh:
package: ur_description
path: meshes/ur15/visual/base.dae
collision:
mesh:
package: ur_description
path: meshes/ur15/collision/base.stl
mesh_offset:
x: 0.0
y: 0.0
z: 0.0
roll: 0.0
pitch: 0.0
yaw: !degrees 180

shoulder:
visual:
mesh:
package: ur_description
path: meshes/ur15/visual/shoulder.dae
collision:
mesh:
package: ur_description
path: meshes/ur15/collision/shoulder.stl
mesh_offset:
x: 0.0
y: 0.0
z: 0.0
roll: 0.0
pitch: 0.0
yaw: !degrees 180

upper_arm:
visual:
mesh:
package: ur_description
path: meshes/ur8long/visual/upperarm.dae
collision:
mesh:
package: ur_description
path: meshes/ur8long/collision/upperarm.stl
mesh_offset:
x: 0.0
y: 0.0
z: 0.109
roll: !degrees 90
pitch: 0.0
yaw: !degrees -90

forearm:
visual:
mesh:
package: ur_description
path: meshes/ur8long/visual/forearm.dae
collision:
mesh:
package: ur_description
path: meshes/ur8long/collision/forearm.stl
mesh_offset:
x: 0.0
y: 0.0
z: 0.13425
roll: !degrees 90
pitch: 0.0
yaw: !degrees -90

wrist_1:
visual:
mesh:
package: ur_description
path: meshes/ur15/visual/wrist1.dae
collision:
mesh:
package: ur_description
path: meshes/ur15/collision/wrist1.stl
mesh_offset:
x: 0.0
y: 0.0
z: -0.0502
roll: !degrees 90
pitch: 0.0
yaw: 0.0

wrist_2:
visual:
mesh:
package: ur_description
path: meshes/ur15/visual/wrist2.dae
collision:
mesh:
package: ur_description
path: meshes/ur15/collision/wrist2.stl
mesh_offset:
x: 0.0
y: 0.0
z: -0.064
roll: 0.0
pitch: 0.0
yaw: 0.0

wrist_3:
visual:
mesh:
package: ur_description
path: meshes/ur15/visual/wrist3.dae
collision:
mesh:
package: ur_description
path: meshes/ur15/collision/wrist3.stl
mesh_offset:
x: 0.0
y: 0.0
z: -0.0715
roll: !degrees 90
pitch: 0.0
yaw: 0.0
5 changes: 3 additions & 2 deletions launch/view_ur.launch.py
Original file line number Diff line number Diff line change
Expand Up @@ -45,14 +45,15 @@ def generate_launch_description():
description="Type/series of used UR robot.",
choices=[
"ur3",
"ur3e",
"ur5",
"ur10",
"ur3e",
"ur5e",
"ur7e",
"ur10",
"ur10e",
"ur12e",
"ur16e",
"ur8long",
"ur15",
"ur20",
"ur30",
Expand Down
Loading
Loading