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

bullet-featherstone: Update fixed constraint behavior #632

Merged
merged 27 commits into from
Jun 3, 2024
Merged
Show file tree
Hide file tree
Changes from 19 commits
Commits
Show all changes
27 commits
Select commit Hold shift + click to select a range
894a348
Add FixedJointWeldChildToParent feature and update bullet-featherston…
iche033 May 6, 2024
4e05844
clean up
iche033 May 6, 2024
4eae0c4
lint
iche033 May 6, 2024
8e32ed8
remove unused code
iche033 May 7, 2024
12cef38
disable check on mac
iche033 May 7, 2024
2e49b03
add includes
iche033 May 7, 2024
e1c1b84
minor collision checking optimization
iche033 May 10, 2024
33af03e
fixes
iche033 May 10, 2024
ab22dfc
further optimize collision flags
iche033 May 10, 2024
936d164
style
iche033 May 10, 2024
19adb26
style
iche033 May 11, 2024
6c2db26
fixes for bullet version < 3.07
iche033 May 11, 2024
c5e33e9
check bullet version
iche033 May 11, 2024
b69191a
more ifdef
iche033 May 11, 2024
c904cb5
fix
iche033 May 13, 2024
8418966
Merge branch 'gz-physics7' into bullet_fixed_joint
iche033 May 13, 2024
755aeb5
Disable collisions between attached bodies (#640)
azeey May 17, 2024
26a72cd
add comments
iche033 May 28, 2024
0617ae7
Merge branch 'gz-physics7' into bullet_fixed_joint
iche033 May 28, 2024
d9b0bdb
Remove SetFixedJointWeldChildToParentFeature. Enforce fixed constrain…
iche033 Jun 1, 2024
83e31a0
increase tol for bullet version < 3.07
iche033 Jun 1, 2024
12688f9
revert one change
iche033 Jun 1, 2024
97bd03b
update comment
iche033 Jun 1, 2024
1de0ede
update comment
iche033 Jun 1, 2024
c921141
add note about disable collisions between all links and parent and child
iche033 Jun 1, 2024
fce556e
Enforce fixed constraints recursively when setting pose on freegroups…
azeey Jun 2, 2024
a112092
lint
iche033 Jun 2, 2024
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
26 changes: 25 additions & 1 deletion bullet-featherstone/src/Base.hh
Original file line number Diff line number Diff line change
Expand Up @@ -112,6 +112,24 @@ struct ModelInfo
}
};

/// \brief Custom GzMultiBodyLinkCollider class
class GzMultiBodyLinkCollider: public btMultiBodyLinkCollider {
using btMultiBodyLinkCollider::btMultiBodyLinkCollider;

/// \brief Overrides base function to enable support for ignoring
/// collision with objects from other bodies if
/// btCollisionObject::setIgnoreCollisionCheck is called.
/// Note: originally btMultiBodyLinkCollider::checkCollideWithOverride
/// just returns true if the input collision object is from a
/// different body and disregards any setIgnoreCollisionCheck calls.
public: bool checkCollideWithOverride(const btCollisionObject *_co) const
override
{
return btMultiBodyLinkCollider::checkCollideWithOverride(_co) &&
btCollisionObject::checkCollideWithOverride(_co);
}
};

/// Link information is embedded inside the model, so all we need to store here
/// is a reference to the model and the index of this link inside of it.
struct LinkInfo
Expand All @@ -120,10 +138,12 @@ struct LinkInfo
std::optional<int> indexInModel;
Identity model;
Eigen::Isometry3d inertiaToLinkFrame;
std::unique_ptr<btMultiBodyLinkCollider> collider = nullptr;
std::unique_ptr<GzMultiBodyLinkCollider> collider = nullptr;
std::unique_ptr<btCompoundShape> shape = nullptr;
std::vector<std::size_t> collisionEntityIds = {};
std::unordered_map<std::string, std::size_t> collisionNameToEntityId = {};
// Link is either static, fixed to world, or has zero dofs
bool isStaticOrFixed = false;
};

struct CollisionInfo
Expand Down Expand Up @@ -171,6 +191,10 @@ struct JointInfo
std::size_t indexInGzModel = 0;
btScalar effort = 0;

// True if the fixed constraint's child link is welded to parent link as if
// they are part of the same body.
bool fixedConstraintWeldChildToParent = true;

