Skip to content

set sliding friction is 0 cause Nan #942

@PhiDCH

Description

@PhiDCH
import mujoco
import mujoco_warp as mjw
import warp as wp
wp.config.quiet = True
import numpy as np
np.set_printoptions(precision=4, suppress=True)


scene = """
<mujoco model="MuJoCo Model">
  <option gravity="1.0 0 -1.0" timestep="0.01" integrator="RK4" iterations="100" tolerance="0" >
  </option>
  <worldbody>
    <geom name="ground" type="plane" size="2 1 1" pos="0 0 0" quat="1 0 0 0" condim="3" friction="0 0 0"/>
    <body name="box_1" pos="0.0 0.0 0.005">
      <freejoint />
      <inertial pos="0 0 0" mass="1" diaginertia="0.0008416666666666668 0.0008416666666666668 0.001666666666666667"/>
      <geom name="box_1_geom_0" size="0.05 0.05 0.005" type="box" condim="3" friction="0 0 0"/>
    </body>
  </worldbody>
</mujoco>
"""

nsteps = 10      # simulate in 10 steps


# sim in mujoco
mj_model = mujoco.MjModel.from_xml_string(scene)
mj_data = mujoco.MjData(mj_model)
for _ in range(nsteps):
    mujoco.mj_step(mj_model, mj_data)

mj_qpos = mj_data.qpos.copy()



# sim in mujoco warp
mj_model = mujoco.MjModel.from_xml_string(scene)
mj_data = mujoco.MjData(mj_model)

mjw_model = mjw.put_model(mj_model)
mjw_data = mjw.put_data(mj_model, mj_data, njmax=100, nworld=1)
with wp.ScopedCapture() as capture:
    mjw.step(mjw_model, mjw_data)

for _ in range(nsteps):
    wp.capture_launch(capture.graph)

mjw_qpos = mjw_data.qpos.numpy().copy()


print("in mujoco, qpos is:\n", mj_qpos)
print("in mujoco warp, qpos is:\n", mjw_qpos)

output is nan value

in mujoco, qpos is:
 [0.005 0.    0.005 1.    0.    0.    0.   ]
in mujoco warp, qpos is:
 [[nan nan nan  0.  0.  0.  1.]]

Metadata

Metadata

Assignees

Labels

bugSomething isn't working

Type

Projects

No projects

Milestone

No milestone

Relationships

None yet

Development

No branches or pull requests

Issue actions