-
Notifications
You must be signed in to change notification settings - Fork 119
Expand file tree
/
Copy pathinertial.sdf
More file actions
209 lines (202 loc) · 9.6 KB
/
inertial.sdf
File metadata and controls
209 lines (202 loc) · 9.6 KB
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
<!-- Inertial -->
<element name="inertial" required="0">
<description>
The link's mass, position of its center of mass, its central inertia
properties, and optionally its fluid added mass.
</description>
<element name="mass" type="double" default="1.0" required="0">
<description>The mass of the link.</description>
</element>
<element name="pose" type="pose" default="0 0 0 0 0 0" required="0">
<description>
This pose (translation, rotation) describes the position and orientation
of the link's center-of-mass-frame C relative to the link-frame L.
The first three components (x y z) specify the position vector from Lo
(the link-frame origin) to Co (the link's center of mass) as
`x L̂x + y L̂y + z L̂ᴢ`, where L̂x, L̂y, L̂ᴢ are link-frame L's orthogonal unit
vectors. The subsequent values characterize C's orientation relative to
link-frame L as a sequence of Euler rotations
(r p y) documented in http://sdformat.org/tutorials?tut=specify_pose,
or as a quaternion (x y z w), where w is the scalar component.
</description>
<attribute name="rotation_format" type="string" default="euler_rpy" required="0">
<description>'euler_rpy' by default. Supported rotation formats are
'euler_rpy', Euler angles representation in roll, pitch, yaw. The pose is expected to have 6 values.
'quat_xyzw', Quaternion representation in x, y, z, w. The pose is expected to have 7 values.
</description>
</attribute>
<attribute name="degrees" type="bool" default="false" required="0">
<description>
Whether or not the euler angles are in degrees, otherwise they will be interpreted as radians by default.
</description>
</attribute>
</element>
<element name="inertia" required="0">
<description>
This link's moments of inertia ixx, iyy, izz and products of inertia
ixy, ixz, iyz about Co (the link's center of mass) for the unit vectors
Ĉx, Ĉy, Ĉᴢ fixed in the center-of-mass-frame C.
Note: the orientation of Ĉx, Ĉy, Ĉᴢ relative to L̂x, L̂y, L̂ᴢ is specified
by the `pose` tag.
To avoid compatibility issues associated with the negative sign
convention for product of inertia, align Ĉx, Ĉy, Ĉᴢ with principal
inertia directions so that all the products of inertia are zero.
For more information about this sign convention, see the following
MathWorks documentation for working with CAD tools:
https://www.mathworks.com/help/releases/R2021b/physmod/sm/ug/specify-custom-inertia.html#mw_b043ec69-835b-4ca9-8769-af2e6f1b190c
</description>
<element name="ixx" type="double" default="1.0" required="1">
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉx.
</description>
</element>
<element name="ixy" type="double" default="0.0" required="1">
<description>
The link's product of inertia about Co (the link's center of mass) for
Ĉx and Ĉy, where the product of inertia convention -m x y (not +m x y)
is used. If Ĉx or Ĉy is a principal inertia direction, ixy = 0.
</description>
</element>
<element name="ixz" type="double" default="0.0" required="1">
<description>
The link's product of inertia about Co (the link's center of mass) for
Ĉx and Ĉz, where the product of inertia convention -m x z (not +m x z)
is used. If Ĉx or Ĉz is a principal inertia direction, ixz = 0.
</description>
</element>
<element name="iyy" type="double" default="1.0" required="1">
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉy.
</description>
</element>
<element name="iyz" type="double" default="0.0" required="1">
<description>
The link's product of inertia about Co (the link's center of mass) for
Ĉy and Ĉz, where the product of inertia convention -m y z (not +m y z)
is used. If Ĉy or Ĉz is a principal inertia direction, iyz = 0.
</description>
</element>
<element name="izz" type="double" default="1.0" required="1">
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉz.
</description>
</element>
</element> <!-- End Inertia -->
<element name="fluid_added_mass" required="0">
<description>
This link's fluid added mass matrix about the link's origin.
This matrix represents the inertia of the fluid that is dislocated when the
body moves. Added mass should be zero if the density of the surrounding
fluid is negligible with respect to the body's density.
The 6x6 matrix is symmetric, therefore only 21 unique elements can be set.
The elements of the matrix follow the [x, y, z, p, q, r] notation, where
[x, y, z] correspond to translation and [p, q, r] to rotation
(i.e. roll, pitch, yaw).
</description>
<element name="xx" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to linear acceleration in the X axis, in kg.
</description>
</element>
<element name="xy" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to linear acceleration in the Y axis, and vice-versa, in kg.
</description>
</element>
<element name="xz" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to linear acceleration in the Z axis, and vice-versa, in kg.
</description>
</element>
<element name="xp" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to angular acceleration about the X axis, and vice-versa, in kg * m.
</description>
</element>
<element name="xq" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to angular acceleration about the Y axis, and vice-versa, in kg * m.
</description>
</element>
<element name="xr" type="double" default="0.0" required="0">
<description>
Added mass in the X axis due to angular acceleration about the Z axis, and vice-versa, in kg * m.
</description>
</element>
<element name="yy" type="double" default="0.0" required="0">
<description>
Added mass in the Y axis due to linear acceleration in the Y axis, in kg.
</description>
</element>
<element name="yz" type="double" default="0.0" required="0">
<description>
Added mass in the Y axis due to linear acceleration in the Z axis, and vice-versa, in kg.
</description>
</element>
<element name="yp" type="double" default="0.0" required="0">
<description>
Added mass in the Y axis due to angular acceleration about the X axis, and vice-versa, in kg * m.
</description>
</element>
<element name="yq" type="double" default="0.0" required="0">
<description>
Added mass in the Y axis due to angular acceleration about the Y axis, and vice-versa, in kg * m.
</description>
</element>
<element name="yr" type="double" default="0.0" required="0">
<description>
Added mass in the Y axis due to angular acceleration about the Z axis, and vice-versa, in kg * m.
</description>
</element>
<element name="zz" type="double" default="0.0" required="0">
<description>
Added mass in the Z axis due to linear acceleration in the Z axis, in kg.
</description>
</element>
<element name="zp" type="double" default="0.0" required="0">
<description>
Added mass in the Z axis due to angular acceleration about the X axis, and vice-versa, in kg * m.
</description>
</element>
<element name="zq" type="double" default="0.0" required="0">
<description>
Added mass in the Z axis due to angular acceleration about the Y axis, and vice-versa, in kg * m.
</description>
</element>
<element name="zr" type="double" default="0.0" required="0">
<description>
Added mass in the Z axis due to angular acceleration about the Z axis, and vice-versa, in kg * m.
</description>
</element>
<element name="pp" type="double" default="0.0" required="0">
<description>
Added mass moment about the X axis due to angular acceleration about the X axis, in kg * m^2.
</description>
</element>
<element name="pq" type="double" default="0.0" required="0">
<description>
Added mass moment about the X axis due to angular acceleration about the Y axis, and vice-versa, in kg * m^2.
</description>
</element>
<element name="pr" type="double" default="0.0" required="0">
<description>
Added mass moment about the X axis due to angular acceleration about the Z axis, and vice-versa, in kg * m^2.
</description>
</element>
<element name="qq" type="double" default="0.0" required="0">
<description>
Added mass moment about the Y axis due to angular acceleration about the Y axis, in kg * m^2.
</description>
</element>
<element name="qr" type="double" default="0.0" required="0">
<description>
Added mass moment about the Y axis due to angular acceleration about the Z axis, and vice-versa, in kg * m^2.
</description>
</element>
<element name="rr" type="double" default="0.0" required="0">
<description>
Added mass moment about the Z axis due to angular acceleration about the Z axis, in kg * m^2.
</description>
</element>
</element> <!-- End fluid added mass -->
</element> <!-- End Inertial -->