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

Fix masses of robot links #689

Open
wants to merge 2 commits into
base: noetic-devel
Choose a base branch
from
Open
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
146 changes: 95 additions & 51 deletions ur_description/config/ur10/physical_parameters.yaml
Original file line number Diff line number Diff line change
@@ -1,26 +1,17 @@
# Physical parameters

dh_parameters:
d1: 0.1273
a2: -0.612
a3: -0.5723
d4: 0.163941
d5: 0.1157
d6: 0.0922

offsets:
shoulder_offset: 0.220941 # measured from model
elbow_offset: 0.049042 # measured from model

inertia_parameters:
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 7.778
upper_arm_mass: 12.93
upper_arm_inertia_offset: 0.175
forearm_mass: 3.87
wrist_1_mass: 1.96
wrist_2_mass: 1.96
wrist_3_mass: 0.202
shoulder_mass: 7.1
upper_arm_mass: 12.7
forearm_mass: 4.27
wrist_1_mass: 2.0
wrist_2_mass: 2.0
wrist_3_mass: 0.365

shoulder_radius: x0.060 # FROM UR5 DON'T USE
upper_arm_radius: x0.054 # FROM UR5 DON'T USE
Expand All @@ -32,47 +23,100 @@ inertia_parameters:
base:
radius: 0.075
length: 0.038
shoulder:
radius: 0.075
length: 0.178
upperarm:
radius: 0.075
length: 0.612
forearm:
radius: 0.075
length: 0.5723
wrist_1:
radius: 0.075
length: 0.12
wrist_2:
radius: 0.075
length: 0.09
wrist_3:
radius: 0.045
length: 0.0305

center_of_mass:
shoulder_cog:
x: 0.0
y: 0.00244
z: -0.037
x: 0.021 # model.x
y: -0.027 # -model.z
z: 0.0 # model.y
upper_arm_cog:
x: 0.00001
y: 0.15061
z: 0.38757
x: -0.232 # model.x - upper_arm_length
y: 0.0 # model.y
z: 0.158 # model.z
forearm_cog:
x: -0.00012
y: 0.06112
z: 0.1984
x: -0.3323 # model.x - forearm_length
y: 0.0 # model.y
z: 0.068 # model.z
wrist_1_cog:
x: -0.00021
y: -0.00112
z: 0.02269
x: 0.0 # model.x
y: -0.018 # -model.z
z: 0.007 # model.y
wrist_2_cog:
x: -0.00021
y: 0.00112
z: 0.002269
x: 0.0 # model.x
y: 0.018 # model.z
z: -0.007 # -model.y
wrist_3_cog:
x: 0.0
y: -0.001156
z: -0.00149
x: 0.0 # model.x
y: 0 # model.y
z: -0.026 # 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

# extracted from URSim
tensor:
shoulder:
ixx: 0.03408
ixy: 0.00002
ixz: -0.00425
iyy: 0.03529
iyz: 0.00008
izz: 0.02156
upper_arm:
ixx: 0.02814
ixy: 0.00005
ixz: -0.01561
iyy: 0.77068
iyz: 0.00002
izz: 0.76943
forearm:
ixx: 0.01014
ixy: 0.00008
ixz: 0.00916
iyy: 0.30928
iyz: 0.0
izz: 0.30646
wrist_1:
ixx: 0.00296
ixy: -0.00001
ixz: 0.0
iyy: 0.00222
iyz: -0.00024
izz: 0.00258
wrist_2:
ixx: 0.00296
ixy: -0.00001
ixz: 0.0
iyy: 0.00222
iyz: -0.00024
izz: 0.00258
wrist_3:
ixx: 0.00040
ixy: 0.0
ixz: 0.0
iyy: 0.00041
iyz: 0.0
izz: 0.00034
6 changes: 3 additions & 3 deletions ur_description/config/ur10e/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
Expand All @@ -64,7 +64,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
Expand All @@ -74,7 +74,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
146 changes: 95 additions & 51 deletions ur_description/config/ur10e/physical_parameters.yaml
Original file line number Diff line number Diff line change
@@ -1,26 +1,17 @@
# Physical parameters

