Skip to content

Commit 42a7c56

Browse files
authored
Fix put_data crash when nefc=0 for dense models (#1174)
Tendons with frictionloss cause MuJoCo to pre-allocate efc_J with size nv even when nefc=0, causing reshape((0, nv)) to fail with ValueError. Short-circuit to np.zeros((0, nv)) before the sparse/dense branch.
1 parent c276cef commit 42a7c56

File tree

2 files changed

+41
-1
lines changed

2 files changed

+41
-1
lines changed

mujoco_warp/_src/io.py

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -889,7 +889,9 @@ def put_data(
889889

890890
efc = types.Constraint(**efc_kwargs)
891891

892-
if mujoco.mj_isSparse(mjm):
892+
if mjd.nefc == 0:
893+
efc_j = np.zeros((0, mjm.nv))
894+
elif mujoco.mj_isSparse(mjm):
893895
efc_j = np.zeros((mjd.nefc, mjm.nv))
894896
mujoco.mju_sparse2dense(efc_j, mjd.efc_J, mjd.efc_J_rownnz, mjd.efc_J_rowadr, mjd.efc_J_colind)
895897
else:

mujoco_warp/_src/io_test.py

Lines changed: 38 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -1350,6 +1350,44 @@ def test_render_context_with_textures(self):
13501350
self.assertTrue(rc.use_textures, "use_textures")
13511351
self.assertEqual(rc.textures.shape, (mjm.ntex,), "textures")
13521352

1353+
def test_put_data_nefc_zero_dense(self):
1354+
"""put_data succeeds for dense models with nefc=0 and non-empty efc_J."""
1355+
# A tendon with frictionloss causes MuJoCo to pre-allocate efc_J with
1356+
# size nv even when nefc=0, causing reshape((0, nv)) to fail.
1357+
mjm = mujoco.MjModel.from_xml_string("""
1358+
<mujoco>
1359+
<worldbody>
1360+
<body pos="0 0 1">
1361+
<freejoint/>
1362+
<geom type="box" size="0.1 0.1 0.1" mass="1.0"/>
1363+
<site name="s1" pos="0 0 0.1"/>
1364+
<body pos="0.3 0 0">
1365+
<joint type="hinge" axis="0 0 1"/>
1366+
<geom type="sphere" size="0.05" mass="0.2"/>
1367+
<site name="s2" pos="0 0 -0.05"/>
1368+
</body>
1369+
</body>
1370+
</worldbody>
1371+
<tendon>
1372+
<spatial limited="true" range="0 0.5"
1373+
damping="2.0" stiffness="10.0" frictionloss="0.5">
1374+
<site site="s1"/>
1375+
<site site="s2"/>
1376+
</spatial>
1377+
</tendon>
1378+
</mujoco>
1379+
""")
1380+
mjd = mujoco.MjData(mjm)
1381+
mujoco.mj_forward(mjm, mjd)
1382+
1383+
self.assertFalse(mujoco.mj_isSparse(mjm))
1384+
self.assertEqual(mjd.nefc, 0)
1385+
1386+
m = mjwarp.put_model(mjm)
1387+
d = mjwarp.put_data(mjm, mjd)
1388+
1389+
self.assertEqual(d.efc.J.shape[2], m.nv_pad)
1390+
13531391

13541392
if __name__ == "__main__":
13551393
wp.init()

0 commit comments

Comments
 (0)