mujoco icon indicating copy to clipboard operation
mujoco copied to clipboard

Abnormal slip

Open Hang-Hu1 opened this issue 10 months ago • 7 comments

Intro

Hi!

I am a student and I'm using Mujoco for rigid body simulation and reinforcement learning.

My setup

Both 3.3.0 and the Jupyter notebook in https://mujoco.readthedocs.io/en/stable/python.html.

What's happening? What did you expect?

I found that when I use a large-magnitude, high-frequency driving force to actuate a joint, noticeable and abnormal slip occurs. I have read the explanation about slip in the tutorial and understand that MuJoCo does not strictly prevent it from happening. However, I am not sure whether the situation I am facing matches the description in that section, because changing solref, solimp, and impratio does not seem to help.

I would like to know how I can ensure simulation accuracy under this kind of control force setup.

Steps for reproduction

Just need to run the following Python script.

Minimal model for reproduction

<mujoco model="Test">
  <option timestep="0.0001">
    <flag eulerdamp="disable" contact="enable" gravity="enable"/>
  </option>

  <asset>
    <texture type="skybox" builtin="gradient" rgb1=".3 .5 .7" rgb2="0 0 0" width="32" height="512"/>
    <texture name="body" type="cube" builtin="flat" mark="cross" width="128" height="128" rgb1="0.8 0.6 0.4" rgb2="0.8 0.6 0.4" markrgb="1 1 1" random="0.01"/>
    <material name="body" texture="body" texuniform="true" rgba="0.8 0.6 .4 1"/>
    <texture name="grid" type="2d" builtin="checker" width="512" height="512" rgb1=".1 .2 .3" rgb2=".2 .3 .4"/>
    <material name="grid" texture="grid" texrepeat="1 1" texuniform="true" reflectance=".2"/>
  </asset>

  <worldbody>
    <light name="light" pos="-.2 0 1"/>
    <geom name="ground" type="plane" pos="0 0 0" size="0 0 10" material="grid"
    zaxis="0 0 1" friction="1.0"/>
    <light pos="0 0 1"/>
    <light pos="1 0 1"/>
    <light pos="2 0 1"/>
    <light pos="3 0 1"/>
    <light pos="4 0 1"/>
    <light pos="5 0 1"/>
    <camera name="cam" pos="0.0 -1.0 1.0" xyaxes="1 0 0 0 1 1" fovy="120" />
    <body name="b1" pos="0 0 0.05">
        <joint name="j0" type="free"/>
        <geom name="g1" type="capsule" size="0.05" fromto="-0.05 0 0 0.05 0 0" friction="1.0"/>
        <body name="b2" pos="0.2 0 0">
            <joint name="j1" type="hinge" axis="0 0 1" pos="-0.1 0 0" range="-70 70"/>
            <geom name="g2" type="capsule" size="0.05" fromto="-0.05 0 0 0.05 0 0" friction="1.0"/>
        </body>
    </body>
  </worldbody>

  <contact>
    <pair geom1="g1" geom2="ground" friction="0.01 0.01"/>
    <pair geom1="g2" geom2="ground" friction="0.01 0.01"/>
    <exclude body1="b1" body2="b2"/>
  </contact>


  <actuator>
    <motor name="act1" gear="10" joint="j1"/>
  </actuator>

 
</mujoco>

Code required for reproduction

import os
import numpy as np
import mediapy as media
import mujoco

if __name__ == "__main__":
    import os

    mj_model = mujoco.MjModel.from_xml_string(xml)
    mj_data = mujoco.MjData(mj_model)
    
    renderer = mujoco.Renderer(mj_model)
    scene_option = mujoco.MjvOption()
    scene_option.flags[mujoco.mjtVisFlag.mjVIS_JOINT] = True

    duration = 3  # (seconds)
    framerate = 24  # (Hz)
    
    frames = []
    mujoco.mj_resetData(mj_model, mj_data)
    n_step = 0

    i = 0
    xfrc = np.zeros_like(mj_data.xfrc_applied)
    while mj_data.time < duration:
        ctrl = np.array([(-1) ** (i // 1000)])
        i += 1
        mj_data.ctrl = ctrl
        
        mujoco.mj_step(mj_model, mj_data)

        if len(frames) < mj_data.time * framerate:
            renderer.update_scene(mj_data, scene_option=scene_option)
            pixels = renderer.render()
            frames.append(pixels)
    media.show_video(frames, fps=framerate)

Confirmations

Hang-Hu1 avatar May 19 '25 04:05 Hang-Hu1

I ran your code (adjusted to make a 10x slow motion video).

https://github.com/user-attachments/assets/52423393-49a3-440a-9b2f-79ee4b192dad

The slip described in the documentation is about situations where objects are under a force that is within the friction cone so shouldn't be moving, but they do move a little bit, so different from what you have here.

Can you explain what you don't like about this video? Are you talking about the slow movement left?

nimrod-gileadi avatar May 23 '25 12:05 nimrod-gileadi

Yes, I'm talking about the slow movement left exactly. I wonder why it happens and how I can avoid this weird phenomenon.

Hang-Hu1 avatar May 24 '25 03:05 Hang-Hu1

This looks like it could be caused by the non-isotropic nature of pyramidal friction. Can you try elliptic?

yuvaltassa avatar May 26 '25 12:05 yuvaltassa

I tried this solution. Unluckily this phenomenon still exists (the following video 1). Also I tried closing frictional force during the simulation, and found that the abnormal slip still exists but performs a little different (shown in the following video 2).

https://github.com/user-attachments/assets/881a3fde-fc93-41f1-8671-20ffab0b61bb

https://github.com/user-attachments/assets/004729d9-8b2f-44d1-a592-3633c87f2152

Hang-Hu1 avatar May 28 '25 02:05 Hang-Hu1

Can you please check if one of the above examples is different with smaller timestep? I realize you're already using 1e-4, but it would be informative if you tried 1e-6 and got the same/different results

yuvaltassa avatar May 28 '25 11:05 yuvaltassa

After choosing 1e-7 as dt with the object oscillating with the same frequency, it looks like this phenomenon still exists, but is slightly less pronounced. But if I set the friction coefficients as 0, then it becomes correct.

https://github.com/user-attachments/assets/cd485dc7-6e02-4c09-8f81-10d761c9562a

https://github.com/user-attachments/assets/bc20a0f7-5e37-4b97-8871-a4ae110b71ff

Hang-Hu1 avatar May 30 '25 05:05 Hang-Hu1

Also, by using dt = 1e-6 I obtained similar results with these two videos.

Hang-Hu1 avatar May 30 '25 05:05 Hang-Hu1