Description
Intro
I'm a researcher at Boston Dynamics.
My setup
I'm using the latest release 3.2.7 for linux x86_64.
What's happening? What did you expect?
Here's a minimal model that illustrates the problem. First, a working version:
<mujoco model="minimal-repro">
<worldbody>
<body name="body_1">
<freejoint/>
<geom type="sphere" size="0.5" mass="1"/>
<body name="body_2" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
<body name="body_3" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
</body>
</body>
</body>
</worldbody>
<contact>
<exclude body1="body_1" body2="body_3"/>
</contact>
</mujoco>
This model consists of three spheres, each of which overlaps with the others. Collision between body_1 and body_2 is ignored because they are direct ancestors in the kinematic tree, likewise body_2 and body_3. I have manually excluded collision between body_1 and body_3 with a contact/exclude
group. This all works correctly: When I run ./bin/simulate minimal-repro.xml
, the three spheres fall together.
However, if I remove the freejoint
, like so:
<mujoco model="minimal-repro">
<worldbody>
<body name="body_1">
<geom type="sphere" size="0.5" mass="1"/>
<body name="body_2" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
<body name="body_3" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
</body>
</body>
</body>
</worldbody>
<contact>
<exclude body1="body_1" body2="body_3"/>
</contact>
</mujoco>
then body_3 immediately shoots away, presumably due to the collision with body_1.
I have also tried <compiler fusestatic="false"/>
(even though I expect that to be the default), and it had no effect.
Steps for reproduction
- Load the model below with the
./bin/simulate
from the latest Mujoco release (3.2.7) - Observe that the sphere flies away.
Minimal model for reproduction
<mujoco model="minimal-repro">
<worldbody>
<body name="body_1">
<geom type="sphere" size="0.5" mass="1"/>
<body name="body_2" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
<body name="body_3" pos="0.25 0 0">
<joint type="slide" axis="1 0 0"/>
<geom type="sphere" size="0.5" mass="0.5"/>
</body>
</body>
</body>
</worldbody>
<contact>
<exclude body1="body_1" body2="body_3"/>
</contact>
</mujoco>
Code required for reproduction
No response
Confirmations
- I searched the latest documentation thoroughly before posting.
- I searched previous Issues and Discussions, I am certain this has not been raised before.