Skip to content
Merged
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
122 changes: 120 additions & 2 deletions sdf/1.10/inertial.sdf
Original file line number Diff line number Diff line change
@@ -1,8 +1,8 @@
<!-- Inertial -->
<element name="inertial" required="0">
<description>
The link's mass, position of its center of mass, and its central inertia
properties.
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">
Expand Down Expand Up @@ -88,4 +88,122 @@
</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 -->
83 changes: 83 additions & 0 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -173,6 +173,62 @@ Errors Link::Load(ElementPtr _sdf)
xyxzyz.Y(inertiaElem->Get<double>("ixz", 0.0).first);
xyxzyz.Z(inertiaElem->Get<double>("iyz", 0.0).first);
}

if (inertialElem->HasElement("fluid_added_mass"))
{
auto addedMassElem = inertialElem->GetElement("fluid_added_mass");

gz::math::Matrix6d addedMass;
addedMass(0, 0) = addedMassElem->Get<double>("xx", 0.0).first;
addedMass(0, 1) = addedMassElem->Get<double>("xy", 0.0).first;
addedMass(0, 2) = addedMassElem->Get<double>("xz", 0.0).first;
addedMass(0, 3) = addedMassElem->Get<double>("xp", 0.0).first;
addedMass(0, 4) = addedMassElem->Get<double>("xq", 0.0).first;
addedMass(0, 5) = addedMassElem->Get<double>("xr", 0.0).first;

addedMass(1, 0) = addedMass(0, 1);
addedMass(1, 1) = addedMassElem->Get<double>("yy", 0.0).first;
addedMass(1, 2) = addedMassElem->Get<double>("yz", 0.0).first;
addedMass(1, 3) = addedMassElem->Get<double>("yp", 0.0).first;
addedMass(1, 4) = addedMassElem->Get<double>("yq", 0.0).first;
addedMass(1, 5) = addedMassElem->Get<double>("yr", 0.0).first;

addedMass(2, 0) = addedMass(0, 2);
addedMass(2, 1) = addedMass(1, 2);
addedMass(2, 2) = addedMassElem->Get<double>("zz", 0.0).first;
addedMass(2, 3) = addedMassElem->Get<double>("zp", 0.0).first;
addedMass(2, 4) = addedMassElem->Get<double>("zq", 0.0).first;
addedMass(2, 5) = addedMassElem->Get<double>("zr", 0.0).first;

addedMass(3, 0) = addedMass(0, 3);
addedMass(3, 1) = addedMass(1, 3);
addedMass(3, 2) = addedMass(2, 3);
addedMass(3, 3) = addedMassElem->Get<double>("pp", 0.0).first;
addedMass(3, 4) = addedMassElem->Get<double>("pq", 0.0).first;
addedMass(3, 5) = addedMassElem->Get<double>("pr", 0.0).first;

addedMass(4, 0) = addedMass(0, 4);
addedMass(4, 1) = addedMass(1, 4);
addedMass(4, 2) = addedMass(2, 4);
addedMass(4, 3) = addedMass(3, 4);
addedMass(4, 4) = addedMassElem->Get<double>("qq", 0.0).first;
addedMass(4, 5) = addedMassElem->Get<double>("qr", 0.0).first;

addedMass(5, 0) = addedMass(0, 5);
addedMass(5, 1) = addedMass(1, 5);
addedMass(5, 2) = addedMass(2, 5);
addedMass(5, 3) = addedMass(3, 5);
addedMass(5, 4) = addedMass(4, 5);
addedMass(5, 5) = addedMassElem->Get<double>("rr", 0.0).first;

if (!this->dataPtr->inertial.SetFluidAddedMass(addedMass))
{
errors.push_back({ErrorCode::LINK_INERTIA_INVALID,
"A link named " +
this->Name() +
" has invalid fluid added mass."});
}
}
}
if (!this->dataPtr->inertial.SetMassMatrix(
gz::math::MassMatrix3d(mass, xxyyzz, xyxzyz)))
Expand Down Expand Up @@ -676,6 +732,33 @@ sdf::ElementPtr Link::ToElement() const
inertiaElem->GetElement("iyz")->Set(massMatrix.Iyz());
inertiaElem->GetElement("izz")->Set(massMatrix.Izz());

