mujoco icon indicating copy to clipboard operation
mujoco copied to clipboard

Negative distance between non colliding geometries

Open cganuza opened this issue 1 year ago • 2 comments

Hi,

I'm an engineer and I'm trying to use MuJoCo for collision detection.

At the beginning I experienced this behavior with our own geometries, but after looking more in depth I found the same output with two general MuJoCo geometries. The issue is that I found negative distances between bodies even though they are not in contact. when they are in a close distance you can see negative distance. Not only that the contact point it is not where I would expect it to be. As you can see in the screenshot bellow it seems it is facing the center of the disk instead of the surface.

I want to get the distance between the bodies. Am I missing some setting for this?

Here is a simplified model which explains my question:

I am using MuJoCo 3.2.0

XML
<mujoco>
  <option>
    <flag energy="disable" gravity="disable"/>
  </option>


  <worldbody>
    <light pos="0 0 1" mode="trackcom"/>
    <body name="0" pos="0 0 0">
      <joint name="up" type="slide" pos="0 0 0" axis="0 0 1" />
      <joint name="twist" type="hinge" pos="0 0 0" axis="0 0 1" />
      <geom type="capsule" size=".01" fromto="-.1 0 -0.05 -.1 0 0.05" rgba="1 1 0 1"/>
    </body>

    <body name="disk_muj" pos="0 0 0.1">
      <geom type="cylinder" size=".2" fromto="0 0 -0.005 0 0 0.005" rgba="1 1 0 1" margin="0.3" gap="0.3"/>
    </body>
    
  </worldbody>
</mujoco>

the python script (not including the xml model from above:

import mujoco
import mujoco.viewer

model = mujoco.MjModel.from_xml_string(model_xml)
data = mujoco.MjData(model)
mujoco.viewer.launch(model, data)

Here is a screenshot, illustrating my question, already with the initial conditions I have the issue: image

cganuza avatar Jul 25 '24 13:07 cganuza

Yes, this is a bug we are working on fixing.

See caveat here

yuvaltassa avatar Jul 25 '24 16:07 yuvaltassa

Thank you for the prompt response @yuvaltassa. Do you have a time line when this will be fixed?

For mesh geometries the only option now is to create SDF files? Does this change the way of interacting with mujoco? Do you have any example? And, is it easy to change a mesh file to SDF?

Thank you so much!

cganuza avatar Jul 26 '24 07:07 cganuza

Hello everyone,

I am trying to use MuJoCo to compute the minimum distance between two moving geometries, but I am facing the same issue (with MuJoCo version 3.2.4). Please is there any setup/ alternative that would improve this condition while the bug is being resolved?

Thanks in advance!

rf4lc avatar Nov 04 '24 10:11 rf4lc

Hi @rf4lc, can you try enabling nativeccd? Hopefully that works.

kbayes avatar Nov 04 '24 10:11 kbayes

Hello there! I'm quite interested in using the margin and gap pair. What's the status of the bug? Many thanks in advance!

jaruiz-12 avatar Dec 04 '24 14:12 jaruiz-12

Hello there! I'm quite interested in using the margin and gap pair. What's the status of the bug? Many thanks in advance!

As @kbayes said, this should be fixed by enabling nativeccd

yuvaltassa avatar Dec 06 '24 16:12 yuvaltassa

With nativeccd enabled, I believe this is fixed.

Screenshot from 2024-12-06 16-55-31

kbayes avatar Dec 06 '24 17:12 kbayes

Worked for me too. Many thanks for the rapid response!

jaruiz-12 avatar Dec 11 '24 07:12 jaruiz-12