std::shared_ptr<btMultiBodyJointMotor> motor = nullptr;
std::shared_ptr<btMultiBodyJointLimitConstraint> jointLimits = nullptr;
std::shared_ptr<btMultiBodyFixedConstraint> fixedConstraint = nullptr;
Expand Down
73 changes: 73 additions & 0 deletions bullet-featherstone/src/JointFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -341,6 +341,31 @@ Identity JointFeatures::AttachFixedJoint(
if (world != nullptr && world->world)
{
world->world->addMultiBodyConstraint(jointInfo->fixedConstraint.get());

Copy link
Contributor

@azeey azeey May 31, 2024

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

    jointInfo->fixedConstraint->setMaxAppliedImpulse(btScalar(1e9));

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
<?xml version="1.0"?>
<sdf version="1.11">
  <world name="default">
  <light type="directional" name="sun">
      <cast_shadows>true</cast_shadows>
      <pose>0 0 10 0 0 0</pose>
      <diffuse>1 1 1 1</diffuse>
      <specular>0.5 0.5 0.5 1</specular>
      <attenuation>
        <range>1000</range>
        <constant>0.9</constant>
        <linear>0.01</linear>
        <quadratic>0.001</quadratic>
      </attenuation>
      <direction>-0.5 0.1 -0.9</direction>
    </light>

    <model name="ground_plane">
      <static>true</static>
      <link name="link">
        <collision name="collision">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
            </plane>
          </geometry>
        </collision>
        <visual name="visual">
          <geometry>
            <plane>
              <normal>0 0 1</normal>
              <size>100 100</size>
            </plane>
          </geometry>
          <material>
            <ambient>0.8 0.8 0.8 1</ambient>
            <diffuse>0.8 0.8 0.8 1</diffuse>
            <specular>0.8 0.8 0.8 1</specular>
          </material>
        </visual>
      </link>
    </model>
    <model name="M1">
      <joint name="j_base" type="fixed">
        <parent>world</parent>
        <child>base</child>
      </joint>
      <link name="base">
        <pose>0 0 0.05  0 0 0</pose>
        <inertial auto="true"/>
        <collision name="box_collision">
          <density>1000</density>
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
        </collision>
        <visual name="box_visual">
          <geometry>
            <box>
              <size>0.1 0.1 0.1</size>
            </box>
          </geometry>
          <material>
            <ambient>1 0 0 0.1</ambient>
            <diffuse>1 0 1 0.1</diffuse>
            <specular>1 0 0 1</specular>
          </material>
        </visual>
      </link>
      <joint name="j1" type="prismatic">
        <parent>base</parent>
        <child>body</child>
        <axis>
          <xyz>0 1 0</xyz>
        </axis>
      </joint>
      <plugin
        filename="gz-sim-joint-position-controller-system"
        name="gz::sim::systems::JointPositionController">
        <joint_name>j1</joint_name>
        <p_gain>20000</p_gain>
        <d_gain>10000</d_gain>
        <cmd_max>10000</cmd_max>
        <cmd_min>-10000</cmd_min>
        <use_velocity_commands>true</use_velocity_commands>
        <topic>cmd_pos</topic>
      </plugin>
      <link name="body">
        <pose>1 0 0.25 0 0.0 0.0</pose>
        <inertial auto="true"/>
        <collision name="box_collision">
          <density>100</density>
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>0.1</mu>
                <mu2>0.1</mu2>
              </ode>
              <bullet>
                <friction>0.1</friction>
                <friction2>0.1</friction2>
              </bullet>
            </friction>
          </surface>
        </collision>

        <visual name="box_visual">
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
          <material>
            <ambient>1 0 0 1</ambient>
            <diffuse>1 0 0 1</diffuse>
            <specular>1 0 0 1</specular>
          </material>
        </visual>
      </link>
      <plugin filename="gz-sim-detachable-joint-system"
              name="gz::sim::systems::DetachableJoint">
       <parent_link>body</parent_link>
       <child_model>M2</child_model>
       <child_link>body2</child_link>
      </plugin>
    </model>

    <model name="M2">
      <pose>3.3 0 0.25 0 0.0 0</pose>
      <link name="body2">
        <inertial auto="true"/>
        <collision name="box_collision">
          <density>100</density>
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
          <surface>
            <friction>
              <ode>
                <mu>1</mu>
                <mu2>1</mu2>
              </ode>
              <bullet>
                <friction>1</friction>
                <friction2>1</friction2>
              </bullet>
            </friction>
          </surface>
        </collision>

        <visual name="box_visual">
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
          <material>
            <ambient>0 1 0 1</ambient>
            <diffuse>0 1 0 1</diffuse>
            <specular>1 0 0 1</specular>
          </material>
        </visual>
      </link>
    </model>
  </world>
</sdf>

Test command

gz topic -t /cmd_pos -m gz.msgs.Double -p "data: 4.0" 

Here are the results:

I moved your changes in SimulationFeatures.cc directly into FreeGroupFeatures::SetFreeGroupWorldPose and that solved the transform tool issue.

Copy link
Contributor Author

@iche033 iche033 Jun 1, 2024

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:

  • added jointInfo->fixedConstraint->setMaxAppliedImpulse(btScalar(1e9)); when creating attaching joint
  • moved code for enforcing child body pose to SetFreeGroupWorldPose and updated test
  • removed SetFixedJointWeldChildToParent feature

// 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();
Copy link
Contributor

Choose a reason for hiding this comment

The 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.

Copy link
Contributor Author

@iche033 iche033 Jun 1, 2024

Choose a reason for hiding this comment

The 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));
}

