Skip to content

Commit

Permalink
inertial.sdf: fix ambiguities in documentation (#990)
Browse files Browse the repository at this point in the history
This helps resolve ambiguities in the SDF <inertial> tag by
clarifying the link’s center of mass location, explicitly
stating that the inertia is always about the link’s center of
mass, clarifying the  directions associated with moments/products of
inertia, and clarifying the ± sign convention for product of inertia.

The changes to the 1.5, 1.6, and 1.7 versions of inertial.sdf have
slight modifications to account for the presence of
//inertial/pose/@frame in 1.5, 1.6 and //inertial/pose/@relative_to in 1.7.

Thanks to Paul Mitiguy and Michael Sherman from Toyota Research
Institute for these improvements.

Signed-off-by: Steve Peters <[email protected]>
Co-authored-by: Silvio Traversaro <[email protected]>
  • Loading branch information
scpeters and traversaro authored May 6, 2022
1 parent e18448e commit 6424ffa
Show file tree
Hide file tree
Showing 6 changed files with 314 additions and 54 deletions.
60 changes: 51 additions & 9 deletions sdf/1.4/inertial.sdf
Original file line number Diff line number Diff line change
@@ -1,34 +1,76 @@
<!-- Inertial -->
<element name="inertial" required="0">
<description>The inertial properties of the link.</description>
<description>
The link's mass, position of its center of mass, and its central inertia
properties.
</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 is the pose of the inertial reference frame, relative to the link reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
<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.
</description>
</element>

<element name="inertia" required="0">
<description>The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz.</description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉz.
</description>
</element>
</element> <!-- End Inertia -->
</element> <!-- End Inertial -->
63 changes: 54 additions & 9 deletions sdf/1.5/inertial.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
<!-- Inertial -->
<element name="inertial" required="0">
<description>The inertial properties of the link.</description>
<description>
The link's mass, position of its center of mass, and its central inertia
properties.
</description>

<element name="mass" type="double" default="1.0" required="0">
<description>The mass of the link.</description>
Expand All @@ -9,28 +12,70 @@
<include filename="frame.sdf" required="*"/>

<include filename="pose.sdf" required="0">
<description>This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
<description>
This pose (translation, rotation) describes the position and orientation
of the link's center-of-mass-frame C relative to the frame specified in the @frame attribute.
If the @frame attribute is empty or unspecified, then the link frame L
is used. In this case,
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>
</include>

<element name="inertia" required="0">
<description>The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz.</description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉz.
</description>
</element>
</element> <!-- End Inertia -->
</element> <!-- End Inertial -->
63 changes: 54 additions & 9 deletions sdf/1.6/inertial.sdf
Original file line number Diff line number Diff line change
@@ -1,6 +1,9 @@
<!-- Inertial -->
<element name="inertial" required="0">
<description>The inertial properties of the link.</description>
<description>
The link's mass, position of its center of mass, and its central inertia
properties.
</description>

<element name="mass" type="double" default="1.0" required="0">
<description>The mass of the link.</description>
Expand All @@ -9,28 +12,70 @@
<include filename="frame.sdf" required="*"/>

<include filename="pose.sdf" required="0">
<description>This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
<description>
This pose (translation, rotation) describes the position and orientation
of the link's center-of-mass-frame C relative to the frame specified in the @frame attribute.
If the @frame attribute is empty or unspecified, then the link frame L
is used. In this case,
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>
</include>

<element name="inertia" required="0">
<description>The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz.</description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉz.
</description>
</element>
</element> <!-- End Inertia -->
</element> <!-- End Inertial -->
63 changes: 54 additions & 9 deletions sdf/1.7/inertial.sdf
Original file line number Diff line number Diff line change
@@ -1,34 +1,79 @@
<!-- Inertial -->
<element name="inertial" required="0">
<description>The inertial properties of the link.</description>
<description>
The link's mass, position of its center of mass, and its central inertia
properties.
</description>

<element name="mass" type="double" default="1.0" required="0">
<description>The mass of the link.</description>
</element>

<include filename="pose.sdf" required="0">
<description>This is the pose of the inertial reference frame, relative to the specified reference frame. The origin of the inertial reference frame needs to be at the center of gravity. The axes of the inertial reference frame do not need to be aligned with the principal axes of the inertia.</description>
<description>
This pose (translation, rotation) describes the position and orientation
of the link's center-of-mass-frame C relative to the frame specified in the @relative_to attribute.
If the @relative_to attribute is empty or unspecified, then the link frame L
is used. In this case,
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>
</include>

<element name="inertia" required="0">
<description>The 3x3 rotational inertia matrix. Because the rotational inertia matrix is symmetric, only 6 above-diagonal elements of this matrix are specified here, using the attributes ixx, ixy, ixz, iyy, iyz, izz.</description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<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></description>
<description>
The link's moment of inertia about Co (the link's center of mass) for Ĉz.
</description>
</element>
</element> <!-- End Inertia -->
</element> <!-- End Inertial -->
Loading

0 comments on commit 6424ffa

Please sign in to comment.