Skip to content

Rapid divergence after simple capsule-capsule contact #2472

Open
@jjyyxx

Description

@jjyyxx

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

Metadata

Metadata

Assignees

No one assigned

    Labels

    bugSomething isn't working

    Type

    No type

    Projects

    No projects

    Milestone

    No milestone

    Relationships

    None yet

    Development

    No branches or pull requests

    Issue actions