dh_parameters:
d1: 0.181
a2: -0.613
a3: -0.571
d4: 0.174 # wrist1_length = d4 - elbow_offset - shoulder_offset
d5: 0.120
d6: 0.117

offsets:
shoulder_offset: 0.1762 # measured from model
elbow_offset: 0.0393 # measured from model

inertia_parameters:
base_mass: 4.0 # This mass might be incorrect
shoulder_mass: 7.778
upper_arm_mass: 12.93
upper_arm_inertia_offset: 0.175 # measured from model
forearm_mass: 3.87
wrist_1_mass: 1.96
wrist_2_mass: 1.96
wrist_3_mass: 0.202
shoulder_mass: 7.369
upper_arm_mass: 13.051
forearm_mass: 3.989
wrist_1_mass: 2.1
wrist_2_mass: 1.98
wrist_3_mass: 0.615

shoulder_radius: x0.060 # FROM UR5 DON'T USE
upper_arm_radius: x0.054 # FROM UR5 DON'T USE
Expand All @@ -32,47 +23,100 @@ inertia_parameters:
base:
radius: 0.075
length: 0.038
shoulder:
radius: 0.075
length: 0.178
upperarm:
radius: 0.075
length: 0.612
forearm:
radius: 0.075
length: 0.57155
wrist_1:
radius: 0.075
length: 0.12
wrist_2:
radius: 0.075
length: 0.12
wrist_3:
radius: 0.045
length: 0.05

# model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/
center_of_mass:
shoulder_cog:
x: 0.0
y: 0.00244
z: -0.037
x: 0.021 # model.x
y: -0.027 # -model.z
z: 0.0 # model.y
upper_arm_cog:
x: 0.00001
y: 0.15061
z: 0.38757
x: -0.2327 # model.x - upper_arm_length
y: 0.0 # model.y
z: 0.158 # model.z
forearm_cog:
x: -0.00012
y: 0.06112
z: 0.1984
x: -0.33155 # model.x - forearm_length
y: 0.0 # model.y
z: 0.068 # model.z
wrist_1_cog:
x: -0.00021
y: -0.00112
z: 0.02269
x: 0.0 # model.x
y: -0.018 # -model.z
z: 0.007 # model.y
wrist_2_cog:
x: -0.00021
y: 0.00112
z: 0.002269
x: 0.0 # model.x
y: 0.018 # model.z
z: -0.007 # -model.y
wrist_3_cog:
x: 0.0
y: -0.001156
z: -0.00149
x: 0.0 # model.x
y: 0.0 # model.y
z: -0.026 # 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.03408
ixy: 0.00002
ixz: -0.00425
iyy: 0.03529
iyz: 0.00008
izz: 0.02156
upper_arm:
ixx: 0.02814
ixy: 0.00005
ixz: -0.01561
iyy: 0.77068
iyz: 0.00002
izz: 0.76943
forearm:
ixx: 0.01014
ixy: 0.00008
ixz: 0.00916
iyy: 0.30928
iyz: 0.0
izz: 0.30646
wrist_1:
ixx: 0.00296
ixy: -0.00001
ixz: 0.0
iyy: 0.00222
iyz: -0.00024
izz: 0.00258
wrist_2:
ixx: 0.00296
ixy: -0.00001
ixz: 0.0
iyy: 0.00222
iyz: -0.00024
izz: 0.00258
wrist_3:
ixx: 0.00040
ixy: 0.0
ixz: 0.0
iyy: 0.00041
iyz: 0.0
izz: 0.00034
6 changes: 3 additions & 3 deletions ur_description/config/ur16e/joint_limits.yaml
Original file line number Diff line number Diff line change
Expand Up @@ -54,7 +54,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
Expand All @@ -64,7 +64,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
Expand All @@ -74,7 +74,7 @@ joint_limits:
has_effort_limits: true
has_position_limits: true
has_velocity_limits: true
max_effort: 56.0
max_effort: 54.0
max_position: !degrees 360.0
max_velocity: !degrees 180.0
min_position: !degrees -360.0
Loading