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

Disable collisions between attached bodies #640

Merged

Conversation

azeey
Copy link
Contributor

@azeey azeey commented May 16, 2024

🦟 Bug fix

Fixes #

Summary

Even with #632 , it looks like objects that are attached to each other continue to generate contacts. Even though we've explicitly marked the two objects not to collide, looking at the bullet code (https://github.com/bulletphysics/bullet3/blob/e9c461b0ace140d5c73972760781d94b7b5eee53/src/BulletDynamics/Featherstone/btMultiBodyLinkCollider.h#L79-L80), that is ignored because checkCollideWithOverride will always return true if the two objects are not in the same btMultiBody.

@iche033 I haven't checked this thoroughly, but the solution I came up with is to call the base class's checkCollideWithOverride as well as btMultiBodyLinkCollider::checkCollideWithOverride and return the result of anding the two. This does behave much better. I tried with the SDF below by uncommenting only one of the <plugin> tags. Without this PR, the objects fly up or down together even though gravity is 0. Visualizing contacts in gz-sim also shows that they are in contact. With the PR, the boxes stay in place and generate no contacts.

SDF File
<?xml version="1.0"?>
<sdf version="1.11">
  <world name="default">

    <gravity>0 0 0</gravity>

    <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">
      <pose>0 2 3.0 0 0.0 0.0</pose>
      <link name="body">
        <inertial auto="true"/>
        <collision name="box_collision">
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
        </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>0.3 2 3.0 0 0.0 0</pose>
      <link name="body2">
        <inertial auto="true"/>
        <collision name="box_collision">
          <geometry>
            <box>
              <size>1 1 0.5</size>
            </box>
          </geometry>
        </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>
      <!-- <plugin filename="gz-sim-detachable-joint-system" -->
      <!--         name="gz::sim::systems::DetachableJoint"> -->
      <!--  <parent_link>body2</parent_link> -->
      <!--  <child_model>M1</child_model> -->
      <!--  <child_link>body</child_link> -->
      <!-- </plugin> -->
    </model>
  </world>
</sdf>

Checklist

  • Signed all commits for DCO
  • Added tests
  • Updated documentation (as needed)
  • Updated migration guide (as needed)
  • Consider updating Python bindings (if the library has them)
  • codecheck passed (See contributing)
  • All tests passed (See test coverage)
  • While waiting for a review on your PR, please help review another open pull request to support the maintainers

Note to maintainers: Remember to use Squash-Merge and edit the commit message to match the pull request summary while retaining Signed-off-by messages.

🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸🔸

@azeey azeey requested a review from iche033 May 16, 2024 04:44
Copy link
Contributor

@iche033 iche033 left a comment

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

oh nice, thanks for looking into this! #632 made it work only for static bodies. I mentioned in that PR that setIgnoreCollisionCheck does not seem have an effect. This should do it!

@iche033 iche033 merged commit 755aeb5 into gazebosim:bullet_fixed_joint May 17, 2024
4 of 5 checks passed
Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
None yet
Projects
Archived in project
Development

Successfully merging this pull request may close these issues.

2 participants