google-deepmind / mujoco

Multi-Joint dynamics with Contact. A general purpose physics simulator.
https://mujoco.org
Apache License 2.0
8.25k stars 823 forks source link

Bug in box-sphere collider #2206

Open yuvaltassa opened 2 weeks ago

yuvaltassa commented 2 weeks ago

Intro

MuJoCo dev. Original bug report in #2199

My setup

n/a

What's happening? What did you expect?

The box-sphere collider returns correct contact positions, but the depth (contact.dist) is wrong after full penetration of the sphere into the box.

Steps for reproduction

Run the code below, get this plot

image

Minimal model for reproduction

See below.

Code required for reproduction

xml = """
<mujoco>
  <worldbody>
    <geom name="plane" pos="0 0 -.005" type="plane" size="0.5 0.5 0.01"/>-->
    <geom name="box"   type="box" pos = "0 0 -0.255" size="0.5 0.5 .25"  />
    <body>
      <freejoint/>
      <geom name="sphere" type="sphere" mass="1" size="0.005"/>
    </body>
  </worldbody>
</mujoco>
"""
model = mujoco.MjModel.from_xml_string(xml)
data = mujoco.MjData(model)

depth = np.linspace(-.01, -1e-6, 200)
contact = [[], []]
for z in depth:
  data.qpos[2] = z
  mujoco.mj_forward(model, data)
  for i in range(2):
    c = data.contact[i]
    condata = np.array((c.pos[2], c.dist))
    contact[i].append(condata)

plt.plot(depth, contact[0], label=['plane contact pos', 'plane contact depth']);
plt.plot(depth, contact[1], '--', label=['box contact pos', 'box contact depth']);
plt.xlabel('Penetration (m)');
plt.legend()

Confirmations