Confusion on Collision between Sphere and Box
Hello, I'm currently running this model and would like some help understanding its behavior. The sphere geom seems to go through the box geom rather than colliding with it and rolling. The behavior is not what I would expect. Would someone mind explaining the reasoning why the sphere appears to go through the box geom? Also, does anyone have any suggestions on how I can achieve the expected behavior?
Here is a model which explains my question:
<mujoco>
<asset>
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
<material name="grid" texture="grid" texrepeat="8 8" texuniform="true" reflectance=".2"/>
</asset>
<worldbody>
<light name="top" pos="0 0 2" diffuse="1 1 1"/>
<geom name="floor" material="grid" pos="0 0 0" type="plane" size="1 1 .01"/>
<body name="ramp" euler="0 0 0" pos=".3 0 .05">
<geom type="box" size=".1 .1 .01" euler="0 30 0"/>
</body>
<body>
<freejoint />
<geom type="sphere" size="0.01 0.01 0.01" pos=".3 0 0.3" rgba="0 0 1 .5"/>
</body>
</worldbody>
</mujoco>
https://github.com/user-attachments/assets/f78549b9-cbb3-454f-81ed-b56f745f07c9
What MuJoCo version?
@yuvaltassa Noticing this on 3.2.0:
- Lowering the timestep does not fix the problem.
- Making things stiffer (
<geom solref=".004 1"/>) with a slightly bigger sphere eliminates the problem. - Changing the sphere to a box is stable.
- Changing the ramp to a plane does not fix the issue.
- When I slow down the simulation, I notice the following:
https://github.com/user-attachments/assets/9e5ee257-af27-47a7-85c8-dd9413ef56b7
So most likely a collider issue.
Looks like this has always been an issue (loaded as far back as 2.3.7).
What MuJoCo version?
I am currently working off of version 3.2.0
It also seems to especially be a problem with smaller objects (i.e. within the range 0.001). Here is another example with a box-box collision:
<mujoco>
<size memory="100M"/>
<asset>
<texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
<material name="grid" texture="grid" texrepeat="8 8" texuniform="true" reflectance=".2"/>
</asset>
<default>
<default class="collision">
<geom solimp="0.98 0.99 0.0001" solref=".004 1"/>
</default>
</default>
<worldbody>
<light name="top" pos="0 0 2" diffuse="1 1 1"/>
<geom class="collision" name="floor" material="grid" pos="0 0 0" type="plane" size="1 1 .01"/>
<body pos="0 0 .005" euler="0 30 0">
<geom type="box" size="0.01 0.01 0.001" />
</body>
<body>
<freejoint />
<geom class="collision" type="box" size="0.001 0.001 0.001" pos="-0.01 0 0.022" euler="0 30 0" rgba="0 0 1 .5"/>
</body>
</worldbody>
</mujoco>
https://github.com/user-attachments/assets/a10a11db-ce14-4f9c-bebd-9f03f7c176f7
We are working on a full overhaul of the collision pipeline (ETA, 1-2 months), we will add these models as test cases.
@abhihjoshi in your original model, you need to add the attribute align="true" to freejoint.