Expand All @@ -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();
}
}
}
Expand All @@ -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
Expand Down
6 changes: 5 additions & 1 deletion bullet-featherstone/src/JointFeatures.hh
Original file line number Diff line number Diff line change
Expand Up @@ -51,7 +51,7 @@ struct JointFeatureList : FeatureList<

SetMimicConstraintFeature,

FixedJointCast
SetFixedJointWeldChildToParentFeature
> { };

class JointFeatures :
Expand Down Expand Up @@ -140,6 +140,10 @@ class JointFeatures :
public: void SetJointTransformFromParent(
const Identity &_id, const Pose3d &_pose) override;

// ----- SetFixedJointWeldChildToParentFeature -----
public: void SetFixedJointWeldChildToParent(
const Identity &_id, bool _weldChildToParent) override;

// ----- Transmitted wrench -----
public: Wrench3d GetJointTransmittedWrenchInJointFrame(
const Identity &_id) const override;
Expand Down
8 changes: 7 additions & 1 deletion bullet-featherstone/src/SDFFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -1263,7 +1263,7 @@ bool SDFFeatures::AddSdfCollision(

// NOTE: Bullet does not appear to support different surface properties
// for different shapes attached to the same link.
linkInfo->collider = std::make_unique<btMultiBodyLinkCollider>(
linkInfo->collider = std::make_unique<GzMultiBodyLinkCollider>(
model->body.get(), linkIndexInModel);

linkInfo->shape->addChildShape(btInertialToCollision, shape.get());
Expand Down Expand Up @@ -1330,6 +1330,12 @@ bool SDFFeatures::AddSdfCollision(
linkInfo->collider.get(),
btBroadphaseProxy::StaticFilter,
btBroadphaseProxy::AllFilter ^ btBroadphaseProxy::StaticFilter);
linkInfo->isStaticOrFixed = true;

// Set collider collision flags
#if BT_BULLET_VERSION >= 307
linkInfo->collider->setDynamicType(btCollisionObject::CF_STATIC_OBJECT);
#endif
}
else
{
Expand Down
51 changes: 51 additions & 0 deletions bullet-featherstone/src/SimulationFeatures.cc
Original file line number Diff line number Diff line change
Expand Up @@ -43,6 +43,57 @@ void SimulationFeatures::WorldForwardStep(
stepSize = dt.count();
}

// Update fixed constraint behavior if fixedJointWeldChildToParent is true.
// Do this before stepping, i.e. before physics engine tries to solve and
// enforce the constraint
for (auto & joint : this->joints)
{
if (joint.second->fixedConstraint &&
joint.second->fixedConstraintWeldChildToParent)
{
// Update fxied constraint's child link pose to maintain a fixed transform
iche033 marked this conversation as resolved.
Show resolved Hide resolved
// from the parent link.
btTransform parentToChildTf;
parentToChildTf.setOrigin(joint.second->fixedConstraint->getPivotInA());
parentToChildTf.setBasis(joint.second->fixedConstraint->getFrameInA());
btMultiBody *parent = joint.second->fixedConstraint->getMultiBodyA();
btMultiBody *child = joint.second->fixedConstraint->getMultiBodyB();

int parentLinkIndex = joint.second->fixedConstraint->getLinkA();
int childLinkIndex = joint.second->fixedConstraint->getLinkB();

btTransform parentLinkTf;
btTransform childLinkTf;
if (parentLinkIndex == -1)
{
parentLinkTf = parent->getBaseWorldTransform();
}
else
{
btMultiBodyLinkCollider *parentCollider =
parent->getLinkCollider(parentLinkIndex);
parentLinkTf = parentCollider->getWorldTransform();
}
if (childLinkIndex == -1)
iche033 marked this conversation as resolved.
Show resolved Hide resolved
{
childLinkTf = child->getBaseWorldTransform();
}
else
{
btMultiBodyLinkCollider *childCollider =
child->getLinkCollider(childLinkIndex);
childLinkTf = childCollider->getWorldTransform();
}
btTransform expectedChildLinkTf = parentLinkTf * parentToChildTf;
btTransform childBaseTf = child->getBaseWorldTransform();
btTransform childBaseToLink =
childBaseTf.inverse() * childLinkTf;
btTransform newChildBaseTf =
expectedChildLinkTf * childBaseToLink.inverse();
child->setBaseWorldTransform(newChildBaseTf);
}
}

worldInfo->world->stepSimulation(static_cast<btScalar>(this->stepSize), 1,
static_cast<btScalar>(this->stepSize));

Expand Down
32 changes: 32 additions & 0 deletions include/gz/physics/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -652,6 +652,38 @@ namespace gz
Scalar _reference) = 0;
};
};