if (this->dataPtr->inertial.FluidAddedMass().has_value())
{
auto addedMass = this->dataPtr->inertial.FluidAddedMass().value();
auto addedMassElem = inertialElem->GetElement("fluid_added_mass");
addedMassElem->GetElement("xx")->Set(addedMass(0, 0));
addedMassElem->GetElement("xy")->Set(addedMass(0, 1));
addedMassElem->GetElement("xz")->Set(addedMass(0, 2));
addedMassElem->GetElement("xp")->Set(addedMass(0, 3));
addedMassElem->GetElement("xq")->Set(addedMass(0, 4));
addedMassElem->GetElement("xr")->Set(addedMass(0, 5));
addedMassElem->GetElement("yy")->Set(addedMass(1, 1));
addedMassElem->GetElement("yz")->Set(addedMass(1, 2));
addedMassElem->GetElement("yp")->Set(addedMass(1, 3));
addedMassElem->GetElement("yq")->Set(addedMass(1, 4));
addedMassElem->GetElement("yr")->Set(addedMass(1, 5));
addedMassElem->GetElement("zz")->Set(addedMass(2, 2));
addedMassElem->GetElement("zp")->Set(addedMass(2, 3));
addedMassElem->GetElement("zq")->Set(addedMass(2, 4));
addedMassElem->GetElement("zr")->Set(addedMass(2, 5));
addedMassElem->GetElement("pp")->Set(addedMass(3, 3));
addedMassElem->GetElement("pq")->Set(addedMass(3, 4));
addedMassElem->GetElement("pr")->Set(addedMass(3, 5));
addedMassElem->GetElement("qq")->Set(addedMass(4, 4));
addedMassElem->GetElement("qr")->Set(addedMass(4, 5));
addedMassElem->GetElement("rr")->Set(addedMass(5, 5));
}

// wind mode
elem->GetElement("enable_wind")->Set(this->EnableWind());

Expand Down
56 changes: 54 additions & 2 deletions src/Link_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -101,6 +101,8 @@ TEST(DOMLink, Construction)
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().X());
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().Y());
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().Z());
EXPECT_FALSE(inertial.FluidAddedMass().has_value());
EXPECT_EQ(inertial.BodyMatrix(), inertial.SpatialMatrix());
EXPECT_TRUE(inertial.MassMatrix().IsValid());

EXPECT_EQ(0u, link.CollisionCount());
Expand All @@ -113,7 +115,13 @@ TEST(DOMLink, Construction)
{2.3,
gz::math::Vector3d(1.4, 2.3, 3.2),
gz::math::Vector3d(0.1, 0.2, 0.3)},
gz::math::Pose3d(1, 2, 3, 0, 0, 0)};
gz::math::Pose3d(1, 2, 3, 0, 0, 0),
{1, 2, 3, 4, 5, 6,
2, 7, 8, 9, 10, 11,
3, 8, 12, 13, 14, 15,
4, 9, 13, 16, 17, 18,
5, 10, 14, 17, 19, 20,
6, 11, 15, 18, 20, 21}};

EXPECT_TRUE(link.SetInertial(inertial2));

Expand All @@ -125,6 +133,44 @@ TEST(DOMLink, Construction)
EXPECT_DOUBLE_EQ(0.2, link.Inertial().MassMatrix().OffDiagonalMoments().Y());
EXPECT_DOUBLE_EQ(0.3, link.Inertial().MassMatrix().OffDiagonalMoments().Z());
EXPECT_TRUE(link.Inertial().MassMatrix().IsValid());

