Skip to content

Commit 60e6974

Browse files
chalongrathurrsk
andauthored
Update dynamic properties (#195)
* Remove unused dh_parameters * Rename prop__wrist_2_cog to prop_wrist_2_cog for consistency * Update mass and cog and use full inertia matrix. * Update max_efforts (torque limits) * Remove code and values that are no longer needed. --------- Co-authored-by: Rune Søe-Knudsen <[email protected]>
1 parent fdc9b91 commit 60e6974

16 files changed

+975
-492
lines changed
Lines changed: 89 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,5 @@
11
# Physical parameters
22

3-
dh_parameters:
4-
d1: 0.1273
5-
a2: -0.612
6-
a3: -0.5723
7-
d4: 0.163941
8-
d5: 0.1157
9-
d6: 0.0922
10-
113
offsets:
124
shoulder_offset: 0.220941 # measured from model
135
elbow_offset: 0.049042 # measured from model
@@ -16,7 +8,6 @@ inertia_parameters:
168
base_mass: 4.0 # This mass might be incorrect
179
shoulder_mass: 7.1
1810
upper_arm_mass: 12.7
19-
upper_arm_inertia_offset: 0.175
2011
forearm_mass: 4.27
2112
wrist_1_mass: 2.0
2213
wrist_2_mass: 2.0
@@ -32,47 +23,100 @@ inertia_parameters:
3223
base:
3324
radius: 0.075
3425
length: 0.038
35-
shoulder:
36-
radius: 0.075
37-
length: 0.178
38-
upperarm:
39-
radius: 0.075
40-
length: 0.612
41-
forearm:
42-
radius: 0.075
43-
length: 0.5723
44-
wrist_1:
45-
radius: 0.075
46-
length: 0.12
47-
wrist_2:
48-
radius: 0.075
49-
length: 0.09
50-
wrist_3:
51-
radius: 0.045
52-
length: 0.0305
5326

5427
center_of_mass:
5528
shoulder_cog:
56-
x: 0.0
57-
y: 0.00244
58-
z: -0.037
29+
x: 0.021 # model.x
30+
y: -0.027 # -model.z
31+
z: 0.0 # model.y
5932
upper_arm_cog:
60-
x: 0.00001
61-
y: 0.15061
62-
z: 0.38757
33+
x: -0.232 # model.x - upper_arm_length
34+
y: 0.0 # model.y
35+
z: 0.158 # model.z
6336
forearm_cog:
64-
x: -0.00012
65-
y: 0.06112
66-
z: 0.1984
37+
x: -0.3323 # model.x - forearm_length
38+
y: 0.0 # model.y
39+
z: 0.068 # model.z
6740
wrist_1_cog:
68-
x: -0.00021
69-
y: -0.00112
70-
z: 0.02269
41+
x: 0.0 # model.x
42+
y: -0.018 # -model.z
43+
z: 0.007 # model.y
7144
wrist_2_cog:
72-
x: -0.00021
73-
y: 0.00112
74-
z: 0.002269
45+
x: 0.0 # model.x
46+
y: 0.018 # model.z
47+
z: -0.007 # -model.y
7548
wrist_3_cog:
76-
x: 0.0
77-
y: -0.001156
78-
z: -0.00149
49+
x: 0.0 # model.x
50+
y: 0 # model.y
51+
z: -0.026 # model.z
52+
53+
rotation:
54+
shoulder:
55+
roll: 1.570796326794897
56+
pitch: 0
57+
yaw: 0
58+
upper_arm:
59+
roll: 0
60+
pitch: 0
61+
yaw: 0
62+
forearm:
63+
roll: 0
64+
pitch: 0
65+
yaw: 0
66+
wrist_1:
67+
roll: 1.570796326794897
68+
pitch: 0
69+
yaw: 0
70+
wrist_2:
71+
roll: -1.570796326794897
72+
pitch: 0
73+
yaw: 0
74+
wrist_3:
75+
roll: 0
76+
pitch: 0
77+
yaw: 0
78+
79+
# extracted from URSim
80+
tensor:
81+
shoulder:
82+
ixx: 0.03408
83+
ixy: 0.00002
84+
ixz: -0.00425
85+
iyy: 0.03529
86+
iyz: 0.00008
87+
izz: 0.02156
88+
upper_arm:
89+
ixx: 0.02814
90+
ixy: 0.00005
91+
ixz: -0.01561
92+
iyy: 0.77068
93+
iyz: 0.00002
94+
izz: 0.76943
95+
forearm:
96+
ixx: 0.01014
97+
ixy: 0.00008
98+
ixz: 0.00916
99+
iyy: 0.30928
100+
iyz: 0.0
101+
izz: 0.30646
102+
wrist_1:
103+
ixx: 0.00296
104+
ixy: -0.00001
105+
ixz: 0.0
106+
iyy: 0.00222
107+
iyz: -0.00024
108+
izz: 0.00258
109+
wrist_2:
110+
ixx: 0.00296
111+
ixy: -0.00001
112+
ixz: 0.0
113+
iyy: 0.00222
114+
iyz: -0.00024
115+
izz: 0.00258
116+
wrist_3:
117+
ixx: 0.00040
118+
ixy: 0.0
119+
ixz: 0.0
120+
iyy: 0.00041
121+
iyz: 0.0
122+
izz: 0.00034

config/ur10e/joint_limits.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ joint_limits:
5454
has_effort_limits: true
5555
has_position_limits: true
5656
has_velocity_limits: true
57-
max_effort: 56.0
57+
max_effort: 54.0
5858
max_position: !degrees 360.0
5959
max_velocity: !degrees 180.0
6060
min_position: !degrees -360.0
@@ -64,7 +64,7 @@ joint_limits:
6464
has_effort_limits: true
6565
has_position_limits: true
6666
has_velocity_limits: true
67-
max_effort: 56.0
67+
max_effort: 54.0
6868
max_position: !degrees 360.0
6969
max_velocity: !degrees 180.0
7070
min_position: !degrees -360.0
@@ -74,7 +74,7 @@ joint_limits:
7474
has_effort_limits: true
7575
has_position_limits: true
7676
has_velocity_limits: true
77-
max_effort: 56.0
77+
max_effort: 54.0
7878
max_position: !degrees 360.0
7979
max_velocity: !degrees 180.0
8080
min_position: !degrees -360.0
Lines changed: 89 additions & 45 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,5 @@
11
# Physical parameters
22

3-
dh_parameters:
4-
d1: 0.181
5-
a2: -0.613
6-
a3: -0.571
7-
d4: 0.174 # wrist1_length = d4 - elbow_offset - shoulder_offset
8-
d5: 0.120
9-
d6: 0.117
10-
113
offsets:
124
shoulder_offset: 0.1762 # measured from model
135
elbow_offset: 0.0393 # measured from model
@@ -16,7 +8,6 @@ inertia_parameters:
168
base_mass: 4.0 # This mass might be incorrect
179
shoulder_mass: 7.369
1810
upper_arm_mass: 13.051
19-
upper_arm_inertia_offset: 0.175 # measured from model
2011
forearm_mass: 3.989
2112
wrist_1_mass: 2.1
2213
wrist_2_mass: 1.98
@@ -32,47 +23,100 @@ inertia_parameters:
3223
base:
3324
radius: 0.075
3425
length: 0.038
35-
shoulder:
36-
radius: 0.075
37-
length: 0.178
38-
upperarm:
39-
radius: 0.075
40-
length: 0.612
41-
forearm:
42-
radius: 0.075
43-
length: 0.57155
44-
wrist_1:
45-
radius: 0.075
46-
length: 0.12
47-
wrist_2:
48-
radius: 0.075
49-
length: 0.12
50-
wrist_3:
51-
radius: 0.045
52-
length: 0.05
5326

27+
# model referring to https://www.universal-robots.com/articles/ur/application-installation/dh-parameters-for-calculations-of-kinematics-and-dynamics/
5428
center_of_mass:
5529
shoulder_cog:
56-
x: 0.0
57-
y: 0.00244
58-
z: -0.037
30+
x: 0.021 # model.x
31+
y: -0.027 # -model.z
32+
z: 0.0 # model.y
5933
upper_arm_cog:
60-
x: 0.00001
61-
y: 0.15061
62-
z: 0.38757
34+
x: -0.2327 # model.x - upper_arm_length
35+
y: 0.0 # model.y
36+
z: 0.158 # model.z
6337
forearm_cog:
64-
x: -0.00012
65-
y: 0.06112
66-
z: 0.1984
38+
x: -0.33155 # model.x - forearm_length
39+
y: 0.0 # model.y
40+
z: 0.068 # model.z
6741
wrist_1_cog:
68-
x: -0.00021
69-
y: -0.00112
70-
z: 0.02269
42+
x: 0.0 # model.x
43+
y: -0.018 # -model.z
44+
z: 0.007 # model.y
7145
wrist_2_cog:
72-
x: -0.00021
73-
y: 0.00112
74-
z: 0.002269
46+
x: 0.0 # model.x
47+
y: 0.018 # model.z
48+
z: -0.007 # -model.y
7549
wrist_3_cog:
76-
x: 0.0
77-
y: -0.001156
78-
z: -0.00149
50+
x: 0.0 # model.x
51+
y: 0.0 # model.y
52+
z: -0.026 # model.z
53+
54+
rotation:
55+
shoulder:
56+
roll: 1.570796326794897
57+
pitch: 0
58+
yaw: 0
59+
upper_arm:
60+
roll: 0
61+
pitch: 0
62+
yaw: 0
63+
forearm:
64+
roll: 0
65+
pitch: 0
66+
yaw: 0
67+
wrist_1:
68+
roll: 1.570796326794897
69+
pitch: 0
70+
yaw: 0
71+
wrist_2:
72+
roll: -1.570796326794897
73+
pitch: 0
74+
yaw: 0
75+
wrist_3:
76+
roll: 0
77+
pitch: 0
78+
yaw: 0
79+
80+
tensor:
81+
shoulder:
82+
ixx: 0.03408
83+
ixy: 0.00002
84+
ixz: -0.00425
85+
iyy: 0.03529
86+
iyz: 0.00008
87+
izz: 0.02156
88+
upper_arm:
89+
ixx: 0.02814
90+
ixy: 0.00005
91+
ixz: -0.01561
92+
iyy: 0.77068
93+
iyz: 0.00002
94+
izz: 0.76943
95+
forearm:
96+
ixx: 0.01014
97+
ixy: 0.00008
98+
ixz: 0.00916
99+
iyy: 0.30928
100+
iyz: 0.0
101+
izz: 0.30646
102+
wrist_1:
103+
ixx: 0.00296
104+
ixy: -0.00001
105+
ixz: 0.0
106+
iyy: 0.00222
107+
iyz: -0.00024
108+
izz: 0.00258
109+
wrist_2:
110+
ixx: 0.00296
111+
ixy: -0.00001
112+
ixz: 0.0
113+
iyy: 0.00222
114+
iyz: -0.00024
115+
izz: 0.00258
116+
wrist_3:
117+
ixx: 0.00040
118+
ixy: 0.0
119+
ixz: 0.0
120+
iyy: 0.00041
121+
iyz: 0.0
122+
izz: 0.00034

config/ur16e/joint_limits.yaml

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -54,7 +54,7 @@ joint_limits:
5454
has_effort_limits: true
5555
has_position_limits: true
5656
has_velocity_limits: true
57-
max_effort: 56.0
57+
max_effort: 54.0
5858
max_position: !degrees 360.0
5959
max_velocity: !degrees 180.0
6060
min_position: !degrees -360.0
@@ -64,7 +64,7 @@ joint_limits:
6464
has_effort_limits: true
6565
has_position_limits: true
6666
has_velocity_limits: true
67-
max_effort: 56.0
67+
max_effort: 54.0
6868
max_position: !degrees 360.0
6969
max_velocity: !degrees 180.0
7070
min_position: !degrees -360.0
@@ -74,7 +74,7 @@ joint_limits:
7474
has_effort_limits: true
7575
has_position_limits: true
7676
has_velocity_limits: true
77-
max_effort: 56.0
77+
max_effort: 54.0
7878
max_position: !degrees 360.0
7979
max_velocity: !degrees 180.0
8080
min_position: !degrees -360.0

0 commit comments

Comments
 (0)