Skip to content

Commit

Permalink
bullet-featherstone: support off-diagonal inertia
Browse files Browse the repository at this point in the history
The bullet APIs expect the moment of inertia matrix
to already be diagonalized. This changes the
bullet-featherstone plugin to compute the principal
moments of inertia in the same manner as the bullet
plugin. It will now load models with off-diagonal
inertia values without giving errors.

Signed-off-by: Steve Peters <[email protected]>
  • Loading branch information
scpeters committed Sep 20, 2023
1 parent 6a21a96 commit b541796
Showing 1 changed file with 33 additions and 52 deletions.
85 changes: 33 additions & 52 deletions bullet-featherstone/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -116,6 +116,7 @@ struct Structure
const ::sdf::Joint *rootJoint;
btScalar mass;
btVector3 inertia;
math::Pose3d linkToPrincipalAxesPose;

/// Is the root link fixed
bool fixedBase;
Expand All @@ -127,6 +128,20 @@ struct Structure
std::vector<const ::sdf::Link*> flatLinks;
};

/////////////////////////////////////////////////
void extractInertial(
const math::Inertiald &_inertial,
btScalar &_mass,
btVector3 &_principalInertiaMoments,
math::Pose3d &_linkToPrincipalAxesPose)
{
const auto &M = _inertial.MassMatrix();
_mass = static_cast<btScalar>(M.Mass());
_principalInertiaMoments = convertVec(M.PrincipalMoments());
_linkToPrincipalAxesPose = _inertial.Pose();
_linkToPrincipalAxesPose.Rot() *= M.PrincipalAxesOffset();
}

/////////////////////////////////////////////////
std::optional<Structure> ValidateModel(const ::sdf::Model &_sdfModel)
{
Expand Down Expand Up @@ -319,23 +334,14 @@ std::optional<Structure> ValidateModel(const ::sdf::Model &_sdfModel)
return std::nullopt;
}

const auto &M = rootLink->Inertial().MassMatrix();
const auto mass = static_cast<btScalar>(M.Mass());
btVector3 inertia(convertVec(M.DiagonalMoments()));
for (const double &I : {M.Ixy(), M.Ixz(), M.Iyz()})
{
if (std::abs(I) > 1e-3)
{
gzerr << "The base link of the model is required to have a diagonal "
<< "inertia matrix by gz-physics-bullet-featherstone, but the "
<< "Model [" << _sdfModel.Name() << "] has a non-zero diagonal "
<< "value: " << I << "\n";
return std::nullopt;
}
}
btScalar mass;
btVector3 inertia;
math::Pose3d linkToPrincipalAxesPose;
extractInertial(rootLink->Inertial(), mass, inertia, linkToPrincipalAxesPose);

return Structure{
rootLink, rootJoint, mass, inertia, fixed, parentOf, flatLinks};
rootLink, rootJoint, mass, inertia, linkToPrincipalAxesPose, fixed,
parentOf, flatLinks};
}

/////////////////////////////////////////////////
Expand All @@ -353,7 +359,7 @@ Identity SDFFeatures::ConstructSdfModel(
const auto *world = this->ReferenceInterface<WorldInfo>(_worldID);

const auto rootInertialToLink =
gz::math::eigen3::convert(structure.rootLink->Inertial().Pose()).inverse();
gz::math::eigen3::convert(structure.linkToPrincipalAxesPose).inverse();
const auto modelID = this->AddModel(
_sdfModel.Name(), _worldID, rootInertialToLink,
std::make_unique<btMultiBody>(
Expand Down Expand Up @@ -392,8 +398,12 @@ Identity SDFFeatures::ConstructSdfModel(
for (int i = 0; i < static_cast<int>(structure.flatLinks.size()); ++i)
{
const auto *link = structure.flatLinks[static_cast<std::size_t>(i)];
btScalar mass;
btVector3 inertia;
math::Pose3d linkToPrincipalAxesPose;
extractInertial(link->Inertial(), mass, inertia, linkToPrincipalAxesPose);
const Eigen::Isometry3d linkToComTf = gz::math::eigen3::convert(
link->Inertial().Pose());
linkToPrincipalAxesPose);

if (linkIDs.find(link) == linkIDs.end())
{
Expand All @@ -402,22 +412,6 @@ Identity SDFFeatures::ConstructSdfModel(
linkIDs.insert(std::make_pair(link, linkID));
}

const auto &M = link->Inertial().MassMatrix();
const btScalar mass = static_cast<btScalar>(M.Mass());
const auto inertia = btVector3(convertVec(M.DiagonalMoments()));

for (const double I : {M.Ixy(), M.Ixz(), M.Iyz()})
{
if (std::abs(I) > 1e-3)
{
gzerr << "Links are required to have a diagonal inertia matrix in "
<< "gz-physics-bullet-featherstone, but Link [" << link->Name()
<< "] in Model [" << model->name << "] has a non-zero off "
<< "diagonal value in its inertia matrix\n";
return this->GenerateInvalidId();
}
}

if (structure.parentOf.size())
{
const auto &parentInfo = structure.parentOf.at(link);
Expand Down Expand Up @@ -617,25 +611,12 @@ Identity SDFFeatures::ConstructSdfModel(

{
const auto *link = structure.rootLink;
const auto &M = link->Inertial().MassMatrix();
const btScalar mass = static_cast<btScalar>(M.Mass());
const auto inertia = convertVec(M.DiagonalMoments());

for (const double I : {M.Ixy(), M.Ixz(), M.Iyz()})
{
if (std::abs(I) > 1e-3)
{
gzerr << "Links are required to have a diagonal inertia matrix in "
<< "gz-physics-bullet-featherstone, but Link [" << link->Name()
<< "] in Model [" << model->name << "] has a non-zero off "
<< "diagonal value in its inertia matrix\n";
}
else
{
model->body->setBaseMass(mass);
model->body->setBaseInertia(inertia);
}
}
btScalar mass;
btVector3 inertia;
math::Pose3d linkToPrincipalAxesPose;
extractInertial(link->Inertial(), mass, inertia, linkToPrincipalAxesPose);
model->body->setBaseMass(mass);
model->body->setBaseInertia(inertia);
}

world->world->addMultiBody(model->body.get());
Expand Down

0 comments on commit b541796

Please sign in to comment.