ASSERT_TRUE(link.Inertial().FluidAddedMass().has_value());
EXPECT_DOUBLE_EQ(1.0, link.Inertial().FluidAddedMass().value()(0, 0));
EXPECT_DOUBLE_EQ(2.0, link.Inertial().FluidAddedMass().value()(0, 1));
EXPECT_DOUBLE_EQ(3.0, link.Inertial().FluidAddedMass().value()(0, 2));
EXPECT_DOUBLE_EQ(4.0, link.Inertial().FluidAddedMass().value()(0, 3));
EXPECT_DOUBLE_EQ(5.0, link.Inertial().FluidAddedMass().value()(0, 4));
EXPECT_DOUBLE_EQ(6.0, link.Inertial().FluidAddedMass().value()(0, 5));
EXPECT_DOUBLE_EQ(2.0, link.Inertial().FluidAddedMass().value()(1, 0));
EXPECT_DOUBLE_EQ(7.0, link.Inertial().FluidAddedMass().value()(1, 1));
EXPECT_DOUBLE_EQ(8.0, link.Inertial().FluidAddedMass().value()(1, 2));
EXPECT_DOUBLE_EQ(9.0, link.Inertial().FluidAddedMass().value()(1, 3));
EXPECT_DOUBLE_EQ(10.0, link.Inertial().FluidAddedMass().value()(1, 4));
EXPECT_DOUBLE_EQ(11.0, link.Inertial().FluidAddedMass().value()(1, 5));
EXPECT_DOUBLE_EQ(3.0, link.Inertial().FluidAddedMass().value()(2, 0));
EXPECT_DOUBLE_EQ(8.0, link.Inertial().FluidAddedMass().value()(2, 1));
EXPECT_DOUBLE_EQ(12.0, link.Inertial().FluidAddedMass().value()(2, 2));
EXPECT_DOUBLE_EQ(13.0, link.Inertial().FluidAddedMass().value()(2, 3));
EXPECT_DOUBLE_EQ(14.0, link.Inertial().FluidAddedMass().value()(2, 4));
EXPECT_DOUBLE_EQ(15.0, link.Inertial().FluidAddedMass().value()(2, 5));
EXPECT_DOUBLE_EQ(4.0, link.Inertial().FluidAddedMass().value()(3, 0));
EXPECT_DOUBLE_EQ(9.0, link.Inertial().FluidAddedMass().value()(3, 1));
EXPECT_DOUBLE_EQ(13.0, link.Inertial().FluidAddedMass().value()(3, 2));
EXPECT_DOUBLE_EQ(16.0, link.Inertial().FluidAddedMass().value()(3, 3));
EXPECT_DOUBLE_EQ(17.0, link.Inertial().FluidAddedMass().value()(3, 4));
EXPECT_DOUBLE_EQ(18.0, link.Inertial().FluidAddedMass().value()(3, 5));
EXPECT_DOUBLE_EQ(5.0, link.Inertial().FluidAddedMass().value()(4, 0));
EXPECT_DOUBLE_EQ(10.0, link.Inertial().FluidAddedMass().value()(4, 1));
EXPECT_DOUBLE_EQ(14.0, link.Inertial().FluidAddedMass().value()(4, 2));
EXPECT_DOUBLE_EQ(17.0, link.Inertial().FluidAddedMass().value()(4, 3));
EXPECT_DOUBLE_EQ(19.0, link.Inertial().FluidAddedMass().value()(4, 4));
EXPECT_DOUBLE_EQ(20.0, link.Inertial().FluidAddedMass().value()(4, 5));
EXPECT_DOUBLE_EQ(6.0, link.Inertial().FluidAddedMass().value()(5, 0));
EXPECT_DOUBLE_EQ(11.0, link.Inertial().FluidAddedMass().value()(5, 1));
EXPECT_DOUBLE_EQ(15.0, link.Inertial().FluidAddedMass().value()(5, 2));
EXPECT_DOUBLE_EQ(18.0, link.Inertial().FluidAddedMass().value()(5, 3));
EXPECT_DOUBLE_EQ(20.0, link.Inertial().FluidAddedMass().value()(5, 4));
EXPECT_DOUBLE_EQ(21.0, link.Inertial().FluidAddedMass().value()(5, 5));
}

/////////////////////////////////////////////////
Expand Down Expand Up @@ -314,7 +360,13 @@ TEST(DOMLink, ToElement)
{2.3,
gz::math::Vector3d(1.4, 2.3, 3.2),
gz::math::Vector3d(0.1, 0.2, 0.3)},
gz::math::Pose3d(1, 2, 3, 0, 0, 0)};
gz::math::Pose3d(1, 2, 3, 0, 0, 0),
{1, 2, 3, 4, 5, 6,
2, 7, 8, 9, 10, 11,
3, 8, 12, 13, 14, 15,
4, 9, 13, 16, 17, 18,
5, 10, 14, 17, 19, 20,
6, 11, 15, 18, 20, 21}};
EXPECT_TRUE(link.SetInertial(inertial));
link.SetRawPose(gz::math::Pose3d(1, 2, 3, 0.1, 0.2, 0.3));
link.SetEnableWind(true);
Expand Down
41 changes: 41 additions & 0 deletions test/integration/link_dom.cc
Original file line number Diff line number Diff line change
Expand Up @@ -138,6 +138,7 @@ TEST(DOMLink, InertialDoublePendulum)
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().X());
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().Y());
EXPECT_DOUBLE_EQ(0.0, inertial.MassMatrix().OffDiagonalMoments().Z());
EXPECT_FALSE(inertial.FluidAddedMass().has_value());

