diff --git a/sdf/1.4/inertial.sdf b/sdf/1.4/inertial.sdf index 417489f80..242175d1b 100644 --- a/sdf/1.4/inertial.sdf +++ b/sdf/1.4/inertial.sdf @@ -1,34 +1,76 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. - 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. + + 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. + - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + diff --git a/sdf/1.5/inertial.sdf b/sdf/1.5/inertial.sdf index b8160bf40..e31a1360a 100644 --- a/sdf/1.5/inertial.sdf +++ b/sdf/1.5/inertial.sdf @@ -1,6 +1,9 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. @@ -9,28 +12,70 @@ - 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. + + 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. + - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + diff --git a/sdf/1.6/inertial.sdf b/sdf/1.6/inertial.sdf index b8160bf40..e31a1360a 100644 --- a/sdf/1.6/inertial.sdf +++ b/sdf/1.6/inertial.sdf @@ -1,6 +1,9 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. @@ -9,28 +12,70 @@ - 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. + + 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. + - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + diff --git a/sdf/1.7/inertial.sdf b/sdf/1.7/inertial.sdf index 963f4b2c3..8c935f8ca 100644 --- a/sdf/1.7/inertial.sdf +++ b/sdf/1.7/inertial.sdf @@ -1,34 +1,79 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. - 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. + + 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. + - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + diff --git a/sdf/1.8/inertial.sdf b/sdf/1.8/inertial.sdf index a6568f58a..242175d1b 100644 --- a/sdf/1.8/inertial.sdf +++ b/sdf/1.8/inertial.sdf @@ -1,34 +1,76 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. - This is the pose of the inertial 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. + + 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. + - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. + diff --git a/sdf/1.9/inertial.sdf b/sdf/1.9/inertial.sdf index 53dd9e485..5dae1eaf3 100644 --- a/sdf/1.9/inertial.sdf +++ b/sdf/1.9/inertial.sdf @@ -1,6 +1,9 @@ - The inertial properties of the link. + + The link's mass, position of its center of mass, and its central inertia + properties. + The mass of the link. @@ -8,7 +11,15 @@ - A pose (translation, rotation) expressed in the frame of the link. The first three components (x, y, z) represent the position of the element's origin (in the @relative_to frame). The rotation component represents the orientation of the element as either a sequence of Euler rotations (r, p, y), see http://sdformat.org/tutorials?tut=specify_pose, or as a quaternion (x, y, z, w), where w is the real component. + 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. @@ -27,24 +38,54 @@ - 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. + + 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 + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉx. + - + + 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. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉy. + - + + 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. + - + + The link's moment of inertia about Co (the link's center of mass) for Ĉz. +