Skip to content

Unstable Simulation for soft material, if the initial euler was set #2562

Open
@dvorak0

Description

@dvorak0

Intro

Hi!

I am a individual researcher, I use MuJoCo for my research on robotic manipulation.

I started with a very simple example of having a square piece of soft material.

I tried to simulate the random initial state of the soft piece so I use euler property.

While when the euler was set "0 0 0" it's working well, it's totally broken if it was set to "10 0 0".

My setup

MuJoCo==3.3.0, Python API, Running inside Docker: FROM nvidia/cuda:12.2.2-devel-ubuntu22.04

What's happening? What did you expect?

python -m mujoco.viewer --mjcf=./models/cloth.xml

The simulation diverges quickly with logs:
WARNING: Nan, Inf or huge value in QACC at DOF 0. The simulation is unstable. Time = 0.0870.

Steps for reproduction

  1. Load the model below.
  2. Run the code below.

Image

Minimal model for reproduction

<mujoco model="simple_square_soft_stable">
    <compiler angle="degree"/>
    <option timestep="0.001" gravity="0 0 -9.81">
        <flag energy="enable" contact="enable" gravity="enable"/>
    </option>
    <size njmax="5000" nconmax="1000"/>
    
    <asset>
        <texture name="grid" type="2d" builtin="checker"
                 rgb1=".2 .3 .4" rgb2=".1 0.15 0.2"
                 width="512" height="512" mark="cross" markrgb=".8 .8 .8"/>
        <material name="groundmat" texture="grid" texrepeat="2 2"/>
        <material name="softmat" rgba="0.8 0.2 0.2 1.0" specular="0.3" shininess="0.5"/>
    </asset>
    
    <worldbody>
        <light diffuse=".8 .8 .8" pos="0 0 3" dir="0 0 -1"/>
        <geom name="ground" type="plane" size="2 2 0.1" pos="0 0 0" material="groundmat"/>

        <!-- More stable soft body configuration -->
        <flexcomp name="square" type="grid" count="10 10 1" spacing="0.04 0.04 0.04" pos="0 0 1" euler="10 0 0"
                  radius="0.005" mass="1.0" material="softmat">
            <contact solref="0.02 0.5" solimp="0.9 0.95 0.001" friction="0.7 0.1 0.1" condim="3" internal="true"/>
            <edge damping="0.5"/>
            <elasticity poisson="0.3" young="1000"/>
        </flexcomp>

        <!-- Ball for interaction -->
		<!--<body name="ball" pos="0.0 0 0.6"> -->
			<!--    <geom type="sphere" size="0.05" density="500" rgba="0.2 0.6 0.8 1"/> -->
			<!--</body> -->

    </worldbody>
</mujoco>


Confirmations

Metadata

Metadata

Assignees

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