Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

Enforce fixed constraints recursively when setting pose on freegroups #646

Merged
merged 1 commit into from
Jun 2, 2024
Merged
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
55 changes: 36 additions & 19 deletions bullet-featherstone/src/FreeGroupFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -38,7 +38,9 @@ btTransform getWorldTransformForLink(btMultiBody *_body, int _linkIndex)
}

/////////////////////////////////////////////////
void enforceFixedConstraint(btMultiBodyFixedConstraint *_fixedConstraint)
void enforceFixedConstraint(
btMultiBodyFixedConstraint *_fixedConstraint,
const std::unordered_map<std::size_t, Base::JointInfoPtr> &_allJoints)
{
// Update fixed constraint's child link pose to maintain a fixed transform
// from the parent link.
Expand All @@ -62,6 +64,18 @@ void enforceFixedConstraint(btMultiBodyFixedConstraint *_fixedConstraint)
btTransform newChildBaseTf =
expectedChildLinkTf * childBaseToLink.inverse();
child->setBaseWorldTransform(newChildBaseTf);
for (const auto &joint : _allJoints)
{
if (joint.second->fixedConstraint)
{
// Recursively enforce constraints where the child here is a parent to
// other constraints.
if (joint.second->fixedConstraint->getMultiBodyA() == child)
{
enforceFixedConstraint(joint.second->fixedConstraint.get(), _allJoints);
}
}
}
}

/////////////////////////////////////////////////
Expand All @@ -74,6 +88,19 @@ Identity FreeGroupFeatures::FindFreeGroupForModel(
if (model->body->hasFixedBase())
return this->GenerateInvalidId();

// Also reject if the model is a child of a fixed constraint (detachable joint)
for (const auto & joint : this->joints)
{
if (joint.second->fixedConstraint)
{
if (joint.second->fixedConstraint->getMultiBodyB() == model->body.get())
{
return this->GenerateInvalidId();
}
}
}


return _modelID;
}

Expand Down Expand Up @@ -136,36 +163,26 @@ void FreeGroupFeatures::SetFreeGroupWorldPose(
const auto *model = this->ReferenceInterface<ModelInfo>(_groupID);
if (model)
{
btMultiBodyFixedConstraint *fixedConstraintToEnforce = nullptr;
model->body->setBaseWorldTransform(
convertTf(_pose * model->baseInertiaToLinkFrame.inverse()));

model->body->wakeUp();

for (auto & joint : this->joints)
{
if (joint.second->fixedConstraint)
{
// If the body is the child of a fixed constraint, do not move update
// its world pose.
btMultiBody *child = joint.second->fixedConstraint->getMultiBodyB();
if (child == model->body.get())
{
return;
}
// Only the parent body of a fixed joint can be moved but we need to
// enforce the fixed constraint by updating the child pose so it
// remains at a fixed transform from parent
// remains at a fixed transform from parent. We do this recursively to
// account for other constraints attached to the child.
btMultiBody *parent = joint.second->fixedConstraint->getMultiBodyA();
if (parent == model->body.get())
{
fixedConstraintToEnforce = joint.second->fixedConstraint.get();
enforceFixedConstraint(joint.second->fixedConstraint.get(), this->joints);
}
}
}

model->body->setBaseWorldTransform(
convertTf(_pose * model->baseInertiaToLinkFrame.inverse()));

if (fixedConstraintToEnforce)
enforceFixedConstraint(fixedConstraintToEnforce);

model->body->wakeUp();
}
}

Expand Down
Loading