const sdf::Link *upperLink = model->LinkByIndex(1);
ASSERT_NE(nullptr, upperLink);
Expand All @@ -158,6 +159,7 @@ TEST(DOMLink, InertialDoublePendulum)
EXPECT_DOUBLE_EQ(0.0, inertialUpper.Pose().Pos().Y());
EXPECT_DOUBLE_EQ(0.5, inertialUpper.Pose().Pos().Z());
EXPECT_TRUE(inertial.MassMatrix().IsValid());
EXPECT_FALSE(inertial.FluidAddedMass().has_value());

const sdf::Link *lowerLink = model->LinkByIndex(2);
ASSERT_TRUE(lowerLink != nullptr);
Expand Down Expand Up @@ -195,6 +197,45 @@ TEST(DOMLink, InertialComplete)
EXPECT_DOUBLE_EQ(0.0, inertial.Pose().Pos().Y());
EXPECT_DOUBLE_EQ(0.02, inertial.Pose().Pos().Z());
EXPECT_TRUE(inertial.MassMatrix().IsValid());

ASSERT_TRUE(inertial.FluidAddedMass().has_value());
auto addedMass = inertial.FluidAddedMass().value();
EXPECT_DOUBLE_EQ(11, addedMass(0, 0));
EXPECT_DOUBLE_EQ(12, addedMass(0, 1));
EXPECT_DOUBLE_EQ(13, addedMass(0, 2));
EXPECT_DOUBLE_EQ(14, addedMass(0, 3));
EXPECT_DOUBLE_EQ(15, addedMass(0, 4));
EXPECT_DOUBLE_EQ(16, addedMass(0, 5));
EXPECT_DOUBLE_EQ(12, addedMass(1, 0));
EXPECT_DOUBLE_EQ(22, addedMass(1, 1));
EXPECT_DOUBLE_EQ(23, addedMass(1, 2));
EXPECT_DOUBLE_EQ(24, addedMass(1, 3));
EXPECT_DOUBLE_EQ(25, addedMass(1, 4));
EXPECT_DOUBLE_EQ(26, addedMass(1, 5));
EXPECT_DOUBLE_EQ(13, addedMass(2, 0));
EXPECT_DOUBLE_EQ(23, addedMass(2, 1));
EXPECT_DOUBLE_EQ(33, addedMass(2, 2));
EXPECT_DOUBLE_EQ(34, addedMass(2, 3));
EXPECT_DOUBLE_EQ(35, addedMass(2, 4));
EXPECT_DOUBLE_EQ(36, addedMass(2, 5));
EXPECT_DOUBLE_EQ(14, addedMass(3, 0));
EXPECT_DOUBLE_EQ(24, addedMass(3, 1));
EXPECT_DOUBLE_EQ(34, addedMass(3, 2));
EXPECT_DOUBLE_EQ(44, addedMass(3, 3));
EXPECT_DOUBLE_EQ(45, addedMass(3, 4));
EXPECT_DOUBLE_EQ(46, addedMass(3, 5));
EXPECT_DOUBLE_EQ(15, addedMass(4, 0));
EXPECT_DOUBLE_EQ(25, addedMass(4, 1));
EXPECT_DOUBLE_EQ(35, addedMass(4, 2));
EXPECT_DOUBLE_EQ(45, addedMass(4, 3));
EXPECT_DOUBLE_EQ(55, addedMass(4, 4));
EXPECT_DOUBLE_EQ(56, addedMass(4, 5));
EXPECT_DOUBLE_EQ(16, addedMass(5, 0));
EXPECT_DOUBLE_EQ(26, addedMass(5, 1));
EXPECT_DOUBLE_EQ(36, addedMass(5, 2));
EXPECT_DOUBLE_EQ(46, addedMass(5, 3));
EXPECT_DOUBLE_EQ(56, addedMass(5, 4));
EXPECT_DOUBLE_EQ(66, addedMass(5, 5));
}

//////////////////////////////////////////////////
Expand Down
Loading