/////////////////////////////////////////////////
class GZ_PHYSICS_VISIBLE SetFixedJointWeldChildToParentFeature
: public virtual Feature
{
/// \brief The Joint API for setting whether to weld a fixed joint's child
/// link to the parent link.
public: template <typename PolicyT, typename FeaturesT>
class Joint : public virtual Feature::Joint<PolicyT, FeaturesT>
{
/// \brief Set whether to weld the fixed joint's child link to the
/// parent link. If true, the child link is welded and it will move /
/// with the parent link as if they are part of the same body
/// kinematic chain. If false, the fixed joint constraint is enforced
/// by applying forces to both the parent and child links.
/// By default when a fixed joint constraint is created, this property
/// is set to true.
/// \param[in] _weldChildToParent True to weld the child link to the
/// parent link.
public: void SetWeldChildToParent(bool _weldChildToParent);
};

/// \private The implementation API for setting whether to weld the fixed
/// joint's child link to the parent link.
public: template <typename PolicyT>
class Implementation : public virtual Feature::Implementation<PolicyT>
{
// see Joint::SetWeldChildToParent above
public: virtual void SetFixedJointWeldChildToParent(
const Identity &_id, bool _weldChildToParent) = 0;
};
};
}
}

Expand Down
9 changes: 9 additions & 0 deletions include/gz/physics/detail/Joint.hh
Original file line number Diff line number Diff line change
Expand Up @@ -263,6 +263,15 @@ namespace gz
RelativeWrench(this->GetFrameID(), this->GetTransmittedWrench()),
_relativeTo, _inCoordinatesOf);
}

/////////////////////////////////////////////////
template <typename PolicyT, typename FeaturesT>
void SetFixedJointWeldChildToParentFeature::Joint<PolicyT, FeaturesT>::
SetWeldChildToParent(bool _weldChildToParent)
{
this->template Interface<SetFixedJointWeldChildToParentFeature>()
->SetFixedJointWeldChildToParent(this->identity, _weldChildToParent);
}
}
}

Expand Down
5 changes: 5 additions & 0 deletions test/common_test/CMakeLists.txt
Original file line number Diff line number Diff line change
Expand Up @@ -76,6 +76,11 @@ foreach(test ${tests})
"BT_BULLET_VERSION_LE_325"
)
endif()
if (bullet_version_check_VERSION VERSION_LESS_EQUAL 3.06)
target_compile_definitions(${test_executable} PRIVATE
"BT_BULLET_VERSION_LE_306"
)
endif()

if (DART_HAS_CONTACT_SURFACE_HEADER)
target_compile_definitions(${test_executable} PRIVATE DART_HAS_CONTACT_SURFACE)
Expand Down
2 changes: 2 additions & 0 deletions test/common_test/Worlds.hh
Original file line number Diff line number Diff line change
Expand Up @@ -36,6 +36,8 @@ const auto kFallingWorld = CommonTestWorld("falling.world");
const auto kFallingAddedMassWorld = CommonTestWorld("falling_added_mass.world");
const auto kGroundSdf = CommonTestWorld("ground.sdf");
const auto kJointAcrossModelsSdf = CommonTestWorld("joint_across_models.sdf");
const auto kJointAcrossModelsFixedSdf =
CommonTestWorld("joint_across_models_fixed.sdf");
const auto kJointConstraintSdf = CommonTestWorld("joint_constraint.sdf");
const auto kMimicFastSlowPendulumsWorld =
CommonTestWorld("mimic_fast_slow_pendulums_world.sdf");
Expand Down
Loading