-
Notifications
You must be signed in to change notification settings - Fork 41
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
bullet-featherstone: Update fixed constraint behavior #632
Changes from 19 commits
894a348
4e05844
4eae0c4
8e32ed8
12cef38
2e49b03
e1c1b84
33af03e
ab22dfc
936d164
19adb26
6c2db26
c5e33e9
b69191a
c904cb5
8418966
755aeb5
26a72cd
0617ae7
d9b0bdb
83e31a0
12688f9
97bd03b
1de0ede
c921141
fce556e
a112092
File filter
Filter by extension
Conversations
Jump to
Diff view
Diff view
There are no files selected for viewing
Original file line number | Diff line number | Diff line change |
---|---|---|
|
@@ -341,6 +341,31 @@ Identity JointFeatures::AttachFixedJoint( | |
if (world != nullptr && world->world) | ||
{ | ||
world->world->addMultiBodyConstraint(jointInfo->fixedConstraint.get()); | ||
|
||
// Make links static if parent or child link is static | ||
// This is done by changing collision filter groups / masks | ||
// Otherwise bullet will push bodies apart | ||
btMultiBodyLinkCollider *parentCollider = parentLinkInfo->collider.get(); | ||
btMultiBodyLinkCollider *childCollider = linkInfo->collider.get(); | ||
if (parentCollider && childCollider) | ||
{ | ||
parentCollider->setIgnoreCollisionCheck(childCollider, true); | ||
childCollider->setIgnoreCollisionCheck(parentCollider, true); | ||
azeey marked this conversation as resolved.
Show resolved
Hide resolved
|
||
if (parentLinkInfo->isStaticOrFixed && !linkInfo->isStaticOrFixed) | ||
{ | ||
btBroadphaseProxy *childProxy = childCollider->getBroadphaseHandle(); | ||
There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. It seems like this won't update children recursively. Consider 3 models A (static), B (dynamic), C (dynamic). If we first attach B->C, where B is the parent and then A->B, the result would be A (static), B (static), C (dynamic) whereas we expect all models to be static. There was a problem hiding this comment. Choose a reason for hiding this commentThe reason will be displayed to describe this comment to others. Learn more. updated to recursively set collision flags and added a test. d9b0bdb |
||
if (childProxy) | ||
{ | ||
childProxy->m_collisionFilterGroup = btBroadphaseProxy::StaticFilter; | ||
childProxy->m_collisionFilterMask = | ||
btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter; | ||
} | ||
#if BT_BULLET_VERSION >= 307 | ||
childCollider->setDynamicType(btCollisionObject::CF_STATIC_OBJECT); | ||
#endif | ||
} | ||
} | ||
|
||
return this->GenerateIdentity(jointID, this->joints.at(jointID)); | ||
} | ||
|
||
|
@@ -353,13 +378,49 @@ void JointFeatures::DetachJoint(const Identity &_jointId) | |
auto jointInfo = this->ReferenceInterface<JointInfo>(_jointId); | ||
if (jointInfo->fixedConstraint) | ||
{ | ||
// Make links dynamic again they were originally not static | ||
// This is done by revert any collision flags / masks changes | ||
// made in AttachJoint | ||
auto *linkInfo = this->ReferenceInterface<LinkInfo>(jointInfo->childLinkID); | ||
if (jointInfo->parentLinkID.has_value()) | ||
{ | ||
auto parentLinkInfo = this->links.at(jointInfo->parentLinkID.value()); | ||
|
||
btMultiBodyLinkCollider *parentCollider = parentLinkInfo->collider.get(); | ||
btMultiBodyLinkCollider *childCollider = linkInfo->collider.get(); | ||
if (parentCollider && childCollider) | ||
{ | ||
parentCollider->setIgnoreCollisionCheck(childCollider, false); | ||
childCollider->setIgnoreCollisionCheck(parentCollider, false); | ||
btBroadphaseProxy *childProxy = childCollider->getBroadphaseHandle(); | ||
if (childProxy) | ||
{ | ||
// If broadphase and collision object flags do not agree, the | ||
// link was originally non-static but made static by AttachJoint | ||
if (!linkInfo->isStaticOrFixed && | ||
((childProxy->m_collisionFilterGroup & | ||
btBroadphaseProxy::StaticFilter) > 0)) | ||
{ | ||
childProxy->m_collisionFilterGroup = | ||
btBroadphaseProxy::DefaultFilter; | ||
childProxy->m_collisionFilterMask = btBroadphaseProxy::AllFilter; | ||
|
||
#if BT_BULLET_VERSION >= 307 | ||
childCollider->setDynamicType(btCollisionObject::CF_DYNAMIC_OBJECT); | ||
#endif | ||
} | ||
} | ||
} | ||
} | ||
|
||
auto modelInfo = this->ReferenceInterface<ModelInfo>(jointInfo->model); | ||
if (modelInfo) | ||
{ | ||
auto *world = this->ReferenceInterface<WorldInfo>(modelInfo->world); | ||
world->world->removeMultiBodyConstraint(jointInfo->fixedConstraint.get()); | ||
jointInfo->fixedConstraint.reset(); | ||
jointInfo->fixedConstraint = nullptr; | ||
modelInfo->body->wakeUp(); | ||
} | ||
} | ||
} | ||
|
@@ -380,6 +441,18 @@ void JointFeatures::SetJointTransformFromParent( | |
} | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
void JointFeatures::SetFixedJointWeldChildToParent( | ||
const Identity &_id, bool _weldChildToParent) | ||
{ | ||
auto jointInfo = this->ReferenceInterface<JointInfo>(_id); | ||
|
||
if (jointInfo->fixedConstraint) | ||
{ | ||
jointInfo->fixedConstraintWeldChildToParent = _weldChildToParent; | ||
} | ||
} | ||
|
||
///////////////////////////////////////////////// | ||
Wrench3d JointFeatures::GetJointTransmittedWrenchInJointFrame( | ||
const Identity &_id) const | ||
|
There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
I tried adding the following here
and disabling
fixedConstraintWeldChildToParent
in Base.hh. By default the max impulse is 100. Setting a high value like this made it so that the constraint is satisfied with minimal oscillations. As we discussed, the transform tool does not apply forces on the bodies, so the resulting behavior cannot be relied upon to determine if the physics is correct. Instead, I set up a simulation where two boxes are attached by a detachable joint and the parent box is attached to a fixed base with a prismatic joint.Test SDFormat file
Test command
Here are the results:
DART
dart.webm
Bullet-featherstone gz-physics7 branch
bullet-default.webm
Bullet-featherstone current PR
current-PR.webm
Bullet-featherstone proposed change: setting a high max impulse
max_impulse.webm
I moved your changes in SimulationFeatures.cc directly into
FreeGroupFeatures::SetFreeGroupWorldPose
and that solved the transform tool issue.There was a problem hiding this comment.
Choose a reason for hiding this comment
The reason will be displayed to describe this comment to others. Learn more.
ok thanks for testing. I revised this PR based on the suggestions. Changes are in d9b0bdb:
jointInfo->fixedConstraint->setMaxAppliedImpulse(btScalar(1e9));
when creating attaching jointSetFreeGroupWorldPose
and updated testSetFixedJointWeldChildToParent
feature