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

Rapid divergence after simple capsule-capsule contact #2472

Open
2 tasks done
jjyyxx opened this issue Mar 5, 2025 · 5 comments
Open
2 tasks done

Rapid divergence after simple capsule-capsule contact #2472

jjyyxx opened this issue Mar 5, 2025 · 5 comments
Labels
bug Something isn't working

Comments

@jjyyxx
Copy link
Contributor

jjyyxx commented Mar 5, 2025

Intro

Hi!

I am a graduate student at HKU, I use MuJoCo for my research on robotic manipulation.

My setup

MuJoCo 3.3.0, Python and C, Linux

What's happening? What did you expect?

In the simple scenario attached below, the system initially evolves with low velocity and force before contact occurs. However, once contact happens, the simulation diverges rapidly. The immediate cause appears to be large contact force, but I am struggling to understand how such forces are generated, especially given the conventional yet specific setting combination used in the model.

I experimented with different options to mitigate the divergence, and found that some settings help (but inapplicable or impractical) while others do not:

  • Helpful: Very small timestep (1e-5), pyramid friction cone, frictionless contact, RK4 integrator
  • Unhelpful: Joint damping (unless set to a very large value), armature, friction loss, range, all other integrators

Steps for reproduction

Load the model below. Set actuator control to 1. Wait until contact happens.

Minimal model for reproduction

<mujoco>
  <compiler angle="radian"/>

  <option timestep="0.001" integrator="implicitfast" cone="elliptic" gravity="0 0 0"/>

  <worldbody>
    <body name="1" pos="0.05 0.3 0">
      <joint name="1" axis="0 1 0" />
      <geom type="capsule" size="0.1 0.5"/>
    </body>
    <body name="2">
      <joint name="2" axis="1 0 0" />
      <geom type="capsule" size="0.1 0.5"/>
    </body>
  </worldbody>

  <actuator>
    <motor name="2" joint="2" ctrllimited="true" ctrlrange="0 1" />
  </actuator>
</mujoco>

Code required for reproduction

No response

Confirmations

@jjyyxx jjyyxx added the bug Something isn't working label Mar 5, 2025
@yuvaltassa
Copy link
Collaborator

yuvaltassa commented Mar 5, 2025

I can't reproduce this. Also you mention capsules but these are boxes?
Perhaps you posted the wrong model?
I even increased the timestep to 20ms and nothing funny happens...

@yuvaltassa yuvaltassa closed this as not planned Won't fix, can't repro, duplicate, stale Mar 5, 2025
@jjyyxx
Copy link
Contributor Author

jjyyxx commented Mar 6, 2025

@yuvaltassa Apologies for attaching the wrong file and wasting your time—I’ve uploaded the correct one now. Kindly reopen if the issue is valid.

@yuvaltassa yuvaltassa reopened this Mar 6, 2025
@yuvaltassa
Copy link
Collaborator

Wow! I've never seen anything like this 😯

Will investigate, thanks for the MRE

@yuvaltassa
Copy link
Collaborator

Initial observation: the issue completely goes away if I switch to Euler or RK4.
There is something wrong with implicit / implicitfast.

@yuvaltassa
Copy link
Collaborator

Further observation: this bug dates back to the introduction of implicit/implicitfast in 3.2.3, so (unfortunately!) not a newly introduced bug that I can just roll back. Still investigating...

Sign up for free to join this conversation on GitHub. Already have an account? Sign in to comment
Labels
bug Something isn't working
Projects
None yet
Development

No branches or pull requests

2 participants