Skip to content

Commit

Permalink
rescale inertia to match specified mass
Browse files Browse the repository at this point in the history
Signed-off-by: Ian Chen <[email protected]>
  • Loading branch information
iche033 committed Dec 9, 2024
1 parent 69c82c0 commit f253f0d
Show file tree
Hide file tree
Showing 2 changed files with 66 additions and 4 deletions.
24 changes: 21 additions & 3 deletions src/Link.cc
Original file line number Diff line number Diff line change
Expand Up @@ -211,7 +211,6 @@ Errors Link::Load(ElementPtr _sdf, const ParserConfig &_config)
// If auto is to true but user has still provided
// inertial values
if (inertialElem->HasElement("pose") ||
inertialElem->HasElement("mass") ||
inertialElem->HasElement("inertia"))
{
Error err(
Expand Down Expand Up @@ -681,7 +680,27 @@ void Link::ResolveAutoInertials(sdf::Errors &_errors,
totalInertia = totalInertia + collisionInertia;
}

this->dataPtr->inertial = totalInertia;
// If mass is specified, scale inertia to match desired mass
auto inertialElem = this->dataPtr->sdf->GetElement("inertial");
if (inertialElem->HasElement("mass"))
{
double mass = inertialElem->Get<double>("mass");
const gz::math::MassMatrix3d &totalMassMatrix = totalInertia.MassMatrix();
// normalize to get the unit mass matrix
gz::math::MassMatrix3d unitMassMatrix(1.0,
totalMassMatrix.DiagonalMoments() / totalMassMatrix.Mass(),
totalMassMatrix.OffDiagonalMoments() / totalMassMatrix.Mass());
// scale the final inertia to match specified mass
this->dataPtr->inertial = gz::math::Inertiald(
gz::math::MassMatrix3d(mass,
mass * unitMassMatrix.DiagonalMoments(),
mass * unitMassMatrix.OffDiagonalMoments()),
totalInertia.Pose());
}
else
{
this->dataPtr->inertial = totalInertia;
}

// If CalculateInertial() was called with SAVE_CALCULATION
// configuration then set autoInertiaSaved to true
Expand All @@ -695,7 +714,6 @@ void Link::ResolveAutoInertials(sdf::Errors &_errors,
{
this->dataPtr->autoInertiaSaved = true;
// Write calculated inertia values to //link/inertial element
auto inertialElem = this->dataPtr->sdf->GetElement("inertial");
inertialElem->GetElement("pose")->GetValue()->Set<gz::math::Pose3d>(
totalInertia.Pose());
inertialElem->GetElement("mass")->GetValue()->Set<double>(
Expand Down
46 changes: 45 additions & 1 deletion src/Link_TEST.cc
Original file line number Diff line number Diff line change
Expand Up @@ -725,7 +725,7 @@ TEST(DOMLink, ResolveAutoInertialsWithMultipleCollisions)
}

/////////////////////////////////////////////////
TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
TEST(DOMLink, ResolveAutoInertialsWithMass)
{
std::string sdf = "<?xml version=\"1.0\"?>"
"<sdf version=\"1.11\">"
Expand Down Expand Up @@ -763,6 +763,50 @@ TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
root.ResolveAutoInertials(errors, sdfParserConfig);
EXPECT_TRUE(errors.empty());

EXPECT_DOUBLE_EQ(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_EQ(gz::math::Pose3d::Zero, link->Inertial().Pose());
EXPECT_EQ(gz::math::Vector3d(0.66666, 0.66666, 0.66666),
link->Inertial().MassMatrix().DiagonalMoments());
}

/////////////////////////////////////////////////
TEST(DOMLink, InertialValuesGivenWithAutoSetToTrue)
{
std::string sdf = "<?xml version=\"1.0\"?>"
"<sdf version=\"1.11\">"
" <model name='compound_model'>"
" <link name='compound_link'>"
" <inertial auto='true'>"
" <pose>1 1 1 2 2 2</pose>"
" <inertia>"
" <ixx>1</ixx>"
" <iyy>1</iyy>"
" <izz>1</izz>"
" </inertia>"
" </inertial>"
" <collision name='box_collision'>"
" <density>2.0</density>"
" <geometry>"
" <box>"
" <size>1 1 1</size>"
" </box>"
" </geometry>"
" </collision>"
" </link>"
" </model>"
" </sdf>";

sdf::Root root;
const sdf::ParserConfig sdfParserConfig;
sdf::Errors errors = root.LoadSdfString(sdf, sdfParserConfig);
EXPECT_TRUE(errors.empty());
EXPECT_NE(nullptr, root.Element());

const sdf::Model *model = root.Model();
const sdf::Link *link = model->LinkByIndex(0);
root.ResolveAutoInertials(errors, sdfParserConfig);
EXPECT_TRUE(errors.empty());

EXPECT_NE(4.0, link->Inertial().MassMatrix().Mass());
EXPECT_EQ(gz::math::Pose3d::Zero, link->Inertial().Pose());
EXPECT_EQ(gz::math::Vector3d(0.33333, 0.33333, 0.33333),
Expand Down

0 comments on commit f253f0d

Please sign in to comment.